From 4711ca8980eddd33299b6b0cc24650e4481942d0 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 28 Oct 2018 17:34:41 -0400 Subject: [PATCH 001/199] Added a number of docker images --- docker/ubuntu-gtsam-python-vnc/Dockerfile | 18 ++++ docker/ubuntu-gtsam-python-vnc/bootstrap.sh | 111 ++++++++++++++++++++ docker/ubuntu-gtsam-python-vnc/build.sh | 4 + docker/ubuntu-gtsam-python-vnc/vnc.sh | 5 + docker/ubuntu-gtsam-python/Dockerfile | 29 +++++ docker/ubuntu-gtsam-python/build.sh | 3 + docker/ubuntu-gtsam/Dockerfile | 35 ++++++ docker/ubuntu-gtsam/build.sh | 3 + 8 files changed, 208 insertions(+) create mode 100644 docker/ubuntu-gtsam-python-vnc/Dockerfile create mode 100755 docker/ubuntu-gtsam-python-vnc/bootstrap.sh create mode 100755 docker/ubuntu-gtsam-python-vnc/build.sh create mode 100755 docker/ubuntu-gtsam-python-vnc/vnc.sh create mode 100644 docker/ubuntu-gtsam-python/Dockerfile create mode 100755 docker/ubuntu-gtsam-python/build.sh create mode 100644 docker/ubuntu-gtsam/Dockerfile create mode 100755 docker/ubuntu-gtsam/build.sh diff --git a/docker/ubuntu-gtsam-python-vnc/Dockerfile b/docker/ubuntu-gtsam-python-vnc/Dockerfile new file mode 100644 index 000000000..83222881a --- /dev/null +++ b/docker/ubuntu-gtsam-python-vnc/Dockerfile @@ -0,0 +1,18 @@ +# Get the base Ubuntu/GTSAM image from Docker Hub +FROM dellaert/ubuntu-gtsam-python:bionic + +# Things needed to get a python GUI +ENV DEBIAN_FRONTEND noninteractive +RUN apt-get install -y python-tk +RUN pip install matplotlib + +# Install a VNC X-server, Frame buffer, and windows manager +RUN apt-get install -y x11vnc xvfb fluxbox + +# Finally, install wmctrl needed for bootstrap script +RUN apt-get install -y wmctrl + +# Copy bootstrap script and make sure it runs +COPY bootstrap.sh / + +CMD '/bootstrap.sh' diff --git a/docker/ubuntu-gtsam-python-vnc/bootstrap.sh b/docker/ubuntu-gtsam-python-vnc/bootstrap.sh new file mode 100755 index 000000000..21356138f --- /dev/null +++ b/docker/ubuntu-gtsam-python-vnc/bootstrap.sh @@ -0,0 +1,111 @@ +#!/bin/bash + +# Based on: http://www.richud.com/wiki/Ubuntu_Fluxbox_GUI_with_x11vnc_and_Xvfb + +main() { + log_i "Starting xvfb virtual display..." + launch_xvfb + log_i "Starting window manager..." + launch_window_manager + log_i "Starting VNC server..." + run_vnc_server +} + +launch_xvfb() { + local xvfbLockFilePath="/tmp/.X1-lock" + if [ -f "${xvfbLockFilePath}" ] + then + log_i "Removing xvfb lock file '${xvfbLockFilePath}'..." + if ! rm -v "${xvfbLockFilePath}" + then + log_e "Failed to remove xvfb lock file" + exit 1 + fi + fi + + # Set defaults if the user did not specify envs. + export DISPLAY=${XVFB_DISPLAY:-:1} + local screen=${XVFB_SCREEN:-0} + local resolution=${XVFB_RESOLUTION:-1280x960x24} + local timeout=${XVFB_TIMEOUT:-5} + + # Start and wait for either Xvfb to be fully up or we hit the timeout. + Xvfb ${DISPLAY} -screen ${screen} ${resolution} & + local loopCount=0 + until xdpyinfo -display ${DISPLAY} > /dev/null 2>&1 + do + loopCount=$((loopCount+1)) + sleep 1 + if [ ${loopCount} -gt ${timeout} ] + then + log_e "xvfb failed to start" + exit 1 + fi + done +} + +launch_window_manager() { + local timeout=${XVFB_TIMEOUT:-5} + + # Start and wait for either fluxbox to be fully up or we hit the timeout. + fluxbox & + local loopCount=0 + until wmctrl -m > /dev/null 2>&1 + do + loopCount=$((loopCount+1)) + sleep 1 + if [ ${loopCount} -gt ${timeout} ] + then + log_e "fluxbox failed to start" + exit 1 + fi + done +} + +run_vnc_server() { + local passwordArgument='-nopw' + + if [ -n "${VNC_SERVER_PASSWORD}" ] + then + local passwordFilePath="${HOME}/.x11vnc.pass" + if ! x11vnc -storepasswd "${VNC_SERVER_PASSWORD}" "${passwordFilePath}" + then + log_e "Failed to store x11vnc password" + exit 1 + fi + passwordArgument=-"-rfbauth ${passwordFilePath}" + log_i "The VNC server will ask for a password" + else + log_w "The VNC server will NOT ask for a password" + fi + + x11vnc -ncache 10 -ncache_cr -display ${DISPLAY} -forever ${passwordArgument} & + wait $! +} + +log_i() { + log "[INFO] ${@}" +} + +log_w() { + log "[WARN] ${@}" +} + +log_e() { + log "[ERROR] ${@}" +} + +log() { + echo "[$(date '+%Y-%m-%d %H:%M:%S')] ${@}" +} + +control_c() { + echo "" + exit +} + +trap control_c SIGINT SIGTERM SIGHUP + +main + +exit diff --git a/docker/ubuntu-gtsam-python-vnc/build.sh b/docker/ubuntu-gtsam-python-vnc/build.sh new file mode 100755 index 000000000..8d280252f --- /dev/null +++ b/docker/ubuntu-gtsam-python-vnc/build.sh @@ -0,0 +1,4 @@ +# Build command for Docker image +# TODO(dellaert): use docker compose and/or cmake +# Needs to be run in docker/ubuntu-gtsam-python-vnc directory +docker build -t dellaert/ubuntu-gtsam-python-vnc:bionic . diff --git a/docker/ubuntu-gtsam-python-vnc/vnc.sh b/docker/ubuntu-gtsam-python-vnc/vnc.sh new file mode 100755 index 000000000..c0ab692c6 --- /dev/null +++ b/docker/ubuntu-gtsam-python-vnc/vnc.sh @@ -0,0 +1,5 @@ +# After running this script, connect VNC client to 0.0.0.0:5900 +docker run -it \ + --workdir="/usr/src/gtsam" \ + -p 5900:5900 \ + dellaert/ubuntu-gtsam-python-vnc:bionic \ No newline at end of file diff --git a/docker/ubuntu-gtsam-python/Dockerfile b/docker/ubuntu-gtsam-python/Dockerfile new file mode 100644 index 000000000..0c7d131be --- /dev/null +++ b/docker/ubuntu-gtsam-python/Dockerfile @@ -0,0 +1,29 @@ +# Get the base Ubuntu/GTSAM image from Docker Hub +FROM dellaert/ubuntu-gtsam:bionic + +# Install pip +RUN apt-get install -y python-pip python-dev + +# Install python wrapper requirements +RUN pip install -r /usr/src/gtsam/cython/requirements.txt + +# Run cmake again, now with cython toolbox on +WORKDIR /usr/src/gtsam/build +RUN cmake \ + -DCMAKE_BUILD_TYPE=Release \ + -DGTSAM_USE_SYSTEM_EIGEN=ON \ + -DGTSAM_WITH_EIGEN_MKL=OFF \ + -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ + -DGTSAM_BUILD_TIMING_ALWAYS=OFF \ + -DGTSAM_BUILD_TESTS=OFF \ + -DGTSAM_INSTALL_CYTHON_TOOLBOX=ON \ + .. + +# Build again, as ubuntu-gtsam image cleaned +RUN make -j3 install && make clean + +# Needed to run python wrapper: +RUN echo 'export PYTHONPATH=/usr/local/cython/' >> /root/.bashrc + +# Run bash +CMD ["bash"] diff --git a/docker/ubuntu-gtsam-python/build.sh b/docker/ubuntu-gtsam-python/build.sh new file mode 100755 index 000000000..1696f6c61 --- /dev/null +++ b/docker/ubuntu-gtsam-python/build.sh @@ -0,0 +1,3 @@ +# Build command for Docker image +# TODO(dellaert): use docker compose and/or cmake +docker build --no-cache -t dellaert/ubuntu-gtsam-python:bionic . diff --git a/docker/ubuntu-gtsam/Dockerfile b/docker/ubuntu-gtsam/Dockerfile new file mode 100644 index 000000000..bdfa8d9a5 --- /dev/null +++ b/docker/ubuntu-gtsam/Dockerfile @@ -0,0 +1,35 @@ +# Get the base Ubuntu image from Docker Hub +FROM dellaert/ubuntu-boost-tbb-eigen3:bionic + +# Install git +RUN apt-get update && \ + apt-get install -y git + +# Install compiler +RUN apt-get install -y build-essential + +# Clone GTSAM +WORKDIR /usr/src/ +RUN git clone https://bitbucket.org/gtborg/gtsam.git + +# Run cmake +RUN mkdir /usr/src/gtsam/build +WORKDIR /usr/src/gtsam/build +RUN cmake \ + -DCMAKE_BUILD_TYPE=Release \ + -DGTSAM_USE_SYSTEM_EIGEN=ON \ + -DGTSAM_WITH_EIGEN_MKL=OFF \ + -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ + -DGTSAM_BUILD_TIMING_ALWAYS=OFF \ + -DGTSAM_BUILD_TESTS=OFF \ + -DGTSAM_INSTALL_CYTHON_TOOLBOX=OFF \ + .. + +# Build +RUN make -j3 install && make clean + +# Needed to link with GTSAM +RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib' >> /root/.bashrc + +# Run bash +CMD ["bash"] diff --git a/docker/ubuntu-gtsam/build.sh b/docker/ubuntu-gtsam/build.sh new file mode 100755 index 000000000..bf545e9c2 --- /dev/null +++ b/docker/ubuntu-gtsam/build.sh @@ -0,0 +1,3 @@ +# Build command for Docker image +# TODO(dellaert): use docker compose and/or cmake +docker build --no-cache -t dellaert/ubuntu-gtsam:bionic . From 906d0277e93b43f5160c7a18df6e83a5990d1ce9 Mon Sep 17 00:00:00 2001 From: Thomas Jespersen Date: Mon, 16 Mar 2020 00:48:36 +0800 Subject: [PATCH 002/199] Added ported C++ version of ISAM2 Kitti example --- examples/IMUKittiExampleGPS.cpp | 293 ++++++++++++++++++++++++++++++++ 1 file changed, 293 insertions(+) create mode 100644 examples/IMUKittiExampleGPS.cpp diff --git a/examples/IMUKittiExampleGPS.cpp b/examples/IMUKittiExampleGPS.cpp new file mode 100644 index 000000000..9f302ab2f --- /dev/null +++ b/examples/IMUKittiExampleGPS.cpp @@ -0,0 +1,293 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file IMUKittiExampleGPS + * @brief Example of application of ISAM2 for GPS-aided navigation on the KITTI VISION BENCHMARK SUITE + * @author Ported by Thomas Jespersen (thomasj@tkjelectronics.dk), TKJ Electronics + */ + +// GTSAM related includes. +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace gtsam; +using namespace std; + +using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) +using symbol_shorthand::V; // Vel (xdot,ydot,zdot) +using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) + +typedef struct { + double Time; + double dt; + Vector3 Accelerometer; + Vector3 Gyroscope; // omega +} imuMeasurement_t; + +typedef struct { + double Time; + Vector3 Position; // x,y,z +} gpsMeasurement_t; + +const string output_filename = "IMUKittyExampleGPSResults.csv"; + +int main(int argc, char* argv[]) +{ + string line; + + // Read IMU metadata and compute relative sensor pose transforms + // BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma GyroscopeSigma IntegrationSigma AccelerometerBiasSigma GyroscopeBiasSigma AverageDeltaT + // 0 0 0 0 0 0 0.01 0.000175 0 0.000167 2.91e-006 0.0100395199348279 + string IMU_metadata_file = findExampleDataFile("KittiEquivBiasedImu_metadata.txt"); + ifstream IMU_metadata(IMU_metadata_file.c_str()); + + printf("-- Reading sensor metadata\n"); + + getline(IMU_metadata, line, '\n'); // ignore the first line + + double BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz, AccelerometerSigma, GyroscopeSigma, IntegrationSigma, AccelerometerBiasSigma, GyroscopeBiasSigma, AverageDeltaT; + getline(IMU_metadata, line, '\n'); + sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf", &BodyPtx, &BodyPty, &BodyPtz, &BodyPrx, &BodyPry, &BodyPrz, &AccelerometerSigma, &GyroscopeSigma, &IntegrationSigma, &AccelerometerBiasSigma, &GyroscopeBiasSigma, &AverageDeltaT); + printf("IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz, AccelerometerSigma, GyroscopeSigma, IntegrationSigma, AccelerometerBiasSigma, GyroscopeBiasSigma, AverageDeltaT); + + Vector6 BodyP = (Vector(6) << BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz).finished(); + auto body_T_imu = Pose3::Expmap(BodyP); + if (!body_T_imu.equals(Pose3(), 1e-5)) { + printf("Currently only support IMUinBody is identity, i.e. IMU and body frame are the same"); + exit(-1); + } + + // Read IMU data + // Time dt accelX accelY accelZ omegaX omegaY omegaZ + // 46534.47837579 46534.47837579 1.7114864219577 0.1717911743144 9.80533438749 -0.0032006241515747 0.031231284764596 -0.0063569265706488 + vector IMU_measurements; + string IMU_data_file = findExampleDataFile("KittiEquivBiasedImu.txt"); + + printf("-- Reading IMU measurements from file\n"); + { + ifstream IMU_data(IMU_data_file.c_str()); + getline(IMU_data, line, '\n'); // ignore the first line + + double time = 0, dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0; + while (!IMU_data.eof()) { + getline(IMU_data, line, '\n'); + sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf", &time, &dt, &acc_x, &acc_y, &acc_z, &gyro_x, + &gyro_y, &gyro_z); + + imuMeasurement_t measurement; + measurement.Time = time; + measurement.dt = dt; + measurement.Accelerometer = Vector3(acc_x, acc_y, acc_z); + measurement.Gyroscope = Vector3(gyro_x, gyro_y, gyro_z); + IMU_measurements.push_back(measurement); + } + } + + // Read GPS data + // Time,X,Y,Z + // 46534.478375790000428,-6.8269361350059405424,-11.868164241239471224,0.040306091310000624617 + vector GPS_measurements; + string GPS_data_file = findExampleDataFile("KittiGps_converted.txt"); + + printf("-- Reading GPS measurements from file\n"); + { + ifstream GPS_data(GPS_data_file.c_str()); + getline(GPS_data, line, '\n'); // ignore the first line + + double time = 0, gps_x = 0, gps_y = 0, gps_z = 0; + while (!GPS_data.eof()) { + getline(GPS_data, line, '\n'); + sscanf(line.c_str(), "%lf,%lf,%lf,%lf", &time, &gps_x, &gps_y, &gps_z); + + gpsMeasurement_t measurement; + measurement.Time = time; + measurement.Position = Vector3(gps_x, gps_y, gps_z); + GPS_measurements.push_back(measurement); + } + } + + // Configure different variables + double tOffset = GPS_measurements[0].Time; + size_t firstGPSPose = 1; + size_t GPSskip = 10; // Skip this many GPS measurements each time + double g = 9.8; + auto w_coriolis = Vector3(); // zero vector + + // Configure noise models + noiseModel::Diagonal::shared_ptr noiseModelGPS = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), Vector3::Constant(1.0/0.07)).finished()); + + // Set initial conditions for the estimated trajectory + auto currentPoseGlobal = Pose3(Rot3(), GPS_measurements[firstGPSPose].Position); // initial pose is the reference frame (navigation frame) + auto currentVelocityGlobal = Vector3(); // the vehicle is stationary at the beginning at position 0,0,0 + auto currentBias = imuBias::ConstantBias(); // init with zero bias + + noiseModel::Diagonal::shared_ptr sigma_init_x = noiseModel::Isotropic::Precisions((Vector(6) << Vector3::Constant(0), Vector3::Constant(1.0)).finished()); + noiseModel::Diagonal::shared_ptr sigma_init_v = noiseModel::Isotropic::Sigma(3, 1000.0); + noiseModel::Diagonal::shared_ptr sigma_init_b = noiseModel::Isotropic::Sigmas((Vector(6) << Vector3::Constant(0.100), Vector3::Constant(5.00e-05)).finished()); + + // Set IMU preintegration parameters + Matrix33 measured_acc_cov = Matrix33::Identity(3,3) * pow(AccelerometerSigma,2); + Matrix33 measured_omega_cov = Matrix33::Identity(3,3) * pow(GyroscopeSigma,2); + Matrix33 integration_error_cov = Matrix33::Identity(3,3) * pow(IntegrationSigma,2); // error committed in integrating position from velocities + + boost::shared_ptr IMU_params = PreintegratedImuMeasurements::Params::MakeSharedU(g); + IMU_params->accelerometerCovariance = measured_acc_cov; // acc white noise in continuous + IMU_params->integrationCovariance = integration_error_cov; // integration uncertainty continuous + IMU_params->gyroscopeCovariance = measured_omega_cov; // gyro white noise in continuous + IMU_params->omegaCoriolis = w_coriolis; + + std::shared_ptr currentSummarizedMeasurement = nullptr; + + // Set ISAM2 parameters and create ISAM2 solver object + ISAM2Params isamParams; + isamParams.factorization = ISAM2Params::CHOLESKY; + isamParams.relinearizeSkip = 10; + + ISAM2 isam(isamParams); + + // Create the factor graph and values object that will store new factors and values to add to the incremental graph + NonlinearFactorGraph newFactors; + Values newValues; // values storing the initial estimates of new nodes in the factor graph + + /// Main loop: + /// (1) we read the measurements + /// (2) we create the corresponding factors in the graph + /// (3) we solve the graph to obtain and optimal estimate of robot trajectory + printf("-- Starting main loop: inference is performed at each time step, but we plot trajectory every 10 steps\n"); + size_t imuMeasurementIndex = 0; + for (size_t gpsMeasurementIndex = firstGPSPose; gpsMeasurementIndex < GPS_measurements.size() - 1; gpsMeasurementIndex++) { + // At each non=IMU measurement we initialize a new node in the graph + auto currentPoseKey = X(gpsMeasurementIndex); + auto currentVelKey = V(gpsMeasurementIndex); + auto currentBiasKey = B(gpsMeasurementIndex); + double t = GPS_measurements[gpsMeasurementIndex].Time; + + if (gpsMeasurementIndex == firstGPSPose) { + // Create initial estimate and prior on initial pose, velocity, and biases + newValues.insert(currentPoseKey, currentPoseGlobal); + newValues.insert(currentVelKey, currentVelocityGlobal); + newValues.insert(currentBiasKey, currentBias); + newFactors.add(PriorFactor(currentPoseKey, currentPoseGlobal, sigma_init_x)); + newFactors.add(PriorFactor(currentVelKey, currentVelocityGlobal, sigma_init_v)); + newFactors.add(PriorFactor(currentBiasKey, currentBias, sigma_init_b)); + } else { + double t_previous = GPS_measurements[gpsMeasurementIndex-1].Time; + + // Summarize IMU data between the previous GPS measurement and now + currentSummarizedMeasurement = std::make_shared(IMU_params, currentBias); + static size_t includedIMUmeasurementCount = 0; + while (imuMeasurementIndex < IMU_measurements.size() && IMU_measurements[imuMeasurementIndex].Time <= t) { + if (IMU_measurements[imuMeasurementIndex].Time >= t_previous) { + currentSummarizedMeasurement->integrateMeasurement(IMU_measurements[imuMeasurementIndex].Accelerometer, IMU_measurements[imuMeasurementIndex].Gyroscope, IMU_measurements[imuMeasurementIndex].dt); + includedIMUmeasurementCount++; + } + imuMeasurementIndex++; + } + + // Create IMU factor + auto previousPoseKey = X(gpsMeasurementIndex-1); + auto previousVelKey = V(gpsMeasurementIndex-1); + auto previousBiasKey = B(gpsMeasurementIndex-1); + + newFactors.add(ImuFactor( + previousPoseKey, previousVelKey, + currentPoseKey, currentVelKey, + previousBiasKey, *currentSummarizedMeasurement)); + + // Bias evolution as given in the IMU metadata + noiseModel::Diagonal::shared_ptr sigma_between_b = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(sqrt(includedIMUmeasurementCount) * AccelerometerBiasSigma), Vector3::Constant(sqrt(includedIMUmeasurementCount) * GyroscopeBiasSigma)).finished()); + newFactors.add(BetweenFactor(previousBiasKey, currentBiasKey, imuBias::ConstantBias(), sigma_between_b)); + + // Create GPS factor + auto GPSPose = Pose3(currentPoseGlobal.rotation(), GPS_measurements[gpsMeasurementIndex].Position); + if ((gpsMeasurementIndex % GPSskip) == 0) { + newFactors.add(PriorFactor(currentPoseKey, GPSPose, noiseModelGPS)); + newValues.insert(currentPoseKey, GPSPose); + + printf("################ POSE INCLUDED AT TIME %lf ################\n", t); + GPSPose.translation().print(); + printf("\n\n"); + } else { + newValues.insert(currentPoseKey, currentPoseGlobal); + } + + // Add initial values for velocity and bias based on the previous estimates + newValues.insert(currentVelKey, currentVelocityGlobal); + newValues.insert(currentBiasKey, currentBias); + + // Update solver + // ======================================================================= + // We accumulate 2*GPSskip GPS measurements before updating the solver at + //first so that the heading becomes observable. + if (gpsMeasurementIndex > (firstGPSPose + 2*GPSskip)) { + printf("################ NEW FACTORS AT TIME %lf ################\n", t); + newFactors.print(); + + isam.update(newFactors, newValues); + + // Reset the newFactors and newValues list + newFactors.resize(0); + newValues.clear(); + + // Extract the result/current estimates + Values result = isam.calculateEstimate(); + + currentPoseGlobal = result.at(currentPoseKey); + currentVelocityGlobal = result.at(currentVelKey); + currentBias = result.at(currentBiasKey); + + printf("\n################ POSE AT TIME %lf ################\n", t); + currentPoseGlobal.print(); + printf("\n\n"); + } + } + } + + // Save results to file + printf("\nWriting results to file...\n"); + FILE* fp_out = fopen(output_filename.c_str(), "w+"); + fprintf(fp_out, "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n"); + + Values result = isam.calculateEstimate(); + for (size_t gpsMeasurementIndex = firstGPSPose; gpsMeasurementIndex < GPS_measurements.size() - 1; gpsMeasurementIndex++) { + auto poseKey = X(gpsMeasurementIndex); + auto velKey = V(gpsMeasurementIndex); + auto biasKey = B(gpsMeasurementIndex); + + auto pose = result.at(poseKey); + auto velocity = result.at(velKey); + auto bias = result.at(biasKey); + + auto pose_quat = pose.rotation().toQuaternion(); + auto gps = GPS_measurements[gpsMeasurementIndex].Position; + + fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", + GPS_measurements[gpsMeasurementIndex].Time, + pose.x(), pose.y(), pose.z(), + pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(), + gps(0), gps(1), gps(2)); + } + + fclose(fp_out); +} \ No newline at end of file From 221dcaa13ac427082e55b7b3b67c78b9eec396a1 Mon Sep 17 00:00:00 2001 From: kvmanohar22 Date: Mon, 30 Mar 2020 22:16:30 +0530 Subject: [PATCH 003/199] adding functionality to use ISAM2 for imu preintegration example --- examples/ImuFactorsExample.cpp | 29 ++++++++++++++++++++++++++++- 1 file changed, 28 insertions(+), 1 deletion(-) diff --git a/examples/ImuFactorsExample.cpp b/examples/ImuFactorsExample.cpp index e038f5117..bdeb99d0c 100644 --- a/examples/ImuFactorsExample.cpp +++ b/examples/ImuFactorsExample.cpp @@ -33,6 +33,8 @@ * optional arguments: * data_csv_path path to the CSV file with the IMU data. * -c use CombinedImuFactor + * Note: Define USE_LM to use Levenberg Marquardt Optimizer + * By default ISAM2 is used */ // GTSAM related includes. @@ -44,11 +46,15 @@ #include #include #include +#include #include #include #include #include +// Uncomment the following to use Levenberg Marquardt Optimizer +// #define USE_LM + using namespace gtsam; using namespace std; @@ -67,6 +73,17 @@ int main(int argc, char* argv[]) { string data_filename; bool use_combined_imu = false; + +#ifndef USE_LM + printf("Using ISAM2\n"); + ISAM2Params parameters; + parameters.relinearizeThreshold = 0.01; + parameters.relinearizeSkip = 1; + ISAM2 isam2(parameters); +#else + printf("Using Levenberg Marquardt Optimizer\n"); +#endif + if (argc < 2) { printf("using default CSV file\n"); data_filename = findExampleDataFile("imuAndGPSdata.csv"); @@ -248,9 +265,19 @@ int main(int argc, char* argv[]) initial_values.insert(V(correction_count), prop_state.v()); initial_values.insert(B(correction_count), prev_bias); + Values result; +#ifdef USE_LM LevenbergMarquardtOptimizer optimizer(*graph, initial_values); - Values result = optimizer.optimize(); + result = optimizer.optimize(); +#else + isam2.update(*graph, initial_values); + isam2.update(); + result = isam2.calculateEstimate(); + // reset the graph + graph->resize(0); + initial_values.clear(); +#endif // Overwrite the beginning of the preintegration for the next step. prev_state = NavState(result.at(X(correction_count)), result.at(V(correction_count))); From 201539680f6e2e1db00b6d2b49ceb1a8c9b8db4f Mon Sep 17 00:00:00 2001 From: yetongumich Date: Wed, 1 Apr 2020 20:07:49 -0400 Subject: [PATCH 004/199] remove distance in noisemodel, replace with error --- gtsam/linear/JacobianFactor.cpp | 2 +- gtsam/linear/NoiseModel.cpp | 4 ++-- gtsam/linear/NoiseModel.h | 19 ++++++++++++------- gtsam/linear/tests/testNoiseModel.cpp | 10 +++++----- gtsam/nonlinear/NonlinearFactor.cpp | 2 +- 5 files changed, 21 insertions(+), 16 deletions(-) diff --git a/gtsam/linear/JacobianFactor.cpp b/gtsam/linear/JacobianFactor.cpp index 2310d88f0..2e634190c 100644 --- a/gtsam/linear/JacobianFactor.cpp +++ b/gtsam/linear/JacobianFactor.cpp @@ -515,7 +515,7 @@ Vector JacobianFactor::error_vector(const VectorValues& c) const { double JacobianFactor::error(const VectorValues& c) const { Vector e = unweighted_error(c); // Use the noise model distance function to get the correct error if available. - if (model_) return 0.5 * model_->distance(e); + if (model_) return model_->error(e); return 0.5 * e.dot(e); } diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 33f51e1f0..d1a03eb5b 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -369,12 +369,12 @@ Vector Constrained::whiten(const Vector& v) const { } /* ************************************************************************* */ -double Constrained::distance(const Vector& v) const { +double Constrained::error(const Vector& v) const { Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements for (size_t i=0; i& A, Vector& b) const = 0; virtual void WhitenSystem(Matrix& A, Vector& b) const = 0; @@ -224,8 +229,8 @@ namespace gtsam { } #endif - inline virtual double distance(const Vector& v) const { - return SquaredMahalanobisDistance(v); + inline virtual double error(const Vector& v) const { + return 0.5 * SquaredMahalanobisDistance(v); } /** @@ -477,7 +482,7 @@ namespace gtsam { * for non-constrained versions, uses sigmas, otherwise * uses the penalty function with mu */ - virtual double distance(const Vector& v) const; + virtual double error(const Vector& v) const; /** Fully constrained variations */ static shared_ptr All(size_t dim) { @@ -705,11 +710,11 @@ namespace gtsam { { Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; } inline virtual Vector unwhiten(const Vector& /*v*/) const { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } - // Fold the use of the m-estimator loss(...) function into distance(...) - inline virtual double distance(const Vector& v) const + // Fold the use of the m-estimator loss(...) function into error(...) + inline virtual double error(const Vector& v) const { return robust_->loss(this->unweightedWhiten(v).norm()); } - inline virtual double distance_non_whitened(const Vector& v) const - { return robust_->loss(v.norm()); } + // inline virtual double distance_non_whitened(const Vector& v) const + // { return robust_->loss(v.norm()); } // TODO: these are really robust iterated re-weighting support functions virtual void WhitenSystem(Vector& b) const; virtual void WhitenSystem(std::vector& A, Vector& b) const; diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index 0290fc5d8..52e1eefee 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -182,8 +182,8 @@ TEST(NoiseModel, ConstrainedMixed ) EXPECT(assert_equal(Vector3(0.5, 1.0, 0.5),d->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.5, 0.0, 0.5),d->whiten(feasible))); - DOUBLES_EQUAL(1000.0 + 0.25 + 0.25,d->distance(infeasible),1e-9); - DOUBLES_EQUAL(0.5,d->distance(feasible),1e-9); + DOUBLES_EQUAL(0.5 * (1000.0 + 0.25 + 0.25),d->error(infeasible),1e-9); + DOUBLES_EQUAL(0.5 * 0.5,d->error(feasible),1e-9); } /* ************************************************************************* */ @@ -197,8 +197,8 @@ TEST(NoiseModel, ConstrainedAll ) EXPECT(assert_equal(Vector3(1.0, 1.0, 1.0),i->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.0, 0.0, 0.0),i->whiten(feasible))); - DOUBLES_EQUAL(1000.0 * 3.0,i->distance(infeasible),1e-9); - DOUBLES_EQUAL(0.0,i->distance(feasible),1e-9); + DOUBLES_EQUAL(0.5 * 1000.0 * 3.0,i->error(infeasible),1e-9); + DOUBLES_EQUAL(0.0,i->error(feasible),1e-9); } /* ************************************************************************* */ @@ -687,7 +687,7 @@ TEST(NoiseModel, robustNoiseL2WithDeadZone) EQUALITY(cov, gaussian->covariance());\ EXPECT(assert_equal(white, gaussian->whiten(e)));\ EXPECT(assert_equal(e, gaussian->unwhiten(white)));\ - EXPECT_DOUBLES_EQUAL(251, gaussian->distance(e), 1e-9);\ + EXPECT_DOUBLES_EQUAL(0.5 * 251, gaussian->error(e), 1e-9);\ Matrix A = R.inverse(); Vector b = e;\ gaussian->WhitenSystem(A, b);\ EXPECT(assert_equal(I, A));\ diff --git a/gtsam/nonlinear/NonlinearFactor.cpp b/gtsam/nonlinear/NonlinearFactor.cpp index ee14e8073..40fc1c427 100644 --- a/gtsam/nonlinear/NonlinearFactor.cpp +++ b/gtsam/nonlinear/NonlinearFactor.cpp @@ -121,7 +121,7 @@ double NoiseModelFactor::error(const Values& c) const { const Vector b = unwhitenedError(c); check(noiseModel_, b.size()); if (noiseModel_) - return 0.5 * noiseModel_->distance(b); + return noiseModel_->error(b); else return 0.5 * b.squaredNorm(); } else { From 3b183e2da0534ffc26ce66b69aeee03ddfb2730f Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:03:05 -0400 Subject: [PATCH 005/199] add test on robust loss functions to behave like quadratic --- gtsam/linear/tests/testNoiseModel.cpp | 30 +++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index 52e1eefee..c6fcdd77a 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -681,6 +681,36 @@ TEST(NoiseModel, robustNoiseL2WithDeadZone) } +TEST(NoiseModel, lossFunctionAtZero) +{ + const double k = 5.0; + auto fair = mEstimator::Fair::Create(k); + DOUBLES_EQUAL(fair->loss(0), 0, 1e-8); + DOUBLES_EQUAL(fair->weight(0), 1, 1e-8); + auto huber = mEstimator::Huber::Create(k); + DOUBLES_EQUAL(huber->loss(0), 0, 1e-8); + DOUBLES_EQUAL(huber->weight(0), 1, 1e-8); + auto cauchy = mEstimator::Cauchy::Create(k); + DOUBLES_EQUAL(cauchy->loss(0), 0, 1e-8); + DOUBLES_EQUAL(cauchy->weight(0), 1, 1e-8); + auto gmc = mEstimator::GemanMcClure::Create(k); + DOUBLES_EQUAL(gmc->loss(0), 0, 1e-8); + DOUBLES_EQUAL(gmc->weight(0), 1, 1e-8); + auto welsch = mEstimator::Welsch::Create(k); + DOUBLES_EQUAL(welsch->loss(0), 0, 1e-8); + DOUBLES_EQUAL(welsch->weight(0), 1, 1e-8); + auto tukey = mEstimator::Tukey::Create(k); + DOUBLES_EQUAL(tukey->loss(0), 0, 1e-8); + DOUBLES_EQUAL(tukey->weight(0), 1, 1e-8); + auto dcs = mEstimator::DCS::Create(k); + DOUBLES_EQUAL(dcs->loss(0), 0, 1e-8); + DOUBLES_EQUAL(dcs->weight(0), 1, 1e-8); + // auto lsdz = mEstimator::L2WithDeadZone::Create(k); + // DOUBLES_EQUAL(lsdz->loss(0), 0, 1e-8); + // DOUBLES_EQUAL(lsdz->weight(0), 1, 1e-8); +} + + /* ************************************************************************* */ #define TEST_GAUSSIAN(gaussian)\ EQUALITY(info, gaussian->information());\ From 227bff6aeeddb4b85d6c05ce75f18df22c099447 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:04:31 -0400 Subject: [PATCH 006/199] Revert "add implementation for deprecated Mahalanobis" This reverts commit 351c6f8bccca726e3515721cde22626750fc4011. --- gtsam/linear/NoiseModel.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index feacf7b19..4c74d9e46 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -224,9 +224,7 @@ namespace gtsam { } #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double Mahalanobis(const Vector& v) const { - return SquaredMahalanobisDistance(v); - } + virtual double Mahalanobis(const Vector& v) const; #endif inline virtual double error(const Vector& v) const { From 9d60c505e87ca3eb965a16ab2919d96c0e32753c Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:06:31 -0400 Subject: [PATCH 007/199] merge with mahalanobis renaming --- gtsam/linear/NoiseModel.cpp | 4 ++-- gtsam/linear/NoiseModel.h | 10 +++++----- gtsam/linear/tests/testNoiseModel.cpp | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index d1a03eb5b..e0ca3726b 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -157,7 +157,7 @@ Vector Gaussian::unwhiten(const Vector& v) const { } /* ************************************************************************* */ -double Gaussian::SquaredMahalanobisDistance(const Vector& v) const { +double Gaussian::squaredMahalanobisDistance(const Vector& v) const { // Note: for Diagonal, which does ediv_, will be correct for constraints Vector w = whiten(v); return w.dot(w); @@ -573,7 +573,7 @@ void Isotropic::print(const string& name) const { } /* ************************************************************************* */ -double Isotropic::SquaredMahalanobisDistance(const Vector& v) const { +double Isotropic::squaredMahalanobisDistance(const Vector& v) const { return v.dot(v) * invsigma_ * invsigma_; } diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 4c74d9e46..cccca225b 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -214,13 +214,13 @@ namespace gtsam { /** * Squared Mahalanobis distance v'*R'*R*v = */ - virtual double SquaredMahalanobisDistance(const Vector& v) const; + virtual double squaredMahalanobisDistance(const Vector& v) const; /** * Mahalanobis distance */ virtual double MahalanobisDistance(const Vector& v) const { - return std::sqrt(SquaredMahalanobisDistance(v)); + return std::sqrt(squaredMahalanobisDistance(v)); } #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 @@ -228,7 +228,7 @@ namespace gtsam { #endif inline virtual double error(const Vector& v) const { - return 0.5 * SquaredMahalanobisDistance(v); + return 0.5 * squaredMahalanobisDistance(v); } /** @@ -580,7 +580,7 @@ namespace gtsam { } virtual void print(const std::string& name) const; - virtual double SquaredMahalanobisDistance(const Vector& v) const; + virtual double squaredMahalanobisDistance(const Vector& v) const; virtual Vector whiten(const Vector& v) const; virtual Vector unwhiten(const Vector& v) const; virtual Matrix Whiten(const Matrix& H) const; @@ -632,7 +632,7 @@ namespace gtsam { virtual bool isUnit() const { return true; } virtual void print(const std::string& name) const; - virtual double SquaredMahalanobisDistance(const Vector& v) const {return v.dot(v); } + virtual double squaredMahalanobisDistance(const Vector& v) const {return v.dot(v); } virtual Vector whiten(const Vector& v) const { return v; } virtual Vector unwhiten(const Vector& v) const { return v; } virtual Matrix Whiten(const Matrix& H) const { return H; } diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index c6fcdd77a..e879731cb 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -71,7 +71,7 @@ TEST(NoiseModel, constructors) // test squared Mahalanobis distance double distance = 5*5+10*10+15*15; for(Gaussian::shared_ptr mi: m) - DOUBLES_EQUAL(distance,mi->SquaredMahalanobisDistance(unwhitened),1e-9); + DOUBLES_EQUAL(distance,mi->squaredMahalanobisDistance(unwhitened),1e-9); // test R matrix for(Gaussian::shared_ptr mi: m) From d86bab0e7dc8f9a16cda03cf69f0869cbbb37372 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:04:31 -0400 Subject: [PATCH 008/199] re-add implemntation for deprecated Mahalanobis --- gtsam/linear/NoiseModel.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index cccca225b..2badad838 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -224,7 +224,9 @@ namespace gtsam { } #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double Mahalanobis(const Vector& v) const; + virtual double Mahalanobis(const Vector& v) const { + return squaredMahalanobisDistance(v); + } #endif inline virtual double error(const Vector& v) const { From 12b0267ab7d9cdc8a61dd5da5c442fd89752cf25 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Thu, 2 Apr 2020 11:08:58 -0400 Subject: [PATCH 009/199] renamed mahalanobisDistance --- gtsam/linear/NoiseModel.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 2badad838..627c0de2b 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -219,7 +219,7 @@ namespace gtsam { /** * Mahalanobis distance */ - virtual double MahalanobisDistance(const Vector& v) const { + virtual double mahalanobisDistance(const Vector& v) const { return std::sqrt(squaredMahalanobisDistance(v)); } From 9e4be90111da17b50a00306b33e7b6b7f8d57c4a Mon Sep 17 00:00:00 2001 From: yetongumich Date: Fri, 3 Apr 2020 13:53:51 -0400 Subject: [PATCH 010/199] add document for robust noise model --- doc/robust.pdf | Bin 0 -> 197566 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 doc/robust.pdf diff --git a/doc/robust.pdf b/doc/robust.pdf new file mode 100644 index 0000000000000000000000000000000000000000..3404719b492e481bb77b96853eea0fa3a2fc39ba GIT binary patch literal 197566 zcmeFYW3(teyCu48+g^Lwwz-#W+qP}nwr%fa+qP}=e$RKm?sK|(+|lFy=wG+Ss8N+v zl1gSWpX8~UA(ayrrD33DfggW&%2;f08rOvlH<0 zLK)i_{Zl5v|Gfi>f%QK%M9JOGn1D`A!Pw+)GmLFaoy-W>|JGR4+{($=;qTQ--^p0m z*wEJKZ>oP?<@6n_9SQycLCDt1+1kdDfQ5ig&cWEo+|bF^fq;SWZ?g#KRQ~~jfa&k~ z7X=9$BV)IJB3KC682=SvVoSil^tT=g1au0vwoU{LZ2t-<{>7Alo$WtLbom!f9RD*m zbP~b@n%sX8HPB}?X4BVaGBz?YU}0b}U}rEkU|?o5VqxPjVB_WHFlJ?DVPs%uVq-Sp zU@)R*Gv+X0F<@opFf=w`*Jn53)&8dk9Gx7D^{t`YvJ4H3^ma}44D|HaA&Jx{`>hP= z+rfnyQv$?ehzS(DDbip7J)I z`!5m+={xCL*_!?*Rx|wb{NGvrx0F&OVEe~@{EK*h4aa{Ska~K0CVG1I273B>a)u@d zMt(r_nV=-&eGTz<<1E+rz%W%GY<4ux(l=V((=6W0Ii5Aj@Voo`#@sMcC$#|PyadPK znetEt#?~~M27EdD+M_G=m$~j5mGj%-t?;%+rrr6_N`L_72n5dm>mdDWxBf@ng=}q{ zjBT782^i`B)ne(tbk`TO{fE^5#ISI%&@!^I60kEf(Ec?ae<}ahO8m|6-w{$UcC>YN zF#L-d(?8bdFYEt>**`e`C&2!r`2SbH{tXoe1M`2u>Pmgfc7qkccSbkAb&P*1d`HQT z$Ek0<*$ldhr7pGwzF}}^-H0mr@Yk7cFBhJ%X3RXhC7V@W4t2cPy<5k}*3GoKL%h-0 zLgHo4&W$PA4)5Nty%fkAWkxPp;a_P9MDgyMYR`iC0D0! z%GxbCc)H7p<@9IiwZCpmXY>^_?WP^7L2W2WnbM{B6C`NOX2_7q<_%ycf~9j)|GWpN zKqafCY(yOh!a_SFlK(Q6nXnmtR+YktmwFk(+w1xD<-G59-igHuf744dGE*Oe>H5Q= zm}CFz_SXPI=0*XN$U%ad(WxX^<)P%zd6U*vViCr^Y=dmi+i*fn_ABj#kB^1(DXdd6yYCY|VK~ zrHz@Ld@Xv9`UjIoH)SU&r1L~u)xF5;?Cq-0suf$i)w%nT>J^1Wid|uvsHfTMUeQcN zlm>K`DPclUkl7Qd-uE03P zUX>N$9uR8rhL1rPc6~Inz;+i*$AD4=qd5^?=yiO{7`P}z_+$vRJ^gj{?jFsL7*Z*v zPbHO-J58@C#orw;^#I6686o5{dU~Mt4d$OvDgz-<6F|kh&wG#; z&>3YB#{(~7T@!8FZeem6m93I2-Qj)3%@Kg}uP%ztR*cRBT$$|YKtbe{_CR%{)s>L4 zX9djLG!rQ~<1JfmvuchxtcdH$Eau9s^7~$maQurg98t3o>6=%dk`eVY0I@Pw2azy4 zZk&*}he!^g(idp`5TWZ+Kq4vK4I)Yvffo->Tf=Ox0A?_+!vMU33DN~@!bwE0lxGu* zL2AnlQX7VZ6NpA<9|XU-AsSxkT`p-R$HCK_Q?*%`EKEO$<4jlzRHvJ!D2k@!#SMG# zns^@hw+FF(c;VKtBtVM>@IVNBu=z@o4q+T$c}(nd*I@2%7=eooxZk^MPK#+&QKri+hn4`Xy8(=LcdD_LRhdroELFgN+7b`e-*5$a`wn%dHm= z`uZz>;f{Ku3Su*+Gi|)LGcek`M;cgHYUsP2UfFk!?wZKp_yVC`zWJY<2jQq^hqvyk ziJ1DDKt?eP@>hZ}0o=hPd!Eih#uJhDXV3t&!{?Q6C`&wD9crN~~*`52BFh5MWN;jgIXA^`ZaVAJtBADx($iNjIB_PAa5cW*Klwfu{`nMb#7$^`IdhaMaSJy+W6% zJgLx!zxJUBuApXilt9xFmr;1kvF}kU(-kp<<@T{ZZ1t$GWy*T+N%3OMt^vY_zD`}J zIPsD&LNo%UnRr0_3=KSa9f<7CxtjQBTb{C8)=OpM0&tB0CT;i&eeGBqomttO zScARVwUTq+uluvu!HxT-*+hCPZdmmmlky=OZ{`UdHt8M89{lcnX1&8~@C+ZF7VBaC zs9aQI?5$j@4BrWehPCUOUMvL}IsIdFj@_84k%_uim|ZBtC!9;?PUstTIl{af;Vz;VOIuT4)2b zt}37yl?4vcVgJ-uvE9{STzeNfxUDBqk5^RjrSV<(OjB9z&iUjSGXqJ~GpT>DZ`s(hcS%= zw-Z0;8l>EA$f-JJ;C%n=os!j0QU~eBmZ$|fr%VKJB^X&Ext;YX%<}_Wickj>INg5R ze7#J)NTMF1pLNqg#%I_Zo>l|Wc9(&tfiG6(8z^g>buY5B16kM&PIw?s`8b#)wGxLj z;5D;7;CLx<@a-*&mE*dFw^`bd0uRzrRSwXOpY&A85R4|C%WQ2 zkeM~=e2y2>HNk$$6}PUw?qJdem?`DSEabu_PVIuF5GE$NN((>9LsswwzP)Ci!6s~M*qxXwot?iKq72z6^qC3*ZkR% zv_I{SK&6q%4^hk;Ei66BalHQeY2MaUry65>n7T|~+p%K(WzD0bZfW|vEP-h=J2e-c z8Zd5U_6QxouRp*`uMPkXJCk>E3-LV_Gjs|e!Y+_wkn~$5PK=-M8lDw2>;qVK5ED-B z!4BjW8t7GoUPtOkkgZdl4fJqQ258y6H9hmtQz+&323>z-9t1%KD$i(vG+iueL z8^}*33&6+TUOtC!5U@c;4rCGv2;7W+^D0jUo=igk2hd|$g}$tF#! z0tm{Do_(My&#pBT0=|s}1<;KhC$F>uZq~tnz&CNp7ugNKcM7a;X5`1Uqqo49G@$$8%FjS6J)&sOvd?D1=*$ZRb$yrN2w<^&fPhrr&o4SVmoq90+N3cTS9;8%}2 zcv~a-<_(=5aG>VKr^UefAgB>QXuAi$GU|5$cbeUI{hHtw;D8>znvxa-fHNq6cl9NI z@BGC_8~=~f{SPCb6TK!(7dkoU0r-30J)pc z0qX2UcRxGi<>>*69w#2LAp!XOv`Qm=|^j>>+g(y#a`$N@+dh;Lv4!_yF(y&Ii zE_N@gk*}i&9td9Koxx1Krulom4Kf!g z_MW5nwo;!OnsmB46Jt%+T%s8{+`m!~c<@$0(#*4*Ir1;Upx2t}eF~PWMRwaK84s#= zQe#Xe%chmGYjVHYW)huuZd~@LWfWm#lfB}tu?j{?4wh2a9(tXh*kJ7WulTQ(4XNy& z5Qt}KiMk)Ll%8#{Dl{--wN{tbDv{j-JQZ06GxZQ`(G++`RLs)3WdB6%P5+MlBjRu< z&F<>M@H>Ied8RC7G8*}oMWAkR#z=_Z&SKm3s=3E+L(@XV0-4fd(J|rf<hk=96&K;C!?g6{t(?5&1evRU}oh^(PS0GyUFMm=RvdTQ6 zIuUHw!?(uaExNX>HRlg)AszPAIicLvu?m=qYvT(Gs3C{2-*w9Lx+FTy`NGyRZgS+Z zwvyytB;o5ykuqJtqG;JzOOLrST^u}KDwEJDhm{RWiNr$-PF@lg38l$JKJ1!ljd5Fj%%%i7oIG8Lk{(T$-+kP@u{`LjEYH%EEjSdW1ZU0@8_+jBoo?1!QRi zUV-twf`UqL>Q6$ud1KGW_QsIJ)}i9T3ByX`^9T>LLlqXHs=_rx$G~U3yKs(BP?Wvo zK=BQ9v|@=^1DN|OWcMdiU3aBMvl?j5M+Wxx(Ht&nDfTzEvGB%{hswIwsl#tySv$OT zlLQaAvVM^1*8KIzhB1jv4x*sFofO=&qE-X07G0XJ*8^p zd5o8f!{6SMcGL0&*6Aw^LgqbxZD71_MJ$7=JYPfV>`)B^!ptrCm}g75L|73f2_*J& zOhYj77)Resxvp1G)9YkKDjGpP;P%b84esxh<$JE|Nj#$7RLkJK z;i<8C@A~YT*-2kdC_P0HLlJ%{W=w?Gf6eomfA90uiQh@J+qS8KbwkHuT*u*_cEW$P z;BYBbITNzn+H2C#^+>ShGTAaVa*jJ8U>9DnsH1fYO!ggUI^_<6Q0_T8q^62pb-aP` zt;>q9iS=z|qZUcz-*1D+N5oomSwVJ!2Ai zGp#~=Q%)VKrR3E=zIXf4lrMin;j0II=b2G1IajVISs;`;fm@VwFM9}d1b z=p41L7p|zhvS--pI%MzDk&-WT(@?Fc-OtFRW9x;nlDD^JlxfqglVMcaWkIh?p{CbQ zAPKPjK~vMPO`n!E&|_Y^WoDmPceq@BHa%d*F(tiv?~I~suwSA`&9YuxlJ5H zZoT&86=kiGhcC{@Z{ijyp%raR6M;#JSWzgxawtOIrK^C0#Du>TF=5@TGDnKyK{J_Q^J6f+(o-AqXuNN? z3T?D56r!G$M_i{@k(qIUTHVUQGD}bJY(-iakI?s5%|dd{a~)4}{>09%&JY}N(cLas zD)j>|-ssp7;}%PrZ8iH1)A)=Ad1p-JN^g>i5#b|S$XeB?3=%@54n|_*8&~^4rPrzw zj-*J#HGnFXop%-SCV##{5FeD5_8zh!PI4R-<6^#ms2+^El~2{9(^e$0SUvHB9Wc!_ zxq21=eopO=#w;~B%cfWc#$$>|hS$$8OIuy@-pETO2?g;$HqA?&{MEIycFh2am6Y%#4?PT zNVO20c{8xQJy!(KuXiHzVW6NPCz!YBedab6nyqq%nwWYROm#rm-}+8V${Vc?#8)vs zC8pk>_u6bMS>1F(aHcpVVbdJ7cf~nRi1-Y&T)W1XNMi3T&fD0A@SRp67Q7IYy|(gj zc2l%Rlr1KI)u@Ur7JfB-^uY>qM9C!<*^8TN$XZ&}4z)~5N%$0V&!*3aPvmt_4DqJ7 zK>y%f1$*q2n@B(+4Bb$*)b%qi@Nf?FG$z@*YXg6GHzpt?-kh?PlyNy)Syf^~@!)`D zKl8apf={a<1*c5*^1P-2X(^pD7&W_}dfwRNiJ*NG09X=+ZCQe+t#z2XCNQT?qcsAG zLDf@N0O~D(m(`T)KKjX@Ytif#lLvFY)u!@2=X^tAoHIOB4vSY^;Zr93FDW%;U(6lF1R7TS0y~jCR;A~(y0`z z6IeIvuXeVtYS;d(%j%`n{7Khr#b6OO+3FR)JuM{n)M?0Nv^f!x2CS9!l)bz7uG@se zvOrGPrX*8pnqr2*n3hY!#@UD{tbs45-};vGFIpNAs{<0Ruwd^lD~pyfIoe`2mjUm0W$o8?o8!SlmC!MLyzF5P>X6-0F*!Hant*2RZt3ak?aI9b}5sqzv}R`;uBHmMX4K>46WiCxX8pZGm#QX{ruv z>UH86Ti?wv$QY%7RG2YcPB6PkiHncDU_1GP!2p{uGA&FVg7=1uo9G!h_PA=g_ikZs zVBKP240HEoQ9!Re%cp_JsnXBi##J9&UgtF-t`{gN?k5I_z*C|%=+1ak{ilvU!WaEF zq+e3Bpx%>PrDom$w;BVN!$f=Mu`RojtaBDI(-TcMBdf=F>hGz7dT>wd4EUOW>#kJ; z*SE<=?wq(U9|$MFo1&gfmgthAXt$056KFCokLB=?Kd%H@+f~pah`E_z5vEBFhC;E>#)fF{ll`U}-`8(cmu@AdGfog~p&o*?rSz@4R#Yb^>ROG&5Ti$$%S2U4 zcnm(?rkSXKNUe=zFj035!=03JebkbnVJJdHwQ#RJ<}Ll3DcDyLq;o^>lSHRFjA0>< z271$ja-4Z7(v6H81P-QEM{?3G$I;|d{+oOM;@wG|8?oSwTU^NcQPeptJN1;s@pn*Q71r4+fh!U?mIeupsOB-IEgi3im}!IAHX{ z+#DK*!~@I+ZW>MuS#BmsSeddJ{P@V-yS-vW(=q7_Ov1NwV1$xwYgknaxDd7npk>e_ zr*W4)!0E#UkF)aWB_UvzXCC|$6t+b!$>61SzrEvYE-ssY$`0z;-cjxo1YO&gg__n- ze=JvuyAz3JjI2`hco)tQo7ss-KcS_8U_Sgt2Mpz+%H`9NOU9t8_s9Eom!g+D#ry%O zP=l_9QkNC>>I<3GZXkviYHu;Expwplh`F#f**#OXhmReR*%&VB-gxnhs_FR!pX02E zRgveEr`z0Cx;XKU&K~Vc!xOGPE%K;(%|kBNE=Jbx0r%J{XFyfNj&W>e#>CfpVG4Kg zxC2CjFt#a_l<7|+#M){)UXI!$Th79cX;PPv)e z$Ze0ak#JqU$Ekq(Jj&^F07M{4nMbe!azm~NR3yQ)wZuLv_G7U!`$SUkC4-#RDE=W zJyuPHy~L$jJj?@6>y)MPw~6y{9Jei% zt{Xd!Md4`gLCWgXYSd`M4*Wr%Q!PFF%nuPUcB>;l%Px>(;m8aFI^U#w>@X%zqwmE< zO)(+l($WKQ0Ia@}(_@QS#oi7cg3l%P_%&)o>kp{gSZ-tRO#bLd|7g#`=rGW1i6uw_ zr+r)iP2+X&b$N4X9NeQfMdP}AmyexP z=i_CG6Mauq7Nl$4P?12jC**Bg+;LXf(htH$OSR#c{)e9o9D4@Jy}sF%xM(l_^>zQ9 z_7@}FWcc84sQknrv|a(N^%79Ec|Pa)l5{~dDXs0@26>e+ul+giMQ3ZG4y$v7UA)QL zxpo%dvB1N6qRX>2=a`M=ABC;^*(626!`FySrzCL>BQqrtycr{EM(`=dYfey5&^GON zsY4TQ;2MyyhY_y}z}_u;&G9I_q1Qcsyhc~ixAJZ4A~nn%vh}JUg>PZlazCaZ@2~1a zQ5bBRb(elOI+GO43@h86$Jg+($j^%agC~as1(tTW+c(fV_ZFL7<@$y0(ZaeREGyY7 z8X1M7j?619Ju+89(hIeOKD^7fO38LDUD+lf=nm6+aN?P&wwFMm z?Ge`ywnE3??oNyHt))CrS0}M=@=rZh29MA^?#VWX47c+|^DxCR#R}VX?+E#>CICpj zLkvL@+Fo^wOs`4pKG)svF5{3;;=cX(|xfyY(35U z-ep=aR}=(%ya~h3?Yqi|a6^KYn>)^2!<@+7w+F{XyMVCgm;7WG$ELI8KT#pq&e*jg z+*hKwI!DCuJkgdv`JaFreTlpHvVeHXC9pAM{3qANo>A=xni;Aw5kb1$3LEPmXantm z2Z37CRjHX#xMMox7@qVAs7DkBF7#?pW_kRUx2}e5dHB3qHG@v7QQdzyjb4~g_B=?; zO*#&PF+h1SBN{V<2-m*KYTpOVu1akl|GbsMH7iaaI#>TToq7BM-|_U*eY3$ZA3FE; z(8^7U@PH~6(J6$?v>)vm@4=Sp3z#Ooy(EK~)@2+=qa#0}2S*@0m0c>RR2IbO`xTX$(Vdak1!q)A>?r8t>bq=Eb# zpLpX_>N0H2L2|)AWs{jyiY4qMy@P8z{bQ)~GRDS&)+V_dR1gvADO63Lb2k0{HqMqO z>MZ$T=6p_bdu4BX+NidvMo$MMSQm<$;D`fa)L87Yb~Z4Hz4Bb{?7hR+LKwp#e$v&{ zoT~l%=r*PyX`v;hYJ-*~SK=_;mA+JV@TOh(q=cI${OH|r6B6Lkb4;e9iF~~ zO?wV?vnvI4cNwPfd!Xwmyoe;A+AYVxV^mCyox`%A9J7M|ckk9u_*_f`ch72W{Nd>s z8O2^YJFot3;*{mRI)%;TD7{TSZLWJd)P3w}d-#IG!;W+=V~cAq_lS@5jHSI0PA=L5 zPW!38#6hl z?N7lQXqN8^96!X1cQ4S=)E0z^zb?mBocCgdSi5FK(f#?${Qd4cPCJPm|9wlul()03 z8utp>w?^@fa+Qu=l~IJ+ZJXKs;i1s1*R#4jhHjV+8rTbYF$|Z!tX0F>?uV(ZBTe)& zbb16cUrGmcybxGVprVzI6IYK~pzG8=IVH(1OQ+uT1Tjg>h3r|l>q*Z!LOu`ewt(a| z*#_1Oi$%UjF~WnPxJv??nw95b$$^hpXSSsVwq=8kh@cf;*3#tlSVCjC>oiz7CDA+C->-I{Ub#FcwLyp3j3>ynoK@8KWjvb-eyECj{r>GISBArgNsRuxdL>2pc+0ucINE6r*Lz} z)B0(mQWdjD&q!HjLWX1nNO_v~Y%|PjNGctB$B;9s5|Q z;P4;rDmwZkZ@nq*^owwxph(Zb1^?iq5Gk#*%uyFJ9La(KyCqr0r=cM}51u1=vBGJZ z9$wd9^b5geT4fF`^TrW@?nVWE8N4=W9p>FfpVD`%@ksYM@%?^_r#0{X?~8J>*)l-! ztCEbnqJb0(TADr0>uj~X)NfIc!hqLsf0mpE?J+qoRxGlQUG|(N4ikU;@%TX99<%Xu zY#qLiw>9?b?~q1qwtTOrSo~o;X0mi4Vr3sl;?+Nx9r+KHICMGb^X{toR z@wMf>!X7{RK|vkq67@a!BJJgrMM`fyVQjwTW0wsR>Q*FmYBA9=LT3A2-Ej~nsHo49 z9P&&r%1zaszst~NBe{?@ zmf+Wvy{sFle3d(GSE3bC%bW<_2LYunQ^=VLMrW*a6xwH0|1cmW2Xnta?jsHBBvq+J zyi>X1I&aOy4nCiO`eIx*LWquGl#&JSyCD7&D1Z|FRGxI;LbujJ;rKUWgTL ziT*WORSj#;-}sKRYeun$nwC+1v=fv1n+-!gG+Um;8a)(6F%M?V88mi$+ck1*Ek4kr z+)IzEJCMqa-nGZDj>3^zh6NBdv5>vHG9uFw;8~_^IZCy<%-q}uj`GY9Q$j<*dqj5| zUIqre0#m=c%^Im<2k`N7=h1gU5|&(Ht1$M?&p1rG^p)q!TEtGV!(Hyt&#G%bhOG|< zEy|0~uvszEE}Q~u8qDS85)!#jZfM$BMTKJqa7?zDI96M{(OO9^>_w%Qy&K7{h?Xe?O4RCN<#W9z-mpK0!C+oWOlS2q7j(AXu#nnwOHeb2g<`@bOrGK5?0h zCzp%BlltL9EUc{8>az^ZSwh>|L`x1R9K|qxF>~T!KJF=wYp|x;|M4-!U~#qDT1>T! zzNUy29Bm$@Q5;+Hysud;kjBWJ{=fu)CaySJqgR-$&de-o8WRnak4*6sF)Khs54}7n zrJ@^HC&h8Kv%TwS$=p&Oz5`>m;LadP;v{)6y~3)tbz<)b8Y#dJ4lGeN=}2h&nuK4! z6Ddtsf~Vx1yMgYR9=9)9+Kx`4{3UN$M_^ilR~r0MwWsp5fi2k;U5j?}0Oh87Cbd6{ z#YPNon5@x(M1WlY)PD_hW;r8q-dRFi>$^ECgG)<75l0RI6DE3Tg3Z0a&q&JdR?4miJY zRd81*E_jG5(VlE!u+wNWoA$@03-=T>Es)Vu-M$E?mQCA6xm%uakw9R)L7P zoDIG%ZBL1mN}DWuW`KaNURzZkEUfoG^lgF)NB~i9a ztzLG?)m^6-`~>6&QIun5s|-b6ihvhWXHl(Tv>>f)rboDPfF-Y6CW2y@tcEI*CA?W5`%j2KBl>#g>x$hH zTduhs$!@uM8#)GD42Nr8^9*53*I}{L${MX|K@$aSjgA;jGu3r-bYQxD(~;x5r^P^w zry#B+QJy`+>{K}t7SShy7!k@mkD*|sZKGYz{R~ZWzm6k++3!#=|1MwS&dh$9?SUbZ z9mwn|D4?fA0~rp<%|c-znDV}pcG3R5F!sc`8tHM(9+Mis#Or~FZ1Fs>u*+CYKUY{@ z(=acQX3;7dVO9b9r#hE4P{I`#*WVteM0b2ABoQ)~YODg}Ui-YuhJ}NmfXWOOeS3&U zLU1Q%-{$&<0*Pr{)8S*juFaFuzZ&;usr?Nq(l3AtF1FkQfey^^=iK7{0-^PdGf?TI zbtMZ63Wrg$Uxl5D^c1P`k3nr%yguRp^7|q)e0f;U25p7Ycb%}R8i0(5c za%~#9q7XwtezXkIP4WK4D$dDO>iHD8bJg{aUx25~8tgD)-&PreOkUGgq88d4;Y_xq z1#VcuG1B?D8AuahPS4s+wHukxM7yk{cUSYd87L@Ik;8A|;vmqP1}aVYvk}?a-`LzfHs{`|Be`xZ9SiZjx3V?MirFhLLWjW9}w%=!ecnF{LsyU*-`@ihqqn z1#pHN$zdJ28H?BIeSk$t>G|vVK$Q0oJUSXfYz#aIz;d$iTuD*n2%)H|7x)c7R?Xsn zk{Tjzp)aMWm}aj4+cj+7L}_Pdja#AJ(7#^*>PC1a7_MJOcZJm0z}3arywvKg1HT;C zN$9}rnc-3-9IuKH^{0*!S|sq*Vs;M~`sqE}IxcEKDxo`elVxEXl3pHuSv3x-hfjX; zu=@8&nkyOOP$>R79 zE}L!2>7}o$=2RJo0P|y7JFpyFHS9jgE&9tkZJWFawDMJ#I;iXuJwBD{rlu3udk@!n z+=DYT4#AOOjDmo4Z=WdqNY!G9uWdPBrM}-o4cB=&;!Dqh3qhgko42$jd~Lo;g%Y6& zt8nXSlRuxjA5K@(ev+pT`bcMAzrL%ozxXMX*nbpN9842RA~LExlf;w zByQ!MCi{h-XgWgP$4MUQXT?bAE4F}s95HnN9&Km(i2m-r;NQT%0)KMS2(}SFF-l`{ zlW~R`r$zVYExGB*>8%0nES3vZ*a~-!tge{tlVLKc7~yj1+|)dl%6idO-YErzc7)Cz zrHPa9arSi>SBta-&dVGd6O7f`Rpg3V3#Bdvv^AQ@`^2H}%pAvEATfZ(6W)ULmAlL$ z-LrsJ^|l~hl{1ihNK*kbk9A&Aiw#<{p&BQk#xoAniGE|i7E_-{?G(;SGJLyKBvRNG z=XFw0NJ;YLR%iATAr;3-2E$?k?WqVZO;Zh#(pcKDA@$B?FM&KsrS>pl8`#1j)MhLW z4Aa-&{F)|_Fcz@YYN;k$`3HXWilXj+Bhq91KNjh+u>W^0-d~X(D=Xu_m3jYJq{qR^ z@n82YM7M&O5N_FX@Nmc=k;%GZDE387=fkkUK6%)L4vr#;*qpz+Cf6*?4r@G zZ8dhDeEKeRvnVs|EIhlsd^oMJJuaSWSRtv<|E{BkIUgP#nrF)=!dUf7KQ@jaHu@nLjWHNJs~- zdz(;oAFW^MAfN`+H~FmH_%)RMt2WWCYg#Go1b=mrUQCQ$Stix`&1VrIt=_ESMz_E3b`=lGG33)5w3<+! z%5raHor5dTIX~g_wI1kMuT+k(+0Up|pACQx92^`kpbo$)Ccrb$8jx@3%Cig5PyXR2 zjZej2X(8k>NSzNQ&?R_17~fakTbqWPAD|8GwH{xtFV#18zP$rb6#)U8AL%L>kjMww zdm@I_7nx6o7kU_aU)VvoXBI%rPHu0mRL-d}XdtKCkKy;o7mzbd5ednW+IQ8fZFUjK zB=qj!@D!}x!Tu2d#O*E6s~ZS_&kwH17SO#a8qQA}C4aR(fInZN_xZdp((~)ZH|9?U z?5{rG5rtr$cr+Nj&(MQmoUXsZNV@4C(~_UP`ya8}9rP12uf(^d0`%2r*z&d*eyU*Bb^9KHB+04PG@Oa;{KH0#B9kFqK z0s6`vm(&LnDv?<6nWV0Q||m2z&r#?`-=gKmaU10-FGN%Y0$r0E^$)klb(T-_brR z5KZssUYv-ZbgxNphq||8D|`5_%xwIty}OC^7rnbw0JB%Rw-lZ)e7n9ZFo)Os_f3r7 zd5?;0KY>51vU+vs7(p$}@W7D4>r25tT{ZCp4@Mif=;`@8OTSGG9@HJq?0WwQO6XTi z!|AxTCyBppMm9Fk47w5aNImU3&aV3*&7~C0`J8y#rsQ!nZ^X2)OR&?+dlAU*$lhgT zNo#&q-UK$*+Qjh)UNq8*ynC6t`cOX!ep=4RI_Nxo8S9D;p188~sPrlb_R?jVL@tE0 zz)_|b)74F;6PF0M7#8vy4|6>YC4(Esqd}<}JQ4w9{A>YlFf^ag>59oJB(|$CP#j{_wgSPWF&1 zf~R9E(Dm>i}8X#I;ZiT+}vKqg#Gj-X(UiPG1I$z2+={LS_VG&>r z;PQ9Jdz4zlrh`5&+&uadOpnavQdLf^dBHJ*Nf{qsOXBVyNPP}4Xx)+N35!arE$P!9 zD&_dlouV!Ew0qX13vsZou;S&KxgDv_`^I`#w9)txV$LBFskYm4F969`VVy{wP|Fb9 zErg=yp3UXVjow|zcbBotW@D}|`)sm;c)@2Y(JJz(c0Yr`00VZWAOs^4Bk& zB}N1&Ll?}m*{03eCA&x1maq||%u`b-K%lOEPj25kv?L4!nUJxx zaH2ELyV1-Tu=o>hvo}689>P-Sr28~d^mMJD3LZo>bVikBGDL>C;F=*0$9c=LS9WA8 z-t7_!ENhUljhMq#CI1}TqdFrXR(cSwo};|C1Sprxny$7uZ|joXbiOV#TymcmXJY!i z`y3s1n!i8NS_Vn9@=f-;axafjuazd-D#@ON8@L&Aup0fwZ<%4eto=htd@eU$&zp`j%8@`u_}&U49KW=g$V1-?;2gW@xPg& z-@~Dpim@6=Z6KAPi-^qgtrD#l+GOK}3!Z~*ozA^QrX!*COzr|JuWNO4?xe(B4| z6dc@RKy&4vZk;?QDa;`80AFo4`^R1N8M2+{_B0-}2vL(yRw=?q0pD23p{@pa$ z+P_Yht@3MB={b-);U>?R3fM8!0})XLKN}J|Zq>w)DkZ$7ZmU}eypa+}G$907onp}7 zH>w4BOr@vsRWN-GGlknp>Je2B=0^`t0O59?*44rzEZ8+8I$Y4Hu_Jl3c&MdmQsD|+ z=(u!DR<+qoa8}XPsxI*Z&Er%9YS+(F^lhd56zA`Rax?)`$#IR4+-^KYf!IM)YfCws z=P!G;`__}_*Mw%(IYa$~*9;Pwrk1P9(KfXYZB0p&3q*8n%9GUJJ)HA%mY7G543map zlV86}c^1xfVzS#=Xp=tZSPfsv{N4xGN$6fVnT1IGuR$kr<%e{)N{B$OU z?JRp{?p|SSczC-a0P>ny!L_1^r5J{R5SfI;w(A(O%h1-`bbUh)f!WzYJYaUQ`*<0| zPYzQ)Z>*lB7GvV{0I|qzZX*+Ex4_=qphU3-k>d6^jS~4K z_tqi>JkcXrl##KIWCrtB_e)Y#W??TJcQ|vG4&-?21!uirE|uCnJmnt09=eV*ot=7B z&4ithDR9{KstSXZ_5MplQliXtET*y&K!aSeAX{dR&nT6*1{0`J;0m^AO>FLd(p-gU z?)K8A2R3Kc_QP95Qy|e0l;^U=EIJrLg%nEF$-&v$;JOkrKNOllL?d1FOOuZLRpt&%w;I zI>gXZcVs5fqBQwZY4k6n`BaRIvRpr7-zc-tJG$iBOAa{J3O{qn+kNU)yFq zb|JAAB-Gf-gss=zy-vdZsDK+&@IY8+Ztb#MpInp%)fDCZAoz*M5iU0! z?t7sOx;9$4u^;-EC93-x8k2V{-3hxGp;2SIe#8;dsy?B=`fP%93mU2aoT=d90H}9e z1KFO)>scKGL)MR=XG1s>cI_6T7Bpq*o^D@u^4zjFE*Eu(I2Mi4U}uq8a$%JbKAC{xbOVAP0=QP7B-h z$AMK+EQM2f{2Ef6d$lE1x)QbTretkY4j~|8VQ2`;iD4gS{3y!IVYn#hv;!DQGJaw+ z4h|EWrDSI>pH$|7HMrJ1HP=~FcC#tVG(fbN7zAYz3bh|ldJ`pe8`g76gYAbkIYk{GYE(MmRJGhKvw+j{QN#(z>bxtv& zgzc7Y+qP}nw(Z@vZQHhO+qSve?%lRAedf=Z%w$d~sZ=H3RaNTZt#7U8sb|$bs0TOo za4@VDnx;EF;cjbJ5)sE2l1sbOTRAnp(n%gXe2)fm3f65tP4BKImy}(FeX7IAyJoA` zB2-L~w}tb*4#>DBoa9if5Ejt)9}~*mYTC3~-en!cC;m#cL9ZO5TuUyC{wDS`JPW#< z460oJ-ZKM>#|Xg`N?OPUKY<-r);7Ov*-rO0Mjj5;jEz6%I1+teHeS<=d`@jBh#}R5X^_Zkh$K?jEj@#(A31tg2`O73|Fd;t z!7tXJ9`aevY(lC`_^D_8I64Ve z*BEP#5g6Q!egOBPgbyg3!?^1SC>cty#=G8MS@WVRb+{Ma@HsqKQNpy~q3BAYXrnov zCZ9b+PP19s9qev+2lX(O*N5veioTMEtB(ENO{pg|O@93IaQgJF7Y3O`MPUKksCVn8 zH<^G}?pBw}7v?X@+8V0-CV?cMA+c@3^yr1jrc_NCU=%&NZ6xyn`_`49f)Gr}VTamG zU9J!s($)3Og7Y}UVG3cyC38}08lL>b`nRjW7h8a- zbF&&2bEkzVtnB_b(nRx@NbBm@@~4>XU4G&k&?+CKm&SpWL}l2{EGsERMKWb;zU% zqcB6Ekq*|mzU9usjbH?2w3#1H$8I)1n$2UaNRrX1TOlParqd8k8vU^^Vi}qzLjtq;kBqZpc_JWbq6L>(DzEt-S>tNZ!-i0+iiS$1!^V zYOCw3p)&5Kq(fV$LdU4v`Mgni9qY)jb)O^tB zZExbiXfc^aRqvxdHS66+kzjdYiYB7nrCxVU&Oeady2#a{g?JvMvjPk`L@U z?apw};j6O^WI2S*ihxR*sKyz2+>C}R!kRA_%ChpqFEb%T)82>SpiFJbo{c^!qcN<0 zb<;Y>$K)ISTWLY>#y2{gvX;D_KxZ1q3-TZOWpHe-oHrF9T(rj}u8Hp620xS{!z4N`|W zubb@5V2?+=1SGQumDPlkNIH4GPG?p)>gZG&_CgWZ19csK#4V|rK;;!tlo6SQ@$wMO z@)(FB)kT7X?f-=4rqi?-A$JmIz<82m8}~^sb8>FW@BZc@w?;AtF=PeH0s3D5aAL~~ zRPW=1JGFLhYfEljGdr?2Ne5a>2MajRboN)Nou2q%i4S5lGz}t{42R{-*m_LDTV&O7 zx#}kq&3sTA`C*Ufu%Q`S(rZeh*ZQM~;3LVkE$Fv}=&PJ1AO;>{nC$nLHqQ76{ZkqDeAqo!lvDOCO^)?DRl&q{*lsI8yD66X~`!DcILJ38qCo-mz@=^GQWFq8w1 zis>4WOzP3@Vha}xhxD2?c@g}PQ~`p26B~aolMkyJ3c0K|vFyrav5HKx+6YXn<-A3Z z#d7~tYGHI`0Zxt#*4@DF-@iPYQhoe2OM{P)OcwGxI77_n7?z0~WlCt|)MY04@Vp`| z>vq)BV2Wux7eX`~#}wN6@(%~{1k;jb&RkvcDg~UL0`p44Ze-v8(yP^za%ttbThec* z7%p450z@#W4BdCG{Uw!w1@hIKK?{#*P9j6<RWiGpIhkIkC}FwG*_ z*wHv;{qX6kEtCvpY3Y5BDmfNd$)5f-MpYswoNlM-OJ0MrGc{eKLn$XmJxtM;ClC4+ zaeYpf z{CRa+Kv6C^J;lyzc1&Tq4OZ-@K%G)2#NV;2pi_9P^hR2VTCjiYf74(pa+AhJ(xCvy zof^b$SaRmcAZ_z`d#j49X52E59HlYpLvvO8f&}WJc(-^lsJxgka)!otWx zYn3C@q6=3MmA0I38O^Q;HX0L8-MLp1t+79&^x}?wsjLQu^*@D}Y9!%!0Kt8Uf1iA-yeKFbj`RyNm zmg^<#0%Z~2`}FnQH0fq@CJ!khsnn*e&S6ptF{HVsHBbEhhG~(D%-BUMo&u*$hy!&z z7P)y9A#XGgORJKqO<2&S$7e>yUG_wF6!AUYZ!G&b()qVahcb8A(b6;!0d1nuuX^CYJSy)_rtE_0mDPVRkd8f^G5~oT% z4o0J_Mbq&ii(GPLk#Su)?~6MfyXzqt#N*R4ci${M+`|)qwSgrlN#WCMQ=2mca>2p< zVX?JN5Y@Oe;xVx7DATL<(C+o3)~ZTM5&Tg}8&ldijH@ljDr_IVKWWWcS#s7yeapF^ z#6(t1CeH4g4>ec!y-J*VMh%xC78B-f07!GOrL4{rLW+H!stZ|m8MR&(YT03nTdyb$ zngkULh-mSDeL3_tdIG3fIIp9SZvU=zN;Nl=QT%+Ij|n1CznGD}{3*xM2D$HV!qX4P z-FL@xKAEzcO>xe8#G35N+z_{0@aN>+tP>Os`I7T3M~CS;a7a?|jw7jKsxA zL_bM&@+tk}_8}$`Y1Y%-r;k|QTg*!}e)f_NdxaJ3+iI}w1k!Dgqs`VMTOXzPCYb>3 zic~7K>*tY|`Hgo&*ALUv;#}qqUVBHK(7zBj{0frd6*x*nZ>4E)aS0sewLXZcm@JD;J9;bR-6I{uo~ z0_#u1C9amKGs&8OC>`z>XY0EjFw};0S`6C=Y}sx%H|Xjhi8=y?HV1y(*=Cf$Nu97aDo;M}m$_Hv;@Hwbu_cx4Q+ME|m+sQeG` zvg^2Il}DQU0^DJ=WE1o>Pt~v};OJoBP%y^C9ixgBP_7|-ewJ7zmlivSlBnd#eTQg# zdWUYy_(86%DD-~_EF)EfpJWe#N>{^ zc(Lv_babtrM`=zUoLX25$dwmpFWB4p>{8ERYgqMgc%)=*pWQ?Q#k;D7wh}NCmBCF4 zX^tDLX0!E5_`O75iu(duZP|(U!oo`8*LJV;>oL2nca(LyUDV(ST1d;QlsxuvJ!s>H z;(E5r<>j&ZP!q$RizWI4_G_+nqBVX0+qog`2@qx}uWIPzv-%}=T*}$_2}le=qeJUl zBYE@t;q5p}{-2ncXBZ#fnKaG`N*bOR;4z*mi6a|*t`7$)8fEt62(mGOfrrlzEkDMv>fvIQWY{6NtxK%3&6WiEMp0Zzv%eQeI3fQ+i~0Bm~_spQFZIOWujIs zyx=ZDEL1+FA)ota|;M|;2q+}XsUaqd+aI4Kct=_Qkf zfs0Lc?~lh2Gha%GYlK^WRpf^G_tdKpd>luOm?6$9(rc^w2Y_2>I`JKw_meo=Gg27 zlruh?IPY?Z|BC8dZM%z9$xrbdj*7qY!PUO85&AB_k&MqcDx+%hxvO@YAtbzLzRRXF zw|eDbn}`&hdKVTi<>X={Ix#H1Ls4SX-dsJdD@_DE%brpTla1=tmkq3TC0cTlj#xRF z^?Ae)&I6I|SFH+;=85DXGcH;_rF`yRTZ#WYV6A$qFg$pNdpVAU0~$;5kQF-i(pTS* zPW_Fx{>i09GyPVfkLN-ff8#)n6en=3G3`;{TTW=Ril}~S_rj$=RCF(wdhkW>qq8w0 zef`MTE;KFqa96)wKm;#^K0@&rITjcnw>KmF`YICRO5&MRaCVRmo`s&IP>G~n#IJTg z_?l8CiY}3y=KTU~#mQQ{Y%EQB!@OC4kq^R}V_G;TF=vV9M$qV!}*RU%3}=Uh$Tyb=x`koFT#n+%Ip+&bV3Ev98@!Y;pKyn$E2 zXI%o>@16_N=X!F)pXLfVE|pPAIj7yAkJh&&IZvRu>UDlZw##$G{NfrljJ4$c)|I)r zmd%UeLC|e95~TWxZ0$`tJF&qs_NdsG`($Mv=EZNL zRsZ*M7Up3iS2Fp#NEzpM8#-7Kn~V9$Nt!3QBd=v<~~xa);S5w^7S>n+4^i??_pt zydNG;Qvk_(o#t{&!9R$2GulYIeg{DzJ}efujjGa-AMgOeTiE|0Q}$nhu>S_X{Ri(V zZ)mCPZ1dlNv0wHp`!Ct~e+1#m5wQN!-^45&oqnOQOl|@U9lw%O))3;X+=YrD2qrEGeFfXiBL{+h<{|=FT8G zeo$jS#6ig7Pq)2PI)QWepvWK6Xwv=Wu-aQT$SM&CH4R!rs6niPVzoi7f@DylBcx*g zTBZp|>|jTz(IN%BR3Ko~VpKV(lxU$pT3iT~A!>-d*afh&+OLmd9OTVGH2{$HDT4#E zh7g0IuQCjI!E%cb@LCuKCk_t;!$YmWGC{?|!p;noNaxUK5@7r}5^&GR-4ckGpt_`_7~sz^p#fL^45UG> z{qS6nn3VM?V5CK2MU)7DYAQPgG-tyg%I4yve?VX=V%UD(|B>Il-gVZToaUWIJ;)!x zEA~{XSD8AHR+7)8O;|j<|I2+{PrRBdZ5p}j=Chd}QtC!q8CY9cI#lfmL>wXxYpO~S zI2S&iAK-zo4H6jt@?VJmK-`}4aqhAGz}n9FKpP7E2sI>s0S=Y87Kh2≦u*_xp6O ziJw@iLu*<(G!^aS<3w4Jd~j(|bEwl}D;9h@`TD-zS^Bx|^M?JXfg_JPw)`p7%U_cm zBcHiZsYwapC&kGg(`Mx%IX+tOQyx9)j z>8)$~2f20_JoaZl%ub(glb0xKN~!fcDwcP_H2bW6v_7JM0wcf&E; zx^LzL|5@)k=rYJnx5s98f8hDRyLe{1{w_+0^RvbPKK?XyWDQwg_4>#Ri=7I;JeImq_1>+?C$fl{q=T~x{US-XLdf7u z%L~(~cJ)D?vmKPQ>pKgv&Kpy4lRGo7V6dThy%G8e-qqEI1W z@N3SG)A!-TKR+Kio$cAgZV+KH8gX0j`|GfAv?4cR>hra{k-k zKDV(@15#SdMtYn@tuNJ>*pTcdP7OuQ=nuI+cY@ublKCf+inD-wcs>XYJ1=&MCo zGu(qIj8dw5#d|&B*_=-5mH&fd{J!}eEhK$}Hi%oRVU9Vkb(|_*C>~i(6pInz6$4cR z@&Ptw^(dZ*=9;p{WckOeK39#bBL4}}4StR1Qy@_y3lLV-5Y&E3gr@y6Eg3B~bk?Sn(lll$o}%MP8%nj^sMFuH4NUforYerg zJ;wiNgA&VVc#v>ZQ`9TMS!R#H0|rPQDJ9vlX#o%(y$voeeQUo?2iumT+6!(gIt*~M zzu2AtWrPj{laDO|1I0O=VFxfo(R5H+5mp9oAE3TY0cA72RTUvQjkA_;*E zW^BJ0Vq99B#6A&VTFVBJeR~A@tf#*O)ODe*_6SuVtp@NubUj2b%dnz!BMVqfOuKTF zd>YX8uEthV$lDGF*~aF02CeRgBk4Fs@lymqBns4b=m4Cf_%+;?+&6b`zH|hk=3!t2N^>D0 zg_j6sEE^PiL^R32cnr7Bv3R6fN8}a1%iQ8K!QUEoG`NZ z6o)+{Mvw~1!GnQ=#AHR`9QWpLB@cT^QHg@^zb;=7Z6=yzW=(bz$g&rSQB?pVo$?_y z^Ox=R5ot&2niUQ~uef+E`97h%? zXf_ihlM%^(P)sGwXi~Uvq#_){3#$SM^X*mSz^NMS+37~SH})Ck+$D~wz%fkjkr=&v zX4^>*Qo+N7cNz9zmyyT)U=>N-K6A^nRh1MYbV&MHT^rI}>WZlrW>GPNPa?0j+W@GN z96TJGJm#Gf6|==E+D{kBc6T_AfpzIXpm+)C!;5Wo`i+{|oKCYqF?k-`tmPmsuaP!Vt<1V4rN=%`IUvPyJQgD@~Pb8=WY;lpD0o74zzQwgq zlC+~R{3k#YL{C$ZVr7%Nkx6-qN3b&r-cjqcoom3>2+tLG!{fY(4$4KyLB(B4;FF0H zejkWPn`7DsVr(rDewYNq0qsJ8K}mk*9$gz>XqIkK_99k^SU6Ecdg1n2Qr!ibJpa<6 zc@=*QnY9N=Mm*(eGmjnaAIR!(XL`!hb)l^}8*L?&mpmKy*)K*Luz99G(fT}*F5l~X z%9D80k-||tyXNIzvqZRuT$;w~`D}_g6SOO>BO&ROlhQUGEyt;(rxH?Z;y@tSykZV| zNNTq&ddK4EboWCry?%)L#1)-S&XNxpJqwjtr=p0%2Zu0F0vLcVV)Cjq`l7u5PH48b z&LZh4jXXWQRn0f;q(4#!HYrn}#*#bQ^z#_<8h7@xylW}S;~aLjRW0U}=)^kU;^Q_# z1l!n$@y!#YKhSwH*F9z7TUg%GqGNBUNt}Yj23kW1`JDfhGm4m$>-m3>*DNQ)67{A9 zRLM-mshjRN$AwtdAIGSG6=}U^(Z|+yScP=;Jh2-a!KUD{^X8m6`Y_8=n@>~9Pk`wA zk6YQ5yU!vFV|lvwe?8&YrG0D_ddwOi-C6@Pl}=simu?zEYj3%eqpirCQ}@y2Af6pl_1CL>y8LSN8O# zbcBxo{A{W}f`5?kaF8$xCFUXBG9{kNpDlx}_^Eem<+JhVtLoKSS(dc4UFDQNqED?h zbFA&{QTka>_!?2bRrEDrm|P3K^5?1AQ?IAow? z=s(&M&TiWKA0SrB6N?IYXipZ*Hhgu@WT&Sqg?w4rt4s1p50)N29-4JzO;t@3j(jzJ zHQ;J9YpNA}X^v6f`3J-~JbKwVBLFv8{ZFv-9)yPT0Bl>8{Kn(jh9k~%BXbDor%|PP ztkB^heFR7+Pll`&WoAipd7Byl??KLc zhvN?{PNaZcN0pI#=(+yaL*7^+heIf*t0P7+1ny;iVN{_V5U$&G0!z@m9H~zpqJt$?`8v8jm|?N2gxwqb*WgIZ9wBrWE0tYMUDk zyWZSZqCtJVmqyBI)PxB$lD;6}=MR9`QWhd^h-Zt<3vLtbdAnCK>#q7~H6MRiVeF?f z`ZmEg9%)$I+butIFkO2(Uc0mY*3L<_*YN4f+##Po1(11;9cxapcZMf-2ZbZlUR4kA$@ zaqeIbw7$`?zP`b!Xl~JBy>&V8(^@ot?oU|DCKns{6CNMvFKAoGW)Z(>l^>ZzEU>VR z*FONdw}*PPhiq&HZr|7h{mDHKNdyrO=CQ5;pt24SDHm&?j-o|LZe|xAlhU$z!S&+{ z!jR4k!~p{Gs_`uYF2UhX$aX>??hiFSgLQe^S;#q#m;cY$7WluKQAjX@tG2eY|7k{H zj}N5GKpK)xjsx8`J2Zir`|A!Mz}JKB#iasP5`f?8*EAH&12tFM==>bdJ2yH%fC%>c zs|WSOaIP;rv5ssn0Kouu*TT)KD1ddlfN_6QYrN?L()jnWf%gxL-sL&^nfxe@kKWB0 z$9Hrj1u>5=Y>qBK8CV#>gLS8=yMX}ep#d&U zY+*l*0BP;aZu8_~`KRl6Uq86GIe}^PHvv92H3Ieh6ufl>@eKU2hjA}&KIF&zh*99+ z{6k_ou=`=GO%B8F-JaB$*YEXTpFRoM^ZlRX+8{1y>^8&HY zT+m2xYA%18V%TaM+4KycS+UujF8n5r^JfDDce%zp59FPt+r zd-U*Y>oPx=Kz(s@fAo|_7q%u2;wTS~_J0xN2=VMtA63a59_|3WICY2SfY0yBBLDVC$zRwGfc{W^#I^tmcXq?j08~FQuYdw8 zKLp=vRKJ*WIRJ%2yGJeMhu@Rvson4k)xi%zfI7%Kc2BLrGrOmW%{TtzST7*$Hy|f~ zz%BnCHQ>}w{~9NN)?fF}tJAlkt0TBK@jZY+j{&myY-@qOEM*8}2KlXh}4&R$!ot(3E$On&ct9rW}0%^aiEq@4R@1$m)@NZlE zH+Ow{f45Cw0e^}f)E#Ye<$fgGw;f-8SNZ1p3D2(C*Zp2L^7#$^AQg9TgWP-4{&<*l zS3d2&&ba|#T!ONRYwFoEp+hy*z+ZINq!8R0Z)c#qiFFly1SG7uVJ;r~#s#F$Y9t}w z13S_t@GZu*w9*dQllBVT9eFLUhGT5xR_@&Gy_hFfGdBG;X<1_UIiCJW6z)@FGEr8g zzSiz0MdiuW<62`o#}V1|Msf3pY7x%XoT78qh1MNc9U?+=pLel#OO?kRH&x&LbqF0G zb!rAR?RW@Qfv~MMmXKLD(@S?!U)!yJDAl7tNy`A0T`JlMeVQ_;=69_wR74kfdg#urR%!nON4%rFjqbjtsH zjQByJ0o7=Ko7;gUJw_D02KS|&G|Cb9Rz@hbCf_iRcq@HT7>2dX^iPf8--R_DNoMPY zJ1NvNgtB_i-b^KgGi5PnLS6@};uVvL7_5vv<3pJZYn1Z<(U@Y<$lYk6w@1nL?gq1D zC{vdalyohv_hjO>Kxy`ta`sFc@ApFS1lT;c2G3ZT*C4cn$#MEhvIPbRLSV%b%W;IA zF_`8Wg>&l#G@s30tBb(|vJ?2fbGfYar<)XUF)Wh&;H7Oa>@KPs#gUlKrm*s=Zf=qf zUGLf*I|lu8lHp&i>;sNh)XEVGRvnb$S8}(l%a3&1I%kZV?#zq^RC{tK*$nPAt*qH9 zRp)S;1}bO{ZFJJ<@EN$NxjJ;_H_BO2taNwe))poHH&;2rZxdQv|B7Z<8l+}bJJ9WW zX!S285zd>6=pdN+1J?xu8tOR*QrUvcu2=M8^^XK!d$ZFCsX??g^f^M^D5JzJT0b@y6wj?1`g*;Q8W|udXlZN*xELK6;i^`rfY6Qkd(yyimR? zfOM7atZ|CiU276a**2v2GeSe^Kh^~!j7Pahg`O|}aRLFIMsb6ICIX%I+A&?Y-GLzC z4ENAd@{||_YT;V<9EFALK$CVBvto6B>GfQ}9gUo?cI&xiE_OMh*VyI=)#PQ5;2W+U z)sC+M2Xo1v!*~^eq4=+rZB-K(*Dz7Cu`)LOyT7kAPBXCxE;l~5TI`}`P?8!3$FE3 zc6S4-*=#RyTPbijwTocnTCP&pUHG{ws@B^qMbr>%BPk^^qbtC)N5i@GY6%?i+_JtM zDTz*|OvX6|J9`46%253;LM7&gv7+%pNU!LDW`>Kgn39k60lFgn%32-*fA_|wXF`KhMMlpdZiRT_E&Q%-nprnR91X{k3 zf+%ph)Z8;a&HevyzBS{Sp32 z;z>7=VzHfM?(Z4*AMa1G_9nh(+e^M;}MA}6^#xrsN&}#eNtD`q=YJoczL2$8m zS@a5(qdr>Zvw}uvE)b|W{7AzV!T3F;u`5}67f|B$xs>B>vgblH^d?g<__6M9MM{J_%)9E&ma|44g&IXsmsb4sp*&V~ zm%4_Q9b73!jwzHXEMb4_8-?C+%JUC;Kac*9zNROn3V29P+|!buyqxdVzybuF>lC>v z!CDc&mOvw=qrYt8$`%#QaLY~2;^{Z%{3blUU$Oso_RBz6VIAtu1$p60)p0Y|`V@_< z$X}NRspT;_nXHYgd}`B*f&dG?O2tVYjNNW?Fm9W#Y-*tLl)64@sk&z^A)8D=OK)%* zL||AVF1u$UuO78Sng=rZ!TLzw&(EAqk`LEM5n%T^^2!3IL+*b&H~R(GIqGKy@WZF{ zP+VYgctf2O$TPg-u9xptu?b%Dz~t1ouYY1H5wlgNf1M-ebzFaDk#6^HhT=2=GF0m z+i(*}TV<(Nu7(dfEbbePaw_STVK>(fUgj?&t+H_#PYAVu9YImND-l21=M1Pr99>i) zVLBOZFXh8VZfx666R0LzlcBn8h4}8L81SF9U5~89qn6JsX$d^Y8d4O0*o!?7^H3_- zUoLiry`CIXDISlsy1_TFz}rL|q1znLJFBl-jCE9n{I@!^M-ry~+y~->4C6gEx&bY7j;NU-iI3xBskloez;*Q057P99Z_p8nmi1VN*J3L^G#}n>kgXQi7CR(-pdj1i|5hzA){s+eO-z^YBip3kB?V(uN#hMJb*xJ#`^g zt2dlV#B_L1_qgrG(9_*HY=0V$p=N$I{$nuxl`olO^*kmx;~BW+!-N*EUC{>Xy!|%K zanuphde=sSzEFg!=Ad`yNuyg3`Lk&Gk3l`RdAq*FqWcft@V3z7SjT*fY!*m_69}kd&UsM?4meiqFb~IjG6QR_J|JDyo>G7sGCUqndP_ z9o)DWjxAmUK6Z35Ec%F}(Tv+GYAH6k_(4z*INER z{txeJjDJB~hggWryPwRaP6Md`9nL+3{p8vkYodb)Qbwzpp^R$t;;PDuZ(ZyaHFsn5 z7Q&Rqvh$Kb#YfRiT1$XSQt$Oh?k|>?w-JO8k(RH3Fol3X+Rnfu7kEC}qx32g1-IML zx(S{ z2W#54j7xOer?yRZ^XMb(v{8@BL}xyDPui5 zulC08htx(CN0k6)09#aqW2?omYb)Jfj_tS;i{LD}x_73jH6sju> zJG0D>@k||9iWKK_7zTp)E3lSQ+Noc4w?i2FXzJ5g6$_vWg~&A#%!zVURUaSJti1Gk zN)k1_AxN_LK72@svN#BMBog8{jRa7yM`EF$Og|u5AEb8I*hzf%9CHF`qY;^$ZtV{y%<`L74TYKt?xz!ztb8e9Du-`iwTvb@v3vV+;0U2QV8U%NO8qjTg zx2pcK?9xS^g_wc;l|GpR*&BQh-mSkrDRQkE{0)ijpJloUAeA}54HiKj3EW zBnnRDyUA?}0{am6=`kmG3IohE7z6~|alAt$CJbmCmY%=SSle?b{ez!F9~SRg&h0=q z20v0UZ;dLgqq+-bMaD~$8S8z&owJr7-oCJpXoJibC9D8?du25z*a`*F1u9 z`3>y5a=Lg)E@(3zrj=L(HQtqRIQLY^*y1tMjLs~gCZW(57SZx_R!v^$o|L-ddZW8# zH~mk}aTT);VTVl6=yiMrhabpV<-v@cIybkQwo8UZzdThGf4y3!E`rqK_*o%0G>&9x z0zZuQQ7$plz7FZ{qw#0Kxnu0mklR4#Ixg9V$Mf^K2}id)1e;vRp8?9oL0HLQ9jA=A z_xicrHWiDzwH3r@UUJC3uu-^I)1?WO5lFPZ5daKD@Dj645~R`>S}329ON#eEC+dw> zG%1tTm)((o5#)S6aI!T3%XT_1Q?P(=W3CifqSYe-w43p8Z=J+z(J5ys;$Mk5la6d0 zMW=kkfkJ;KO?j+F9s2$CTT23X^g6z@e(h4Xd7s3l-35okUG7v6=}e2+)Q^{( z25~@S%ytQ9m3Ty{Su!f4&>;;EiGIynJ_23`T{H;xvly;}Qu$V|$ z&0$Z}Y;48N`M8}(0d_9Q_|g%lbv|~ly6E9Vn4z*qd}`lMIf}ff=*zyHxpbIm61r`u zPwc3`Ss*86LZMG>kVIHyr@Reb2g*k-NjWJPTg?`FF|1+Sg z$`d45vMUcCBrA&;~rn*|Ja(}2Dx@<=B ztP^Nf4Ok3r^37R3C1y-vgjq1GRCLtC`|o3i(!y+l;{YJL+iHLgPMA^F?(7-MCqubG z$h)5Fmnp@p^cH1r`(7yFx%z@cIau2CJAz>GU1F>`eVYEGi$V0NVU#cwh56&X1+$7F zEip`hW-z6y3@jF8z<%*{>eaw2RPZWez@M8~dE~DaJ|*7+b5j*96(eDMMAZQoj?6cJ zyTA()p54l>jtl6A65fwvTOpKyV;z2YGl9^M#pQ@GWfX(S|Harj1!n?8X*;%U+qRR5 zZQItwwryu(+qUgYY&-el{PWk=R_)gA#a{MZS9SHN>OSXvp5Md77oUe%uBv7qhWo|r z+^!i?ZKll&!NrzLpSmC0hJunl<>7JKX}jjQ8=6F2T3qZ1Jku@^$kV$0+Qz$!1?kZwa!L~DzX1KQ< zY+1{5&HOlF=V&TT^}yjiR)_h`FoT*6|VJK|-oxx=Iz# zJDb>S6O1ds}a$W&(vcg&|c;n=#eLN|0%)ZIM?o-Ja-yjhX?*Sv%FgiyAvn zKw(PtB3pz~(mkRymwL1fLa@~762AA52 zVqbIX!bK*P&jhwW&DKdz&^nHmEXeZTOuY_CGWXCr^}M{`wDgHpsx69Bt`x54lu&K- zKNg4Vp|l?>1Au$)j?~U=UipB7XhPl0(W#vYA`%!ioIagaoM@TLa)7&>o(FDcWD%d;ufO+DJGKTDP8_Uk`!uJ$Dyc0(C_sM2 z;Yvt8;YN7#=VCCJ(c$9|wR5Z%SKkMoYd~SxjXpiokUToqEatje4zF;F`%FjmnXHX; z{2Jn)Ei6v`sGW2w{2lyduODR=F*mqx2e(vKFo%%2V9)(-mBVqggXR1}V6r5Fj0>{17P^q- zwkMUChpOzZ3b%f@)`DEX#00oLSElaubNK`y(*cvb0$hQrC#Jl9b0Pv;RgX3(-c#xQ{d(7H zry=dcG+$n<);gR0w*3v9cGw4_9uxYnAad7KYFLYP&kdYrR#vY;TA#A99pdj1@>06K zi@RA74GAA+iQ0iQ)<;m6EAVv>kX{Bby1d+=%*Lsju$~Y82$fN!5o6HqK<&!yiP`7P zxKU7xlUkf^P*f3<&n!f;#Ivc#@T_-XG=PvPSy^aXpg?NlW^(SlAks4?xCI>`5r`-z zJ@EGu(P0kSlCU=m2kEkuGv|f2t9nf&z9-HET9#zR`atEh@;gI%ZNHt#w;_Tv{7R#O zP}<$;J1I+F{x3Df+ZO+}I?mBm1HCN(gg{M=b_%iB`7xf&ds@oO{ea+Pn|?~d3sR59 z-g>M2cO@^9mg975Ds!@&gz%W|a!LJtV%x{n_>N66R*Xr5sc8|cH>X=)-ZFsdbj-cQ z_cYLuN-x)#ckFy6;5^;ptp#-jDzF;U*v$Z3nju+M z5oYsEpUu8V_|tYIH{BdJcL4@(1H((*H=updmzX=X5G!(C!V2V0=(8@riL3W5$>&6@ z?q|LMrQyb`?nPZaale$)0Xua~HC9!9gM(jpB{*Ve*)y+Tsiba#(cDZXZk5}=@-izj zfYGjg%+f#zW88V&%ix5LFDPI1?s`Y2_Or7kWgz>~FFf~|3+2yO5G}EDOi);3p~_HG zptm9yL&;d+b3!^twnMksg;1^OZf3ipN0e#Uctp)Xt5KhVF?U*;_5>=`a<`YJtyd*W zRbF4FDfB7EQK8HBiFGyzX=}>pteVT{Yhmn3Ic|@R0en8j`UhHj5I&>BfW`r|<{KQk z3dS4g2-B8=i!lGBQ^uUjHB-j$5L+5IdnUcWK4n~@A*FJ@unMMd<7Za<8If@B*ovDfeC7jMjxdYRl&&vHjO1R*2 zB-|I#Pu-}Me)MJXH)L{t_*7|ckjr*ox{C2`X{FaxT+o-2f(%C;I@8Y&GtGvqkXED* z6)r{eRljMwt==_@#n_5)`0xRfOc?r95^(g$>Lw=&>B^C=T&HYd?_f_Y z&FXeMB=@znYG9?_Dr{VT(%Jg_G_Z|*MuX#%jWcuWAJ4W07WWq8vb+`*&{)9%H_+4} zC!u8qut{K`*3|a>yH?p(fG?E`Vgibg_ldV=Uzz&a(>@GsF$IwPGR@s^^jHNb)8@)|C6D!8Bw7reSS=K9>5D-?I`A=3K?D z7I5~~EVhRL92wbz^(=&{zS|IK0egNZieN7+*!KsIlgQv&;GT-S;0^oHuU{L5@dyJd zOHHI0BijMg9HKV))20w>F=21H1I28ExnhM6PJ3p%jH2(KCsvVpccT|i?akN)6bOiT zj2U@!1@GFSGk<~}WF-HJ2IjKObp4^?O-}9pCmEkkbTZdk0H{M#>;5rax0091nIg=? z-^rB~+k%?OeFy3?p5>!0;6Gk+R~9{FW5s@lH`9E<-z`!ed3=e9e9(396^}moMjp4Y zOR}SBU;J(Ek`pc<$@RmQBCS410Oir-PohbR&$q04>d=?fHQCjs^ax%`hO7w~Y+Df4 zm1mJ))EoIUVZ3Ov4GOh70Uh9wV)bS;9fPZV3kureEi_QWU3TOh z54j%w3E1AcO}60@k;g1FOYRi*LZR%tkcinv#XUGC8W#S>@I-FG$yKaYUO0!)DT3dJ zFWL9X0D84?M@I3eljw!L-ue|fsKWqZa{~dL-YA3wiaM83=E7?>ItM{D5O(V@eYLb` zS^Bcm{}q+~8iet!<40YOd0I@pbt_^&ZBKIZmG)Rrxvs}@Qn}(DUyk^|$ky*B(J7#F zvq_HHt5_bGUbevMHpctNP1I*mqu3;C zh9_>P@L@pIpodj(d0&-pdvJ+aTwI70^qs~P;gh&A3OOj^OCp|@7ZydxOX?xufkD8g z<;~n{C8Q8ECJ%8Fko4?`oPnF=D*w$DMlj)9Hx3qCiz5`>up}#qMky*I6s6eobpLmZ zx3I2#S;wiw?$<~Wk?>>@Z^_cwMVJ%-4+-$<#t7TUWsuc zIhZp4eI-26BX2@m?#w+AJ^J%{Je{@wfefD7{mxg#1zl-7XL1hkuHA7{OXe;qvBUszuATK`_*1QoC}jSmFFCg5a>tFD zh7}LN?cPhs+6ryoOO6bs))!sk`J63%$zNA8*4Re3AV&NMPA)}Z-)7isz5AKVRhLN@ zZxIS8rl4o;B|5S_lS}pOCto7)#(QI`KlvG$?(+U(#2P_90fmj$KSo!3ZoMpPywH$Q zETGQ6xwlmxY(CBK8-uB-PL<$gr{d>^%+1L@?vy-B zdfw$bO*;3&%lJ{WRG+AOVt>U4M!ze~!p}`6p{{VLy~KK#kGX?~YzUqtzq1$QXVL8s zGB+lD?SO?{5?_p3VkaHHiBtxr1=JLkBJPcSbtQ`#A4aeD#y68}0()R#Isc`Bv-o|x zMm$nuQj@Ape)T1DOku^izO=wZnWHJjruql$%aXG!dy@%D*IjKkF`gyBcCDC5hNgjIL`vUPx-3TM3Dzffc(|7 zX`ANa_jRGd+>Jek5zY&1K5n{|ze-7ye0pFM`p2^6m;x9+{YC$NcH2ymDEjrn&b0~S z#G8|8o^XEe+(RR~2R)&2d=K(7E@&j4ehj4AqyKY)HL*vlvK6>~ttcYHR^rvro_R9L7XLGsT^WKUZ(|~ugMx` zfu*(K6g}ui;Byhh7uSj%`uwj{X`eca;>|5V6eeOpJUYABhtO5n3HhYcC{Zfp_Sp%~ ztl0J?H8Y(fQexX%krhnwoIYFMDdxa^jF`R2xxwEj){%T}+34vaA1Pxp6+M#~VS_ug z1+DLj5}WfuVv+_0=I6|;MI*7)yuN`Uh{X2QW@y9enH_s`t}gGzS}g~ogEg>muaTeI zUca}``iHAWnYxhf%uA-aRK`brU=~9NOHh+<;#W`_T{NUDNs&y?3`KZ1A?LIwZ?MCL zPCKcX*Mr;F9BaZpS+!Y(3GesBOxncG=bIhVM!uMa-RZ4e9*#^+B(^X`y?eCWQ%>D~ z%#JK=>t?jqLxPAq;R{o7eIL2UK!@3!?%)rP1If+8@RJExU`@(w?;}ueI~mV)arHC< zM^1|6FKij1p{Jp>z!_<;w@pkiJ8^#fAhF9;7ea(Qpk6do@3)Pt4K!86tIXYVaTZa6 zvVS(4!va6&kExT3;5TO!8=KgiJvpz{Hh;iZyq(${serMLJRP>W&PX4D%T19#W7jq0 z=xGH~nrb7vE{9f^bM z+r7g1cpUynS->6Fyt67-qN~?t`ml2|?8EwvKG)&yZt3n`Pxx_QXC3&>O(ey;5st#9 zQ0}zLFFzRKZ$Ft@&4kvy5j;Ve+E~@j`9fLks(cL$T!?{;?GA1lFe>MwTr94eR8i2e zZ8N9w^U96FV7AvKi(1`S`u`y3Cj>My$fu|o+BG|19NO~OFin18j+HuWL7vP%@mMux zx0T^z-^k%Tp$x%kp3N;Mla@rtzR9^v;!=o6=FbbFv|Uv!Bw0aKJnG7}**OlUTVrSi z`H4D#m%kU(yNFMRK?eKb@3m+|#{!f4Q3w$>A&atKiKm8*P^m1imtmuJsA-AY9e9rv ziLdl8pAO6>xYPCX!ln8grB_l)fL+=267`G675aU29JYPpmd$g}p9ZT%M7TRD#lwBA z&VM%B)zd+wtUyc<7zi6m+GSEZOh>cuMzV=W#55F~1R<&_B?*@WC(#VpJ6xIQ3)mL3 zqYcw~!M`zkk=Sk^Db707_pu4J{D8MCVH8x8Rm$MhlgILk3&(Wo%Xd{%R3$B1{IIz# zMfcab1nZubj+98E_@I5%a=A)yFrVoEZq|o9`Yn8#D>gM_V}KuBU}pSM6(-{~@$d6E zK?%qLjquS0N|a7|_T5>4R(_HBC(_}7-M}cuzDv6Fa^e_ZvC|tt&-q~g_heni`a9c` zu?5r6;wBP3)AVBccZ$VMZ8+HlNdE3O%kz|^3fO>I1lGAKvg@r?#t_qiVTqhGp=tTx zo~@Ib4Lu4Xc!&O|yr;$Z#+mrJZ`aITDo_k$t88Fxd&Xu?R@%-4#gByqshT=ThW4Vs z`Os9U5Gw%}d$AS>aZRKBRhU_<-g=uOS< zk8Lav>CLzCvhb)%2QTU`4W+fJFtLLBJScdYjle|H?(!AICL{8m!CajzDREF}KkI?4 z`L|2ZidT<74D@t56HgAr9%_AHs`bS#SjK3fv^`>hOI}(h-3c^$*+>8bhA;pPy#Q-# zUh+6No@!_yC3J_%^W?9AWU_3d&t=xfEgH#4&Tfh1x^}J)JbVfgVrUBiOg`kVBhDfx zqYE=wmn%G?M&81-h!x6nemrEsmN8xp=a6+3Uep>7n7+F9*@85U;J|bP^iOOw{RZ}q zAv~HJGq<>fFiqQDz`9vSLjCL2pSrm%;?FANE%$f>Ym`7o+2`p_W|eSYLtY%}(_>gH zOUBZ^pM9~{)d0T*kZTq|5l7&%rR)RZ#}eed7>!rYB!~c*cFqmnjv{lVW?*WzMc#$} zYd(sgvi(b6!ZL-zn|p0`i(HTGx_qhsVbf^u*9)tFi3My;)ITW=YpExYLA99&a{rh&@BN0vOT zKEUQ=vf=U0v6Bj2d7n59)I|s#(NPNnPu`R+Y<oEEf&UFms$&!MDtp^C7TWU_j=&6Fi7lOyh_uNXYhDozW3c)(RTY6hpRg` zyq&9F$vns} zE;ZfYMwmuzIwQ5!K=J7nu%|orcMpzuW2ZHy=8O93(l!)*f^8zw*v*OLhBn^dR-~vQ zFyAd}Cht0S$xpEN_;(xE8Vn#rT)-P=BK(9D@_)ladwq^YP-a zAchC4pvp)%bY>KZ#1HSnY#(G-ne6c{1Yr#HWu4mrm!41 zA)2gha}TDqgV1!gFa8>Sf;)P5d|Zsqx!U5*l{#kSCuK=dceyYVdZMxvpUd`JH{K8x z`m;f(nYlY!-weBtX?<}Sm2ja);lV?H7(PoGVV!H@3If)`;3)`Pl!ixml z^l64F)CQ2gKrG2+_FSd1`d6vN@_-y@Tz`o)_0jQ)T{59wf;&iQWo^hQZ^jvz*FICa zAjJMy;rocH;#>H0vx~3kSU;Yt>ffkzJ|PCy{{FClqFrKRkYHeNtb8j(7XV-beCw(1 z*xeZNM}i^!ULiZJ;YlmiwkuHz(QjeyX1E{7`%z?_rVYcp_NxTzVU3`uR(@^8_C02b z?MRw8Q;oj;9u7al*kqWAsGh5ho`IZu12qQ6Idq}Q1^046+^C((E>N#`>!suKeS#u{ zQ_RNHB>%^KG~vPdmX5{8&BF2BcQNy0?54+D^heAGjRAj^wAnTf7vDkbTKV^b@colBg2o6-04D63Exy8Z~B=I#Y=d&l(6cF{s$CFnus#jQso1g zalfb~_woX^FJ+n`ni*OT@3f8EJ#|^fW-Bx#=;690>=HMj{W{Zh&P!aWEZSvD_~^@8 zzw-x#O%=PNC8}=Qul+j?1BQEE^ZpYgF%}Yr@nZkdrWzv@e}?U82+-|d zr?G=7z&HfyR=q`Pm6kL27(+Hdv&2vseu<3tWj0VxmYHbe^G5ZnU>L3k!IR1t4~ zBQZjVE6?`*{swmp>Hrdwl5*PFy#e~AL4^VVF#xmRz8 z;v`nMRSX8!-P7|XTubl?RUC|m$=Ht@<_v}<#9tuENCkFRWg37mj{aW8<_E$NkVrax z$k>l$6#oE0To`~G3=0Pr>b=$OF-WXPwrB1hP*{o~v<46J6J7m`8Hjmz>Ifv{x930j zb^nbH1@UtY2NH~2Yfse92zLWiAKoDZ+-a@-Nkxdp2m}`XNfM;Xhs60!#E3KvZt5=j zn#%)KP+E=%w5|GDCV_r6x`dPP7+UbJyE1Z&_^M+e%CiR3`ZZ`15w zo)(eP$vjn<_yJB$K@tFB%TIs`P>@uXMFK)YMhA|Fh6M)s#+O6{`$!)5=e8NVMh2Sb zd+6aV?{j&1Ck2@mL>&Zwb*IB0j&&^rn)OeyC#Rx;>h%Qv$$$R-d;Ftt()Z`nAoaTs zyTY@x{d1K2hvd`WF@bh^1b}!b-kDdP%{(u@1qb@+Ur{>WXRd(@6X@Cb%~%-;vK%i&gMvM;RSKT*wbTE1?_{|W^K2pCb}U(QN{ z1ngx01mxih677=_3H(|3OZ+>Pc^x&f8+&`VvXlDs_W9Nu1m-y~2-=(i+3?)4Z1Zk) z$$F$~$EQlPF@IfMj^>85O&;Tq#3Yn+B8*}BLS12$*`a!_q$zb zhWefU^c#~y0Zv>)2dY%U@;xlN4b1?+vbTH4s;v3g=L+D2cIsUT*|-m&-`!RT601vi zSpKN#oV(o7Fc1)zuf3>Ki{vNk_Fx}PH^g&5e=yGZr^>SkiUWrn84DPbYd96<@pJu* zByo7nIv+qK2nx6c+ec|0`J;HS5wfe>k(eMs`Q_^c%M+#}fkr5?u^@eUj%ZmnUqb%) z>u@^q#eVJLA#F^Yn95?#7C{L|kAxrSZmfXZzhu$7q}h%<#PEXXUIGdWF$cT!Sm+`*PI`nzSbdhL}F{EhEkI{Q0T-L=YKYArA0m`qa%SJK7iqO60XjZ-p0CaEBy`R1Yqy6|0BhYt-PfU##&Z9A zO;wvt78aIRE#h>}?H;cQrLvsuQxr&rnltL3)AM&a!3>fu-84d{8=v%2f=2|sB<7xF z_H6PY#u6u34u1%!u{V)Jy?Mcw;sj^dockovWG`3BXA8(*g$^c?a*S);HD%_=9mbnf zwV=k?@Bpa1-uH~u>!3IpnYv2l2#WXEZP;u(o=doP=-byh)Jbn6JNdN3Wt^77IysW& zo%OJ=(JLHTn=P%ukJ#IHtG>10M`kUgZ;mnslF16_E0TOgtu19% zN4$cZKF+B`DjOOYteZ61$!kGgjz{8-O-3ZnhtkJ}7rxT4L5iy?A%YigU*I`VidCdE z--o%p4SM}NH1sn)73DVv603ZJB=MJ@@C{IEf0C?fRVY*g-Ru}y!jqGvPFT%dMOO9v z^CW8npnG}|l~hHp7;T7R&Tne>qQO_qUwxyiT^o zf1jZ+sWkW0X#__~@9!Qu~ zX63}2C%4c`VFH=hIkd)H$%l<2LI)_3skwO_t!#j=GZ; zg;{v&7q}qb_hOsKdl~8|Hq1VB$a0zH1pzO{l3_m`&ms!tLiBG;0FSF{3886;dt8>t}(~Kgc#&$>2s)P>2y(d>jp%C;`E#MZ|%0-M}7N-9uRC@qc5D0WTcQ<;PZMtc_d zy)DcjbZMp%x+kBs2;X115w!Bh8J37*2^pb{0>KE#7>%jR8K-)RW>HY0^e-{mz_V@D z#U=V1M+wEO=@)(9C(?4n3i=EaNy>8|v}g67eddT;$ifu7#DrYZtKU@B z-^5xnz$(Dln{&4%b2WP#{x@Wt^K%xa|rx-KQHpX~HEqs%YcJNH$G2 zyNa)@rl!YRy3E_8U_`j7^}+r)g7_Zn))EHEc~-J?zTeT^U(Q3Py5*2df4a7dOBuoX zUdJ0*}{&ozv8I;0~+)2Ps62ON7JyeQ}_8rwD$2mWvj~STx4S4-X0T_!rNOC z&)bB?k8J)&TYQHM#EbYy~Zu9&Zpm`!+egY+*m zF?E5amv4@I@0612R~pXPp@~kRm(R~a$){`4Fg>*qf{lYL;tIsg&clLUW&+eEK-$#Y zwZ|!zt}yGCT!ZUGuyGPLM#IV~=m>qyg3-5HYYgbngDRU7Rh@6kv&ii^aWRs{E)=K= z++lG)%P$81T82u|?JNS5F9_)Z)^6s#Alh3`dP6^# z2-!o?)qCny_U+X^#FnMW&Jg{J##`zq21{EwYl?kA`3u0 zL9-BW8*~Mqr2M}7UHv7C6s?l*ml&Fe$ka^QXUR1J&xv^(rqs%g1HHJz=ElLyULoo*Tqbve0@RW_6~ zh0^7XhaY?M=UB_~&T!gfCN)CoAU#@T`To9Yl?yKayt2!~p#ncgQq2ZUmQtZJ1GTEe z1`Fa^dFZCc+nKU8S)WEOchcwWj-~r8{M|;j4?hO0xdJ?lc;5Ng4zw3rhT5}z;S~7d zJzqH?j+1?Qp5l6Iz9P3WkcN@omUQs+3C#*${fKrz>Zun53%3a}o8l%JN<|R%ZcS(b z=;XOfoNY#~?)Sz0y=t-nxja%~TpsH@xXNNs94SNz~kfIf+ZP|yyUe%_|!U+K;DQX4f|(sK9g`3W3m z)ctme1bDKWNj!VnJAmNY(NN6i*2aGL~4J{ku z2fE3?JAwQ84_)iI*<#^iwz-$l2fRO>c1 z_2b{ba7|ewmnBZ4kX98dw`uPm5c%rlWw-zG5SyfP-MmW>)qMlq)RgCaQM;fQEqbf< zA}qg&@-GElC)134j3p8XITn`7mpeH0^I!O(WsGkV#(fafS zwO{%q>MzFC+d+;V8)3>#h#b@@F=v{_e$(f1n2LQF4o`9rv-j9DU-kIBZ8-o#9^-| zF-vAnSflBy5a`IQM;oD(#^&)%Maigptd;z@*pHCS>Ht+Yn$_5vzD2YJiZ}qth={mf zz3$2Vo2#W^Cnewk2pS^s$V=8HXY;(Q*|bOc8D!a}0^HZa7-UWDuws*1y#jx16Uhtrsg@exU4x=JvCXM4OqibVDPY%Vi{0rpbTK z|ClV_V;%)PgydBNmdc7U;q25K)mx48fO?qEhfm+n!F3)3DfqA7&)%K zU_%R(jw)xp8Jn~V($4A`iq>T20amC08&Rt-JMKZw(2^#HLLZxg_{~w@GMPZMrtQM~ z!jMy0gcOPY9#ar03r2HOgJy_;N#svhNpM>{FJSNE)apC-EBJ340;WX9GIH8jZ;C#< z!YjKAoQ`MGJNZO;ZdlA^GZEjyGxbYeMGc|!4n*e#=JGo0i%0pb4dO|r#CIVhL!+qD;7B#0Cl2xqS z${aAopJxPHkG}9$^5^wBIyJeP7V|%9L~$X;P0@SvqgP)~^U^XO7>miGP6IQj(i4yS zaW&kvIo@RbPvMzfRai&fPf}grS}aau0&>{UDO}#EEEhP8Y|oZI7OhH4R{I~hw;W2y z+w$=TudCwRbo(QY2G)AfB-GofRZgCV!^;}Nj7giJU&Sj41tl7$>x>{tV73uWuNV@l z4_rts(*ReEC+-6X>*laHbe2ec`A1gVkC;y=vQQkZ37jc})bjSa6+WNdgz3CX>JFzk z{6DSzWAP%hdn$gWWYdIT37G#lL=6;qw^5GIJQo}kHiy=tI|xba zHROyre{rX_=Q$ngXp@}qs(-UpT8s&kCsZpOw)&TqJMe@c^>B+DVTs$xnJ5|p|(95TNwohM$jahfNzSg|Fk`_EY{%o zmAY_z$TKbR_4<6DT~4pk%hzDShX^U{V^h{q^@)zHH+ZAsCgH|bq&C=KyN^&()5oRE z#5*x*pz1?%`YvB<`;d=JZDsga$)XqfV;+9GdcG@2q@zN?ZI7oM5O-1Ac z0uy$iU3#<9w<0|1UJMokXqXckVf3dwbD|$6C#hOQie^3!5-h_J&G+ULv*I`^jJ-lk z{Z+Hjy*Rs#Z#!2KXJj5CKz{}ET1=OVsVQsx+07m$cu~3Dta0x?n&PSpvD&&&7azJ$ z(_X6A)|WJwrp)(isIv2c+Er|ToWi}ow!=C{0LwI>pHqlK`)dmbe+u2w@>KJ=mRShKLb~2K` z+4@JGZ750)k|pky`rXd=%>PbSC9D*xLr2nxmwt_JS18kZsYOlDhkTn-X$7FmoIP%m zz5O)^v#-CIV|n1JL)Z^dh31AJHQJ6S$iwyLu;3ywR>SQ0hM0++nb>-2O?P=Ief!Bmg%+G$k;Nq?I5$}5k*J0w6qNW48;Do z*&X*}GJ=Spf3}Ar3_I9Xd`i?Q5K{L zazAm~EKcQ$ygC<2`)ywXCO;11^ zoOu>I9p7g1%YV7n3}N5)MZx#Tdnm3F496Jbq-OwdA;hfc*zKMm4jgqfxr;sPnA@Ao zFRt(w8oX7)*f!9_K+GN|l2Vb(5iS}Equ+vHJ|doF<%zG19RDh67N%q%gkqlVU-RjD z&@=S1fJq|fZz!t~MroB@8zNEkg=^h%cbJ7yw=I*anbc$lSp4&L7LBbltga2Pm+@By|Z^OYUy#-tSdQ z8m_2hSwV7b#h|R4Xt5H88;f zrA~r9i+`sdq>mY#T1Qd&M-{m-bz~A40a~c~V*W-pcooY0R5jt5y6z_iywAQgHP&8< zl^STH<%cG3R~dI7<1(*CNF6)N7DS*`)He|tQfYsNeZnSuVdb^NK35{LmSsBilTpFv`L|ct3Q_tj98VZTblNZ=NgWj1 z->YBME^_D^w!?Ny$6h6!beuXnM6^Ui`{@TXn~y>lYuCR5W9~6orW+!8;isa%8Y>o~ zjaD349`H@&eX z5<+lsG^&|Y5#D1*L#w#{qV^M0^PEuA>z76{PR2DSIkK5M2AHeeow{N+rBX|^Jdzt;-=jmU_Sv~q-82IwJbWUV3AFu#b9 zjGesCXeB*F@aAw4wA~ZXh2^AhJEX_JkBSppo4Vy7H5y z%uZPb$i3qBSj6qfDFLV?(JY^Q!p#Ugx<|~cPrGF%D)kt;9!GowOv2K?B77dn+emof z%^f2?$G_fBeSi^bFx``-uF#(Ka$*0x%g-6G+0U5oKkt_)QHqxXAdp4}`qS&{Pqgb|QIZD9I4A zQIXBrb6w$g`oz2?Dymm6&E!iw2?gd{4+BGa_>Hc1SY}mYpEHA4ofeEDIK!@tv3wWl zkLJp7UAiv?e>ub`hQInsbIeuWyIQBDdZAv0qipqTRILVuMXxzys9s&I zo$wFaaQb!fze6EU(MoBg(@_kx4p0{BA#k2!OMas`$S+31T}a6QtMZZTb35t!B5^5&>>Lux-B***MIKW@PVoHP46oQt}zwIWN~5YG3SR2aNgI7`N~-0YbV zv?^ld-I~Q?e7tgT|BkoPF#jVi*Z!1A%en%ytfULdQMqD217TrASEPw~=dZygC(VT@`my|wd#^QCsC$(u;^EehUwqPr z1rACvm74EvYC4<8KU`XsNA=4C8^eebD*cD>^V2~0f9b+<{GYq994!B(3(LjL{BOGC zf6_;}xw-zkOCz@JKf16nDJjjaF)6O@?%`|^!$6>L>_gL%q}#;XY0HJ;R8mvp%{bLn5LBVG2YsJ}hgY9N@}2d|*BwAOc|} z0%9e5dmu*6w(;FCqzoz{f-{&_2unv0RpMD9E{q~PunS<&znjDa51(I9hONfHcM%a# z4L|z`2~Hpb{pvy%0T4(=kj`G?mf)^nXCl@8L?L7Tp@tZ3qC^FMban0R?Q?`ExhTQR zX(t8|96?F1fOv?wpiW>KAwKP~3!q&=zE*H3F-V2x5a51P3Sk?B+kuUU`h)wCZNZ(x z1lzmaS|J925I2B3X)b{1sm9+FOr8bd*Ma@vA^V3W9`hajJ%13u+`fmfEzQ84fSV7{Ry97L$;7p&H+!1U05Y`5;4^FP0IU9j_ zb^dV3R{G`tWLtPSP(nA3w?O|XXpke?8=mHVB)AH8tLO<~p6bPp9 z^^G9%zj_E0D+bJn;t~YLQ<-Ie%1v z_YrCTjTsX8oBUIye7WPp%&H?@?*1L4C4vGPG!#Ot4j=Lt0s&&o3ukYE==d412f{34 z1-st^@i^OnGz1Ma`Vz1d1_nx>c32>kjKJ(K`6MJGf!k~RL`3nK-}vr*CV+Tpy9zV~ zV(9W0CI(6$>MMW>m^#k~LTptef&+%&(GIq={U*iqkOcK5f*O7&RLFz;>%VvhBS6GE zE|};6r0Xa_^l6akNub>E1?t%Wtb6klgxKQ!4g6!{pJC(cWMcAn`T4G_k zS59U1n8bU3tYOU>{+bf;n-xKOL{3M0YJK9PN#YP%|5VjA*#lnk7B1P$N-WxFTavMy z^!_h%NwrUR*f{%%4EeztgG*3VK(iT^BU-!1pc|V z^Cu2R@(VSOD080NERRca^==*TZ)FGnT|8mT=X6PbwY7j2(J&;iz#vV+RKA}>nBWe+ zt?V4*wOm&bMj3LFbNtJj_-MKb%$2OZD|P?t3;`2)Tg=8L$>zv|jpy!Sihx<E_Y@I)Pb|MMcc^VX`)im{qrj52A>tH9(OkCzOxy+F9xDQ!SWt;4mQW!IlVC-+$ z$anYrPT*x}mxsbiwrkggT3?0rPg=Nvi(1fzT{JQ8#sIp?3sB>y<-AZV$ zQcBUdS8*!DSOJGCk%AL#1d^;MglRUB{>v+Ir`HJ1JVL0j?-QukL(yf%5Jh&aK|P+^ z>*GmFR{)75Icjac%1?Qgt>88upWn%`)x*B}HUGQ=a#bNDU{eEoYc@kTkyYA@9&Q47 zVolS`3Lp_JA0TZ9yW;Fqbh&INVvR9sN^!UQZ0VA(CXP|vyW?Bj`%NXqT(c?tCG1x0 zWj$@(;TeMbDJ3jan%x)BSRVf{9SL!6@pzss475ci(62VI56Z~3=wm1;n*APzGapq8 z^wN(m8ySs972R{^#G|(Ax@}G<_K!PdGz1^%$APWn?Pqp;X*IE#m4pF17&UGSBWb;K z23s+ph}E(g?boP?Rj~;ndbn$}`u8An;lP9w(sgWCjkitG2WN}Rq;H_0OK zHSbb@3>v|YH0{6;-PuhnxQ9Eb8D4TqM>!ppd22yhzf!yuLD3Fnt3cuhl>=Djwdzfs(XP- z4OZCFU3y?K|1R0gA@M+q4c6rl{PnV};Rpr}7S1dh#>tBa|B6wgHrt-RK3|1d_%% zon{B;ZmmvI(gRtB#&=OF*E0C}s)H1s7TPdW@i+j>AAN`K0T{cDqLL3m(F2F>RsT!m zBjLD5&*MM{&4%^|3o>my3FC4YMA7ACOeV<(d=iw|V84TAxdlcmT{!Cj zGwV^0%G_m?t|JnTKhw!tn)kXhkPU4kJVWXik8qq)mfia%Vgq!T0vPveQ!+hg@>oSa zhS8fL4X_|u*s*Ce60OUU2K)|v-iFG{KMmW_j7xc!Rv9~qN;pY~9gHlM)hSyLQv6wOrFaz@syrun9gK<*>2e~y zsDM!)BvAxRozlRzMc4_~HfHJUe}YbAA!^G}G1|OG{JiNL_`hLOUe=e5S_WpKo+BGJ zoReQG6Dbbu*$OnFqO-kuT~{`0Ak+ZyX5d2zMT(L+oCEt#kO)?lpu0`>cLO|W7f`SO^{5th^6$X}~{PnC7*@U%4F9O&3(`AQyZj6m@dE!|7XrB}>) zJk1alLKp2WI{5*^rwC+EM)`w0&ck_RE&x$VFRHFm@L+$RvP`BYkRv6NK6w;b39+{e z#|?XmDgUv7r}89aL}~swmvbm5C}jVsLv(i2m?$23`Zv4ySPmtxdQxFv(v{IH?I>Q> z#!&O%-{x1_NVhBJFk8D~BO&5(tT1^XO}U(8Q-_(SDJJU_J|ns*b`AhD!$NSMh211k z{XiuBZcsSDX=f-z8&D-6KEO6Iu;%^LgTvQ1*eAOr*#+-ZD@v|;O^=_W`F#Afi6R3O2(_V_d{v7{$Hy!`T# zXgQHwduf>^;}1`oGbK*CkMsnS8&Z zG3`uW zG5f19@rj&j+@qtvqISDBNMPS-%Z9@9G(b zOk7|$V1^o++#AEJex9yMLcqs$nSWS*Mr-Nr*}ddM{;M?ZfkQxd)w60{fN=XM^R9H~ zPSHi?iA&&du3AvLymTV?>sPY%tvm7T${x%;M6AxuaEUfpth zJE0+)Ft)LTEMOuuU)om^d81gEyDqe2<^auC{efIU*J378TBZ1#6Ix_?E1XHC9R~zX z1|OU0D=`-eZLYSTY9WPNL{_RUJzbnf&rjjE$)Y+J0T@>h9K@o9_6|rfbq5dDhv{D3 z7d;O4wmGf9iRzlfh|`BN5%O|}ic*v<%QY?&^|1wTd)B|ZSTFG8HESZR zM#PT6f8)?c;LA0A`0-vBI&xXnOM%wfSg|OT#qRs&_9+rWqZWihPX>2&yoQc!YAF2G zuD1KHp?|?z>U;C6b-N2;;Cdek^xgx|GWmcCP8X*&8cD^N1nV&yL#P?O7-yJ|P^Qnd&bld?llH)&rCCx-E; zS{zZz%^$W3u!{3kST}hvfJH>!I*eQ7pn))Vkz;c*;uMjE5Fp+r#i4>3EcU_pfXw;r z{q<_?jI!LZmC$#DQ8T-IIBtxg+F1xU6vk)IFy%x-n!7TpFCpGMe;+l$LF(j^oAL+2u=Oil}v+#ay2n1Xd4NoZY5RT<;#_iGR^_yG!c=qzJ0evVG@d(4h_F(+k$4WdXcbnY}yp$mlm0^jw#Ou+^(P9M)uXLhG6BFQ_>QGq`As zs9w3B;wurE1ZR{fAi%1opXivkA z$;U3&LffbGiD=1qQ4A+}Oa^IH6yt32s%Rl1*X$58`Io~xNb+A=Fq!~R87_#@=`ucS6g%&EFrrD@Tu1(;c4EsFf zrgm&?z3;!PQ*UfB=VQK{?88?(3W~6!AAof}x+}@wbjKywNE=-ot4S(!NohbLhAxhZ zb#ocRU{*Z`I+UvUxYBnmngygaz8zfM&#QaZ96<>6y&*d+21n+!i%(ltL|E)XWTZ$;v%r zy#wC~Z8&l6pjn;ZMjg`Sw{l)lyJ*n0`zh2b#ht-Y!%;CuvxNXY9c=pKFke@KXy2OL z%_OES@=?Hu$aHSru=ZC;_h}3%FNBEZ)<~-sXuza zkH$GQ^sUV}K#Yh|g>&+N_^OmaC3@UqaTfPgO^->1q)7(G3aECyD`DJnJPy81AF>KD zx~?8VfjPnTaHz-noT&Nvs2sLPZkEzzXK>NoK4_jI+e9c1w#(?~MpWhLI%JdK(+|!f zc%%|Uc4RPhY-pd1&rBXddaPSRj6BjCN{^v6nd&New6Vy*pP+7@7QVr{&?!GqAeVc1 zM{Ln>zM#`SCtDsZ=mEreChZ4LcpwWwdaC?U^8_{0-I?^08=;m8pU2{O;bsIg zlA`^-Uil@^WDJ~pHyy)lc2%I=EH-)7oke!rqaZqFRy*6u5QzFa3Hy6Q}? z0ax19{Q}%P{+JrIouyYV?+oibMfez6QACMMF>D%lNmK zOURQExy%-8>=4iL`|*@FNk8u`lm7p9fq5G*R+i>*=Tl z<@)7$(JUTKv-9E(%A^cre;&dYZDO-wBB#y|X@~+|$9HV0K`7Cr+)c9e@#nDDfbI78 zl&2Sh7Ve+N#hI$T#9Oc8zi^=U1jXP*ZRJAkv%5v2;?PjN~^6scqP*Cr$zRRC4v!sH8D(f;8qJm_Ygyjepc!%43(C}Wcx z9O6wLiT=z{wKyb09mJv5KO!Ov8W%ZHe11AY71|tojlIzqLef@ow~^+K@Z^Om5u5hD zMT>O7EKg&`;x2fMK88YKprKR4iYQp8H`&UmI5x^|1t^<1U}Shi1yL)mKMzuu1k0(ENz|LF9=v+xG)pG+Uku%sL zcV%AHt(AGLTz3`SXS{gAs3o?iRojRp{!Ua_p+PH})E?Q@iE9N<+4lnsoz2`)i1PXv zQ-<45Y*O-5HJ-FX$ssLR3!ys=B?8z_hW8wmOC0I*q?v4C=suD*vxg`{F1U|=GJZLi~J6o zuCUJFi{zFKP>2E37Qb>b`fw~PF=v+2VL(-DK9r>jEh*8EFv3cn8FxaTX|{VyJvAle zHyz$_C#|LG0udOWa?q4z2VAL<_)AQ2u9I$-Hx(?*y6QY6qzN)}WX(8wS^JO|PN+#7Sz6F;3?Y z4$X#tB~%2{)h>^@qv`>QyN}3_m&mWjaR9W)!dHrojcymMDYn?zcVv*U1k0%iVDvzs zzbt4}_y$Y==DDlT6nC9bSR`|(T|TyDU^Z%otc5mhOwr=A6>j1*K|S5?s-&Q?4qui! zTp?tZ>bbGB>G{T6RvDZn`N-fe(YHKJ+ZuyeP`rxonrg&~@A>Znzcoc}p@qz!w&TP` zoX>m*h>nfP+Z?`k`X*>MlcwS=T<^0DPrJ;GzL(HRQm=8208yY(*n+`zk+#ZaN;shFpA;ThwD6!v#S_N;}y z7m^UP)1!B9DXlHWn^FvrdQ$%btmd0R6ZhgneR0w%%pr7;*peiZD4C`-J`R~shJ`2S zU9p-Gr`V`*2P}IrYvR6~%k1WQ@{H(R|Doy1({G(_ipO#gakf{9D&K|Dg9?yHgq#x= zc@3&(=75IeL(&3=D0eKPoz`sFV}Bm;~?B7%^S zUyb^d3oV>G{b5%(?1Rp>9@B_wWYWx3*ADEwuEl*_j2+{ml^EfvTxJZA%2-xW7ICwE zFJ;F>Oy)%7#Ms;V)=QAlM{?i+yz>ZvR`-h;Qi1I5O=`GYI5McpVRk34lDb0|jVs#l z)?AMpGJfm!vLWZ6k2ncKcj}Oy-Gm|ZaPX=(MjZ*(e9Dz|}OBXp5twvJpi8Kr6 zKD86~gtRMER+M0Ct%l7MO)rrEsmazLpVG+{j?kz7=kuypQh=|k5z^8O`=q$(3%SAk{A$s^HBpu5Rm z{B0KgW#p}dFdKZVgs{_V=xeozZ9(_)xi!F})#$Rb&-8#-t?yVz+x_6~rwGQC6`Qk{ zN4EPE?aA9t>B7_~yxu#5O|3dfv{N5ow>@c=le^;f4#*E8uXO4A^kAS**$Qm8)4%hq zRSCIOBa(wt3JL;kA%@+|J76WOV_@4FZpSHp<=hkTrww?Rn1*yg3%?)ApN9P#?lhAR z?PKE2t#mhN<@rKq5acsLwaJpk)x=CnhZXYvZviEv}gQ;DsGxT@^-qut;E$4o_PNU9Ul|XS#-Wo7Hv12Fn3-d zm-*IUiA)p$Y{N-dG~e9 z*vImQBN~!Qi~qMCf-@4Sb&3A1P(@o^uk7|1!sFAL)soW2DxvS33fI^y7Gc6PH(-#Y zIZh`gVY%|fi}u!dta=kQwmMpy9kHCq!~=eboij`k!Dn47JGm|>hgPqs-8;g#oEnmI zP6PeoQ#SrJn<7kILqQ4d{2YSfFrg7D8I_8?giM@!=To<^G;QOSM9P&(>hEsAm&R+H z!)oY)Ll)wS%AJ*#&-6Uw`^=P2$TzW51k0Q$!j?CDzMt29-~enmBA7r>GY^^kDg6i5 zh9T90p>_x2L!qlX`@SdxsFI;GKjOKG6!fjcDheuxiv)4v3gUG<4AX;;dswW9=eFOrdsnH6Pr7@hJ>z%qYhI$>9M;3%VFoZ5TD8OC6$uVz;~8{6 zr9^e&$i{tgE&dT{iu!eRB||4y-yDy}X&qcGjBONPO?DSzdSMNI3Cj||$Ws;iT_hwJe9 z7B^Ieo8!!|T(Ho*UR(L-uh!RI%(#{X2x4K2z4$UneUnEla-LZ4z(Q`8(uNJ0+IE@> zUaxbHaf52J21$lDBij47a^{}|Ki|vvWA;WKy@G~7IIdSgp$26CIMQD(3M+HbGHhgC z_|cJp<8XxxzKlO2N7t!~-SF(Bx#wz*riOGjVyrljV3;J?>a)=F5F`Wt(jY+zRx;mi zI+=$|B9=QXtn^Ows*32xhEbgmb55ZTw~HJHFw>Spx&!beM27{VTaD38YX9L<>7iYIdzjw0d*3@f3`_(~|c4ps=Uvh=?=sZ7Yi10`3A4 z6W~2ni@k7NRshYtD9zkpURQRLAT+TtU8999@vSVa9)NW0lD*e5I@|($n>}nEVD{i9 zQSVGFTsz%A!}c~G!@f91?#pC}HZ?6LrH8Yv30_#$cxMAZ>HX?joco>C5A0lCZ4xRcyV%?+(|>~t*yKV9k@uZ=1oiD zv<{Qrk`qp0`03)^M=B_gbh-z|E+<;1@)J`^pR<~xCcd#Vy$5lx?cVk8f10u0kDxUc z1%{ZTDI01S%S|HC zw6Sxsi57i7eEys~XKjBaez-wwD`|g@eOi2#4tUeBF_H_-OD#~e^99si$-)$vf>ew8 zfuw{QHQpHyFWsJCQ5Z?krGLy3j##$zPG>J_Tm6lDtpcG?W#EUI5^Y_h_IXf0)q^-1 zs=^?I9;>6OMy7;-fTcRcDt*W_;{@?0J;^YTjOW7HMxZlqF0a4f&8UJ3F9#-2;~ewa zwJddJzeEUl=hAg8RDYtvfPY%ggiS0!M_%wqaMlMuT^Vc2)=8QHVWN?~cm_ikVUHI{ z&NHY$nE)WCmAI*%oH=BwL48t+`8(Te5A8As(H+hV|5SWyw7D2kx6ZrCUo%n+@5Bd? z{7JrtEuv;G+UYZOce$h4Fo3u_;_j!kv-+{Wr2y(Hp5%6pn^phHaS+~3+J=#7@xGn% z83B95oaJw^0|}6l|7|P`TZbDXoHvsZC^)DX@Lk`KqwD8X<*ZJ%S-~p z${Z?ZApVr^+`IJF;zEqVIT(fM%O?N zo#bN%-O` zJn2SSbdcyB^kkw@QulK}L`l$BDMooR=?Y4Dl+NS07BYe2+<%Tl3B-^xqViteQRG$& zd|5MMs~EGpqkfM0QeR|sd6_P+J3SJuB>np&0}WRmRg|og>El7GkxOdQdp0AHj6B14 zATM*0?yZ2@q{y1@AJL$aHgJ^I?sTu1ADiMu;YP zO2*I5?<9KVIUqpbb71`VkClIoI^VDLmW6)X;Oa(`NWV_FAjB>GQ@2aUjhpuVwyop7 zBbRLy_oR;3f;!5_4hHhLL*EdN%v8D%44V5Q0eV!eG>f5k_FDLN0wh3g5IK5 zFdgw6e6e1%U9VJ)8%cT|wo|_8I<om#aItx{ zkPIF0T_q(Vl1Pi@l;|s#=5D9Rh1UVHW)9MkOXoogM)Uhbfz!dOa}xBRrob|ourlu- zlSfa?H~y)dtNA){qKazX-azy$FH&A3<$0}2xLBO#Zc!hcYj})OjAAKsKaF7SWVWW0 zkqZ|~9a>|{rJEU3MZ zNSC1ldB?x0L0D*zgNV)-^f>+S5dy$X+t~p65&-I=f2gV8fdGm5@!S144C@{MT++ay z0R4dgH!zqNq9gQR4-cY6*4GaqOnzKIAo@c9^*J~+=6Cl2P|b+ZK*RC@N%_3+>;>Fhj@Kzz%5vUMt9o^XEd)!JmO9gYwTu?8PyV zwZ#zRo&pYa3|vRR@pXd(=2wORpdaw}8+8gYQlMpL%fp^HU;TT~yMSP;0URwq$j(JH z&(2n%_g!9CC(gdV(LMZYy@D8hFZ}s~YOP=%d|gX`a6@}AVxCmVr6~1X3oRh>jF*jz z1Re*r9hck%2!^i%C{EYb{Z{)VxV*pWvH-RScR`}o&GJh<(Fdpt z0i!AL)o;u1R!tkYpvG%d_-Je+5?z9{@!t5AdT`M<(7+99o1>{$}Ra zW_h3=LRem46S0pPECndA=;utq79j~8>0gDd|N58zBzETweK||syoh%M_W9C=KsbQ^ z*M#T}`bONHZwsRB%P6oNaV+$+dqj^hfxp!6B|jk42%*=VjDQB%-=Ln}j&k4vGJzQo z5+sl?PPaE676H6~fn5;7pS}^V4=t$pquG>R91B0@qqy)xOt*~-O^W;r8!ouuH^DCv zJN!v-pxm^S!9D~b>>@7Z@Raf@$FOoR0^M~nW}0{?G?zE8@7X*`i-rut)NJ~EkDzf| ze+)Rxl}BauFzeN>_uaQ@zvelG6Xh_}dd*>TNG2B#Nsjd6kArq*i4Fb)n~cJ70$u+L z!nu>Eu7`*Rw85&;nB1p)U56FvypsPurm!kklSu9L@}rqXhcu2O=_Zw%Lp1BRXyw8u zbznQyOnpCI0rjBLGh@v;c}uoDiMy(f#s&6SZtuqQIwEG-HDc38$SuQ7MW`TOSOQ3U(TEP(q>`>9Q&^S#r*H)g+Qv#?)H9)% zH2+2TKREkc^wQS2mE0AfH(~^ITqmGSv|TPt6cgUGt~%D+neew|lLmR@YrfBWW4G9k zoiYp&?gHihi6Q?Y_Yt#?FWa_@9Q)soG6m$UinHX!M`yZf8s(ie-MI&D^x5q(d-UOP zj>1dlKvg>N3IAD-soCtE)i&v*#cl) zxS*JgVydL_yY$OsO5z=Bpp>LFjLZ4ZEMf4X96NW9Cj%Bybpg1) zJ3d~h4Ze7k5&C(1eH!I?vCbr>(Lea#k`ZhwF-6&GSa=U}U+@OFUTw!DDB{geTl;Tc_lyqZ2M=y2gEs4K?a33(JxpC+;&49H( z4$omNyTH7S8KtO|$@uQhrS{uNK!+(St`=P)5;b% zQkiRXa-RWA;l2}mhwW1T7%z5pnj0W`KU`VxVQXBFY0aJLMRCZXDP&10Y3ShPG1mk+ zGr^5~U{He7HVA;0QE@7yteOw#TxHt!ue(LdWiY4VQwGm5?jvHCH z%XSB^&S;js3Ua!fc5T1qltsg`VJgX4x5<84tF4M0_<&>9mq?-H$ZpaGQTRb+%8>Nm zJ;yb%=rB&QEOTS>laxU_bcf&6Y4JSPyjxe9))K^4gQVrX9&=SeXNQ(*lOr>@!L>4u zU>=wT&$S}aSg>@8|FZqOF{#CW12Z6{^Cz+e9Aw#{?OP(9Dt!0ymEy%}_g zRE5eJGTeG+B1{(_Oz~<){B{RB=bvR`D-M}O zZ>AkZfp=AK(p{pMomHIY#v+MRR-US`S_-npg_A_nmwAT|p{r?dC8ufPjoIi}%p!dd^t(`sj>WRMRt z+9GC&-N7o|&9P-}pj_AihfbOd&}v)vJ{{VJBl!{>p||WxW%}vb8Yw9sdiN0=LT_>q zI|5g7MeKvaZ28Tp)++AO7HW4MMk^JP?bp>h$S{mwMpM31-zp&A@C;d$TUk9|sa%3= zn^SNn9b`*OdQX|oM^qK9s|jbOgwR~JyNk;OuJZVqbi+o&jius)U~Bx(c=7b>L^+$v zC>I8<*ez_55-G>Yj^oo;QdD-#)eUK`;oH34xxBYbsE0%tTA<-x@AJR&@nbHz^ufC9 z*|m!G;54KfZ(lQSA7p!cEnOr?yQywfEh*u3Zerny^?#hJP;1e>N` zC+YEcKu$1g%~;uM-TYb>d*`ABOmA> z83`@6?jlO;FGLJT--_;gg@BxSZ;dC7pD)Rm>rm?J`F*f}salp^*X59ehu3C`ScV+% zthYOuo%hV0JT}vAb7HQC4kfnH({Or85Fxq)0vCr^>z0N?_W_ET%H;!wL7^OceC#oj z={_-}0TAmogNStrC}z*S$jH?fsMrW??26JUY+20jE+e7N8Q%Ls_6 z)sb%1*@*mlB7UtW3pEuRuwl01Z(>83^V{E0SeMyw7LV&JF9JhIm7(Toui>u&;hlbU z*mG7(?$OpM3(v)y{>iGlY51 zN^2dWwxQRl?av|4JhW)`iJNHGkf7D+;MGEhMGQJS+};)H-CbkW%6|j$2O#pW0Je>6 zwC_1#Rz9o8Q)!;0jae0-eM%zQP(~f2CUuN{&Vo29N|VzTh;C-sNQngn1LNRP3*Ng3 zx7*{;naFfR<*=(^@@Jzu|Logt1fp25T)QK@@ZN9^)D?iy^WcnI&41dVU{*3#*0AZx z`C5Pz3Oh5Fldjz*@qDoFFgRCN^zARDt748cL(Nb2rUFApg>9u#juv=*yF%oAb!eV5 z(z_bC|MK2rW^$YIlEHuddl&iKUewK&gGf|~@L7FK%T>P#hT6~#E<~fkv3MYFB@Khu z(44@}Y=zp8_u}P#5{U<3L3pQ6BWh_RO2~n{TY|?bpTo?pUu3^__SImGD7}Z&cov>I zlyOUp=zjzoOL!dG4>I=*OZAQNVdOVDx^${`bY&eG+!oJ{T2)2jpy{o&e3X5x^Ux=I z4|TCro$ELo7yIj7pbPLI>$QvIPeHuH-E_kZ$7sVNrNGfb=X8B%?bEVAU1OeUV1EHs zNUvY5O_M44**M7btMO`GdS*js5OzPG@|$DW>zcPpipF)ZS`W1!f0aAU`x+JkX1)gr z%A1rKW#e9=|00c-Ne&6kCl`2$^)p-Vo~=?QF!gB0`lg=E)ya;()rk*@d2bnRw80&_ z#psmIb&Lo2a(=yR%C`|PIm~3Mkuc8=Q>K&aMB(r1Op+S$Qnxxcje&H*w58C8Z$r%G zW9`gv7s}ML%%IRHBbhZs8Q%A<$t}Y_olRH}EAe7-ORpHQ^+)&CYzc~9P z_V^y|z7!Zlrz+FxnTiqGuOL!Sd<3qE&-#f3?Sj;8eaZ1-fR9kEK%fzIublfM=gPfR zbTE>xD8@>-gr>k0UD}>Oc~2}l#6!?odVlF_S5m!%#UN`ySD?UTx9ex(oYDjZ$$&$* zCV05-{Q3%e$>o0JLckZ|9hM&BYI^;|*M0($z^GAvv zw2<&3z)1Hkk@7%Jtsuw>8qg6MqvU~7O{{bka-TC^(M)McNJYScgK}K2p$s{W&m_?8 z(+e}6Z99n4yD5Zl+Gjm5{Twix&q`1CDhDfim!Hu~3AGG;hE@uHh!TdE z)|+sXbOTlSK-%j`Fb2A9zkiUKnY#0f(E8&8F}v0Oc4RZPMD3Wdr{2Sk1n*Q}5j-5l z4kzbv@b!I1=L1pWDPY*UiAE*I__t`sENPMf`2cUi@S!+5`_73;_u>&ZyrzU(6iAaUTm9*qep+!O(_$idI<~W8pfBWk;E=jqt$4dN1xu?f!}c!n zi95ogVO<`Q?%S1t#m;K`)c7r|&kI5YzRWzXROLy`!jD_k6bl>)W5G7~+p=P0^q(x3 zaG3$%LB@9Oh_K>{TXH<;HZCTYWvGb1(Ri_uIsX>5OvxK`gZ#;E06fj#(LT_` zlzxC%Qg}~Sd)R6nnn{_=eyPjn`Y2i}K)K!nx5L(Q_hqGYdR;M?#3*eqWDt2oI(Kyc zm}^?rP^_sP-kIWmzZZC-jyK`m%yRn#kLn~ zvkhMsTe_Rl5LZt5aV69rH}B+j z8~-zSg8edZvy#piVKFApSSdPR!8>WS4o1q{eDkCCQmwnqD|3%2WC&Pa^rRmyF_&=idN!fmGeFtkg#j}g!$l*V$Qz5!O5J}Zz60^dIPA=- zN0aE2*sQ^ljrv`n<9o8xrnnn-6@T)*l6=UR_c&q^92{}ogy-lX)0p@&(O`2o8n&gv zhrWu6!qVIh%xY!{EAW+AI9Reu9JmDuJR^T6V*hf6nI6~+^tc#PP6asdWckd59s9eJbq@>JND9%hY_ZLO5^t0wV^b(uwCVM3qLAFKG@ox%3Q{fQjP zv9=>ktNEEkJzy$i$N(%u=>GF5avge#pP`@Bj^+zAL@P%_FL-Gh}dHu zkWocg0nSkxC6*LfjGhU093hvf)*8@aJexUf$b)z? zmR|0!k(EZRdFrNRnB!~8@cZy!mC zW!oDIgPD>D&77PZ9x=7a++;bar0I#em8<2HwiQW52X^djFQMNzKU*kr5+q}|-QPKL_c=EQO>X7>+v zW0BK%5Rxk&D-qolpq>0Ee8gm8t0Yn`WBXq3j7LNhRfGj?)?RO>#}Vh6 zb+}p;r}ZLar_yybube6TEf?&r^DKl_T-v74Ij zcFmkG_vMAeY-tUkeCV*b7e{rGQAPBHW@V}7?mNGLSHv3BJRvAfE z1Yg?RC_f0LlPzMYBe`BKYvAHk(dQ(~%GC;nkGmF)_cWBPOvU$>mN)SHLwX6ATewkt zjlHK2X9;XXmukEPM{Cqh;AKU;=|^n{i}0xB3m?8#LAhL7%F`rbJ*uU&uoNYM$Ix<_ zJA6fM5HGAZ1JwTEY!=)5_GdscdDaZ;#wNmv{6(|yJ)c%w0@|5PTN+L^+%Enu3#O9W zddPEhzY8G+jd!sJdQ$0n+i9U|I2;F%O7e=A=$v7BROr zr6ZNYCW*6cC7H}i@wQt8gIHkBJ`d87JU?si%4?Y{|9eYx~ zL2j3R0BWRzv;QF{WdA?sgv@OJPl>>Y&&I;Q{@G}bEN z*c^~~(c3BgCt( z*J=%`ldJCB?%ADF?paJ$QX3v#4Xq*;Wyo;;$AGs0BmfUsSQQ2U1o9zx5GbUE`t!j# z`?FnJK~|wMY^YFS@h@=x9at!V-47J}Gp#HzBtZ8AIB@@90DMHqxH1p~2m}zI;a^bU z4haAh{6F+s{$PB2kVt?chz;XJI$hiPFK}m@Hb2cE_8azq{09dGU49FI4Kwm=X|N!G zbN+d_c{8nC8~l3!JVmfD5idWrNLh+-=1q~o{{H`>LcSr);aKNJzo}v9yWo6WfDU<- zrDwH`P&1pc- zihq0#bn*kbx(_`7-M(EjV1WCeADx@qtKAU&zkK5e*w{sl&>;J;LTkWR`u61fQWDvC z*C8jM{0J?*0SN3+9+~j>{(XB0ms)+fGXwx68n^&Qu6@0uLhEh)+H>T-C@?=>!U4M` zwsIPX22`=muAzi;5WBswTo?l@H?IgSH?%-t5NVZM z$}0PIW7Uy&c)2_%umHfr!XZP!0P<=8OOqo4du|>+cIaoh_-C!3u0VWx=taA}HY3O?t zcPU=@0C%sayHt-_p6i5&_P2g}em83T3JPjc3W=w+;lH?vi9()$-tQnGfZl=n_y8b4 zfPe+9(7nI3g|GqN+hBLO+A6`gNcNGxi#OLC-<2k@y_kLPt(1ms&Sg?`&dc3GcP<$kxr2nWC{ zKDFEf^$`JvreP0c+`XP#(J=O)J5>-DS-YPP=_2UeRJ$FVRc2M7Gkj!}}gH=c&Y^ zTL#Cdgd+^%h%HWrrgNfkO~@jfYp&-t@mz-`@0^%d<6gBY;t%2?iN^Nk3U-}u!0fjD zSX7-S@XJ5nEO!hnVk;3&)^n}ojj7`qeVW zp#|fpBwlAI!S|G~r%n>Srl=m)rHXHwR7w+kbBkjJ3&o^Y@v|~-bz(LziJ-G<4By2< z-21F7=cQXqx1exi{zuRR_Fi%7jw|d=X+FWV)k}d1w)~G_<#jy@6^)qx#n?H-=)y#6 zw{4xaZR50Uzir#LZQHhO+jjS9+qU(8qd&RH9o%_McBOVwse1NW*(JRy9155ABxYPw zEMbiYL#IFAjh+dyRA_9a-d|$t^OBR<2r#yCID`x9kS6kt$!ex%KL%1x;lTl*doouE zvnk=84+U*#K@>VnwzO0PHC>fUTpiWos#?un&AQ7E80zM+;jT=0y#>Og+uwEuV`Qjs z3>19}67@6y2boDn^pJ=d^iNewvF?}KZthq&#aVl~>_4Ip5@buMJ1eW6qM`RVA(8^< zqd-wO&Q!X8_+PRUQZ^x(2Gm|U95!O&;06@m)SakFjSk7EvyIr}@y67z$`kN|vOnHV zaaC1jD(1(slaF3O=;%~e9{xiTip0V1Px}BjWz_)~svV@r%l{T^JTY6wxQDW3bPgE8 zAQ&EyZK_dptkd)DHY%;WE+#YQX315T{$=IlFJXQ6$ZT?8QZW1B+=sJw#y0Rc(>G@= zf!XkI?DYILDJ_oIsvIJlS{44ds>RYNa+Gd-e?Kw(FaiexhW~&~5G0za<85G27VJiA zQk$3Sz?t+0s+ElYiea1zeVY{N$@X)U91ImIu4MhGL(!Hd{)_*a$ql{P^yPmzo#19iF12PGzSKOPPUGi}?fDNVulqg4Ak>ait7NTNMyt=t4RcGh zQWj7@u~-)5YGY&XXAOE}aNRVKxR!xriiNaz>~J^sG>QtMrlws71zQQ;SA$r|?V`J> z$@s8eHq)YKF*z7{VY?arM16?ZmwOIRNOxtb*wSRK1`A5wA zgG+}t?eHv12=&FtT>;I;AyHp8;`=oL6&K_C86C?T9(cDb=3kd3p={CgrQB0<8oHAC zBv1(Phwi@);fdo|O5L5y_=g%#P87U)d6-(gs#tRtDUA8GUzv3L#e1TM$O7iCgtcWY zdBfI;ohUA#u>w+W#qf|F(d*-(zgG!itrC-I4M2jPyKL9==Mx@fQN5REZpM~3co5d= zO|MaT?13hLkeQz(IilvYvH;~w%!=+_qvupz!Og+W7i^OF3h`2x~O?ns;aR~ zRaW6zVbmdygY7gBngY0qXq6re$g4Y}&bI^Yis?GwJ%cRn_o*K=Nl|Q^V=SK!Q}LC} z#QatNc}RB`t8mpT6jwErjGk4v-YGeX`8Ktvu|6d@>T=<;bz16&`DXGH%c{20r8q~~1*+G# za;|4bs9&^=`@~Xk<^K$!1XWH;lZ_^3$_jKEJUA7@zX9r2_miZr5*R9nK2{TdpcAi- zOw;N(q5sk6`_!Ho8z@V%bGv$Mr4;h8q=-oxFWz3`l*2Llz zoI9)fkr39rp2qwAvz&voP1+vN$~Z9k?ns?BFbYpQ5vbK8ZHtC&#t= z*4LTG`T)ad72>F0IJ34ciXEE`EKiLKJBUAkwwC4=kPx?-x|ku)e+U)X2SuIo;bAS5 z`z(+kL!&2^8utvCp^4oIDQ9D*Yl0lXm~pIpa8uResq;L+B5T#Qif8+m>62VXqeM5v zkan!*T}CKH%1(I~qOX_hTd(SH%CLd)7anr>31jOxs59mu8c&&vWODi4O?B%TzNyP=S9EbSg zgM&P#%mz}Fnj?`Gfk51_htH>`Yx%;K<9Ng|{by~H^Wo4K`xE&lVpV*rx@R0LTkRZf z>}_Yg0D$p4!+r?Rr7kKIN=?{YVxZX30CJMi>t4h$)RM@g^GUu6zXWGvV^)xu+wM1l z;rCz|!Ey)Aaekvk{${?-5f*m+PS*ZTf!p!PtiN&*toiTF=rda;YuWO(z3PMp%dl2y zha#W^lmHw0QW!M00vLA(=Om4UKp^xfP}< z)sKF7z&1An?h0fY-mUb1TsXaf#CykslmX9^l};{(csw2!=6`8_M@m?!$Z!?`!nWSl z90r&!;>4t=wl{0^aH}qb?WE5z&ORv_cC8+=5T_Y1i-k6w$*NL}79)X}KI>r9!{+Lp-#f_expOs5vnQoik-$Q+1?o z85Wa)I99OTQ0K(|9jdshw9@r8MoPLA?Oap~e(Hgrc~Ay2_$);2jg$22!UiAN*~e!K z8;J!M$@t)-KVoKm&Huy+?ml{0m}?B^lVMy|b#e^SAg$W_XlJ>wk%BH-WH7-wTbFJ4 zoE4#kqOX~j*a`(dXLi>mppKt&dwJ5SMCU23QEwkTBAGl;%2jb?;e&RV?|GCO3E?%lW*l8zrA(8?ABvC0A z3G=UMstRp)zm;W;z51MkoF=agmpsAwsv9~zg>Qx#N{Tp*!RA7VC6zT`*IADJVv$l}WkytX9A#sN-{9STpEdQ_Ucu;1%ZbM?-dLC?jz3^Yhxt}2kF_RN zaB+Y$&T@}EemmqGEN`*C>Yp!th_9O{afetOF z-N_r*nZ9FCyJ?KMqUdnf`F3W>{Y=mfTji~&-_~E}(Xy98z2jvI2UObBNmq0KqJN&B zAt)4H<2Cv!!pya@@f-%X2OdAo8<2EqlT=l4${BHqraUOKFq@dpb1GH8j;SDpfzMcw^e55o zYDUR{vou9`C-d~L84RqouaBjBV-Tz>Jimti;IJ}X^EkB(vadhMt`IHN!y@Rqc)hb( zm@TRW|B(};X>kHdovga`5Ncg&eb4_Hry7&^{{JOcEZibOq%dqdGW{u*m5pX_f0J;Uc;cpP#)m{)e)`A z?fTkO*rs8-BvKg*S7d5vOjPoX)u|pxE3c1!h)J5+sI+#+Kw);Ef-3&Sz^$J-_YQBh zm&Ccau=fjKmMdRD0icwZlw?M@*d>f@R`VjCL=4AtmYHGib>14XDhejG5nuwVm8(l( z`hcRIEIntNfs;#VE6Lck>=JyBFdsGTq7O*dRR4(L5$vMeo|*$HGe?R~?5AZTo&||l z6{W920Wi!Bh}uqHGkYGPXHm~~?8e{wTf&W#BZJq3ZECYjS?t5ydW!@a@N?i5Qg{gt zIH~*xR~S>gX8W9{8jtAP$zl?SO;qC$`7p^-7)qoe%(o1`AVymD+%Lsd)_RyC{&$Q> za5*4U#wxk$EvlZ+77j0D%+2x42+Nc?k>W`h0S6zar5doc!*TQsH_@Z9cqO+OP7S)` ztFDVmHkqDBloLM66bbkea5&)nU`p!w4KcSB za|KZ)HjdYky04Xc8)_8e6xW!fX^6uNPxp`Ow*ypwNw1|J7^=Ng&^wL?rqt+;YRjgk zV{;#GtO4CIdL0wriKMSejB$cL=x&~e**Kv>Sn&xn35xVy?g4Vq#(c_f`t>g447A2v z286dAmtnQDaiWm(2iaglC%388Fi*>(-Fn;=NUkE)A(zeh+qQ3Lh3 zJ{*j5+IZbPryu9p6yVQFnNSIOGWQewm8U{Pu{@%@l@Ia#6aZfc`CNRD7Gw;RV;$PM zwcpFViPf!hgSy3q$z_W2roW|yLos>TLr)QhRB>vi*9s?QL55GNi595shsTI;O!z%| z;V$--&=cWtD`Q@czLwR3138pz`b>vSHlRKzvI;E7h2tuPS?+BiR2oNsGP7?%!1yFE ziOoj4Jn}mQ0>U3tWxJ+FQ>32C6_R}Ttnd0&llX1E6)Qo2*F3^HL$(W^Yvm{HQJii~AZ}|&X2q^4pOYBcK%Z-% z6!np(8Cp5rblPL4_Z_0g#&SrNz(hd@DwiD`r8aaCrWD|Ys%&&hf#vTu(%cx%q~p=m zMGoq>GaiXt_vKlG>kj%b+GBpIkbB#Ozj3rNM`J`N)Q5E-!oPJP*fvKBMC5R7xqd;m zPX5;H+Lf_`#`z(veIqDA_Ya*%4mQ)S4(zpVK8i-%f^Q=h(_J zH)zb>E90InFFMQzQ8m%bNP_r7WX1H6#nB?ke}EM44j`XupY&5PUbo_np%d92A0j8n zL%P7a=F0p+BT>0_&(a>>tu_OD=FWcOUn7oZu?RHol+8L-i(D}@|9mESdipP7FHP9ipilY4+`AU!aeHz#P zsuFSw1<kLX;g)7LPOKqgNG6Q;`dUi^mjXTLe#Pjv6N!abkEU=E9{2 z`eLd2lfCQ_h!sSZdQVZ(`1lQghG2tWpS`j54RA15vRjl4ePR3TK1grh;AhM6n|bq) zl0#sVEAq~%gl$Ot!cJpa;UEC))z^n_1>gSrP(Ss}RL{1YI&NIe)&_Vq)|t}84wmDM zeo;Kx8qwsybtgC`5oFC9ihOM6OUl%h_s%q`S^{P{*a9e{_xZ(Y_{&Y%3o!DF$U+(h z$ScjFg{7jL9}@MbmqS*u!d}ibS`(nI#f=`dm0mpV7~S;N82_4&0eTyh%-_zld}#)M zmjRdCrQA>hGKLafB+Eo|B9(jJ3K^9~~smSW@d;94E_m)Unv2LuccrLL?AR z8qtOUi+k6!u14AU==h><$c}wTqqU-%lN#TcdQ#4m%&o|J{-o+|fAWz4&g%*L7K6xj zadAus5T5bhTuz?zs->ts*($2Z>XxeuHZZ{Ky}1`Z7bUG_!NT-@7`+Ny38<($&cB#d z44z1@S?~f?96m}BN3-#Pl#^iMbfAC4ct8AZSeOjljrFaS?phw=DeRQ~v(psV=jleQ zGTKM*r|{BvNUt+2JcC*@ZRw_^@$o3;t~mmJ77N{*fyEvhq5NaPZL5VHHG_JMq(FH2 zFIxTIT+1V?x><<;td*ADasXqt#>FW;f0{GGi;*h#)_F5IMhdQ#5-e@=-Ol=U1%Awy zuQ-QSvW*E%#YBNfu_x*L=(-A_%?@5)xzp0|X| zr^opRlSM^(@%?f`GCMQ=pw#YiLohWfTKGm^zG zGkCzl>bKEjj{L8|0$b;lg{45c+lTsuQUFnCaPgby0cQ4;q!su!aDr4Vvh1k;zUI}| zo(cgt%*hew(~7*+c5CwBi#fMas}R;EjXq0*Oaf7aWHc2$nk6<8K*)UI=_K~~8eDP{ZCrw9(??~t=ZBEtAvq^IkZ$+Kr|NRjq{2$c~@b!?po(V_GbJf+p-Qc*RdGn(TyJu z)rj464_}Piy#rHlvl{aAmf-~z4yIj%_?}h5-P6+Q>6LD`cq{lC((HtfnDPrug>KI^ zdF01(KG4TkW8%VZ!S;)>8EFM2i5j=82dIqOF_;UYwYf&t3@>u1J2w)bKVwe50MR#6 zBRcuAq}Pka62iJ68q>5w?rM&utx!`D3qDcz!a}QFmerXp$=L@ee$GApI%#HT`GPHc z0ajABjB{RCDA5`&r45O@+$@@kq9U3`WKe1xW)c&DU3s6^*9M0~zUtz27xkW3^HNo- zdgmD&O^o?N9TXex^ici~d?tP9H5RJyD$!Y+UM1ddQi*&o2)n^*ntZ6>XiRY0Ad8;r zluI}8YCw^fggpiAI1!jg(xs84M1RIUjQgV2nPFyj52_tlL`!MSZ_lqZHFEP5c977H z@;hmq%XJ;vbTK1+QP*z>wJ25oJ)lScGj4!vq;2v);!HZ zeWNLKks{`#O~dpGqQlZ+^@v{z^iK<`BA|#Eo|f(X+QtBeHO374KNR;F^RZLoCqDvW zsENF#wM>Ag0T|AwqG6t0V>^rx2tSggGOD$elTr9E-eiLU5<|1$Qz^Ic{@DDM%L}u& zm-+U)#l}H#TkAxW9Hd0Y^>VFO8!x#dIRKun&?#jS4zcvke--~X zIlYA8=epbog@QhkaU=B6$MaUHj@MC7uqW%Qf*AFRlUfe9UL2%^KWpvGn9~IhR#kP8 zn0NHrxm$K&8fzGc6ps7oP-I@uBeh|)+O!HMn=|ZA(-ss5bKcU7MpV&1XeOG}IHDTX z*vzGkM1#IM_62@Qq0CJnb@a!9pAD|&voBp{ERx&cWvdDm<4;I#n~G`Eccf$UH&RUo z=*bWd|IO*g(jB|Cu#&r_Y;ZL}!_A#iO7RnewJS**iR$*@$%*+zlxpd5aoyc4ESJsJ zkXOTb#zG>PttHvVI^x}sU=O9GoT#(X#5>u=lk^tJnJ?_BOTSt`!8PubL#J~g!LOmW zhO`@J*%pYxT0cRQn+jz~=Ct<2o5l$ql(lHL^;9zBtrS+v)JUWvx*6IanE}oN>sm?7 z^2!QcaZzR!pzV=K4ay}(?SLd=2yL_P8??YJh|gHSp*YU?lve1aP1tvFE-U>Jg3As0J)_KV zwU0!zkS&Zd{>N}PGh?c+^R`$-OcK++9Z_UfjXr{NkVq$uQt36IJ2 z1NXQU*jB@6P`SPk_Lrpay`{50C)dd`>1O(iJ8=JU;ajdkxjoan%A`$>1%9yRJkGgg zpJ-fEdDzx6M5_!@keeMSlOg8lKe+h4J{$Ilz%zrume_Vr^ zkeP{*>F@uR-e6|_%gX#e;v3Oz;PToU&GgZbh&PKIU~d1JRgko?%N*Qb(Fp|z+q=4w z_HJ&FdE5!xyJx4jBu{?)R=ieJp59aITKZb#ghfjWXDKaB?Ld+nAv+iwnH%nahtXEl zHGpVouViRxt;3a-u~q3?`~8N)l{Ez@%xJujb_pO300KrB^)iEN;MQg4h#=z~8zAcI zz}4E`)mz@Qv_Nd==sUkm&29&v5|~{Y8NjF+K#nhj`7FdK?L9$dNhu*EupBeLJRs(> z=Rnon-CJ;e9iSrD{s7g|Q9}R1hA6UmgzSaoHS~O2J4S{ni z0zzNY%m5Lb)kjo|$C`%*0wBnzsQ^)O0}1-!(0tkS1HGBC0jZMz^Bej;{HBRVJ7X|2 zQd08bhBS&VLmLOtw>5zUqm-s%>~L>q1d0|k?SqT4$+;f*8MPf%Z5<`o59*_4hmeS< z1c@Gi|5?gysz^!+iegD>O1Z8>&+rQYmeW8sCbzXSg9Pi~Ao;138=QnThr#cnc-*D1 z0&R4I^!Npxt`RUj>C0qva?$?>roq_>VnX)A1RRCrH%04D4+KC*N4M2=1)Bc@^u*X= z{DY=Dv;_Q?miU~8xfM{?7SsdUkGlmnzdDHv^&|A;%H|3RqMfZB(7WSD{S$?xp#f~F zT1pRuk{^Nwb?@d}k7@qH4nfeHlmaP`20qQJ3N%$W*C+R(@0qb4WX!zop*lp=(}?fj^?$v!95DLG zi`@Pp0=nj(5`=uSqb2iVvbIpv4YU+nDk#}HV+?}o_#wW);v^0Gh+FjcK}{netmG=$RyQ-}|_ z?lWq3Ol^Ds%B)cDNZ0(CN$oq%>}#F=2LqzZ&7_0Fo~17x5#u1!Q`^8xGk|d(U794w_#Rb#KSY;IHwZH#`GEzGny4n)(y7 z1~kpw_lMhGPu|zsi~ z*!T6o+kKb({!nnFSM<=Oga4B3@4b;Vd=@q9J?XQ3f(9yq_=y9xfqcn9sIuAHG8#nZ z(D}W7PK_;~b({7L`Hva>-~_@?|N8eOtM(<;{|4IjH8uVqe<6&%Pi^h2oX4H%gGTWa zwpZ=0*!xeIouBJNgMAwSr)qoy57=n@0uPAmKSF}VUC*iZv$T8`q1|=+il2aW1@?14 zhv9Ekecu}P&%XRB1Z6qA)j&Wx0rgP}{&MOf{PQdR<<&;8UqRTLn)!KkaPWuR*T1~@ z68EkjzSkQ^0NkEgBKCUxc!gK*MSL^KsouH!j_rMg_}ltT$Dvr?!1+3TWub4iG+pPR z>YIRLymAA-NtwDfID`BQklL5g-@N#7_#3tV01pVe{kI9QZoff{`gU>rgdE+c1V}te zb$xq&woFQD6nAhsKb~{`SfBiFb$aju`H=Id4i-B*$^65eY{lQLn#uDy4sP1^p_Xdg z8LHS7avk;V!Ly< zl{YF56C}K;02VPT-+5Tt%#ul_iS!|oFed}jP`@CDn|sff(`Pubf5Wg9+PJ)hw+?^3 z0$#ghThqHZ>slP)*-io8QeSTF!}I)1VrAt$BM6B{_88q!u&SRJyqaJz5>4`$e09u) zOnCJrDjF4{0hykbTViRw^*6>8AVTI)pG{C4OJU(MT|O@Yc~GFkb2W2 z|2FDcI;U&+QRp54t35!b3eL1~Aemj=1Q&R#p`o8xb~}EyJ$RPbJ2ww2^vE|Ti@QrF#geX~N7ZACs;J)_wni3P@75y@Dfq(Md=8umNYm;HUGj? z-kEyULJkBUhzL)|OxIGqw6uoqeZQ!i?H6$iS5$+c$qpnM=6w|iq|YV(6p9EU`nvc- z0fy&Ffm$~Zj;gj`}awPEUH!*fH<8*CaADr}_e zHeq^*V|Pq}_)o)7%{MtL8$+)Bm#5$bHxLu%P7-D=Gj9r?r$ksSn!fvE4hIx4nIhHj zu4vVT4#$}NzmPMZTtYxRtJB_tWiIV>v4~%b8)gDiW<6Uj)%n4Nrof)LTnMSyNrQ)2 z`$%MNcpb@1WxXU$%L5@Mp_EAO-Ks0gPxws|>12qg>jn4zotc&v>e*ntEhYFcBKqKf z*?IcogCjQ3F^UJVs^eri7lc*}(q{;x500w^0fKtpd8i_(UpphAT`SsDwQX^QW=l{5 zJIAtcZb;PNiAD4O8P6G?E^KvA;~ET_pgK)3RxSsIaCe}dmZ`tOKHE#>Ri+7esRZ1A z-_J=%D2e&TfMAhU(~|MsQ89qngt?kM%eqCKUkaz5Uak}2poIb7!NaetSPTlki4CT0 zNs4nwgchyWcSh*Zd+;cOaj2h$Gl1)m+nNxj>J{BNl{EkTPm%=e7yz?>Om*D@A5DhS44HlU%@5Lo(M)9rx-JUK<6h z=Bd83$)Wv~lkRK^Neta^3PWdE%ro|XdOQ;i-JaE%<1XIR z-%wD#2@K-y{k{Nh$wnO|N3No4!0uS|Mg>><;v0Ev-Q%u%S$j{lZqTG{r?|O;TKMEr zlq}nG=ZnX%gLE^K^c!p>6~@l&&{X1Pn{ccsNT=P1$Fkt{3>3J;;dm>tW>q%LrnHD+ z2bdzzQ|-;oL!z2DeI(@Fb0Ae>%&OfYZ{~m4G*~hGVWcFdRCIFj6B-p^s(}ZlHKiXHUpKncq65?;(XY6CKR8(QHDWCs|!Fw^JSWV>ouNF zx+E`m^1u_I4N=4mECV`F{@n-Y47&eS(n+DZ{*Sx+i6>_tPwpG$`c$FwvY>e0>$~G6 zjs@zUISo^@XUb(325+?@zb45mQS1J-U8`0s>2>qp2fA;_b|p00lp^z0mRHeoky;NY zG!FFi3BMP!HFvo(>AK^aM6<~G@(61BE0~l6fRjmjghlj`&6e5vou)^eE5V#f6JvKU zuz2raV!wzmkx0nBdj4A}k!t((#zGcjqxP$0 z#p)m^nI9J<)aG0V%cCt@o(#!UL7G-oD|*~bFY1P5y7FT$5{*xIR%6d|Ap;u%zyc5y z&r*H@a<&MQf>;s^1DRI#AN#L4a|>?Xv}){~w*sbUR<5W~;ZxG`YzNle!ut(E-NQ~z z0`)2Urh-3Dz|^v%;)n>M&un_2_w4*D*&hkuMW-D))}W2ql%uyxyYE=X>fx)JM(aOz zQyLPxskX7gN6RBsiU}AUpxozfdsMk1k<<$&W1aF#M*7m1_|W-+A_EmFri-&XEJo&M zhm_dlkiEAa`Id>L<>l;^g0(Flb#*UPNyd(dIB%j<^`q%(YD7)cMjI!bMW3)W9tF>} z7q`N9{w?J&g;CSkK9>{ZN55tjsR}wRm;)2;toNUguCCLP!v|lWt%Cnn65H|T+2u+Q zEy3#XLwt8HLsK;p{s+sJl{}D6F8s^RP*NSZ!r~HmRtUb2KAt*-!YqS8q$<_1ALh?9 zc#|-x-s>1$PPtRR`3d&>Y_X|*@g1s_vmN4@S>gb7eLS(Pe=)0_D&W!2!sklegci86 z*h~{BNiNvNK|Ci=msTz_ppDK=T1c^kxNRMmYG*}XU091&f;Em%h$7R8>v0ifO@5Pi zCJRhY_Fg6>0Ky|p9I>#$TFm!=%8cBX!|dy63)$oChUg8KW49O%VU_(K*}Mu8dJR)V zBeaT6auJ?g>og3wnY3`cRW@CztXiy!r&cDd_Ni=B`sg)H=<5{jM_2e+Njdz*Mg?ab ze?EwIVpj0%G3X6*qgoLkrK|}uj~xho&edT79$zz;A18I8jCuT-s{8AX4}-J)`%Gwp z(3c?1v1d(f`iOKCM=%23^5362B(t7d7b;eif_AEt|BMX^Fj+B)b)nO_`*W9Hd|CQ9 zlrD0xVa;!X=gf^riGEI1{Z}2`pZj3Uy&%^Phq7M90)7U716Kl5C{wCtCo`ftfgoqv z$o67|@_z=k$EIWQ3}~&EgYC)zJyPPgZB$SCev^xFct=WCSJ&*+-LTzbw}m+#LxdL5 ztuzwyu{o(Nw{OXOXt;=6b6>b`%OcbuX86(BwgS~X=u$JI`>_g!mm$sKoKvMfp&FOH z=o^03(^e0OZPK;c=^>mvrQ45UFv5N@9rNQ&PeGROLT~dFyeq@DLKW;KRjSw=7z>aP zQvOyfLp-8Idta{?%GfSaH4j@2DtAwoRF7kw0C0=AATIt-MmcBPfZl7?D3Nh+1@}J!-zzZ~mT{zHD7v!vpdc{0EYd*rt~_4mj7ar` ze32_UhL!pTM_c_Q)5ab6kDD+j!(#cAGQ>W^?79rl^~KX~%-H>xYZ(Kh78iyzlKn{5 zj75T_3Bc3wGUuPFuHOg9vu%i{tYo%<#4Ll;ywev8b#mezhulYrJL7|cVuhXd(mR=r zpIhv>If)l_dqIgTa)bi(S?USXBmBi{aRrQ@esnB`V|u$E|Q) z%g7ROMmzTfPui&QaenAov={V5q@ZD_NPMjsoC7%y& zH~tr>%T9Ns-hN2sf@*M>YKh?0VdG#C&J$zPoYzfp*RNvE?}R#6^*zLrj(5GWLO3E( zDLPs?9V|rXYkRCNZnEr;bH?FnzUlo(AFFt#g2Fc9}Pp9UtB&nSRZ=H z0TEh2gRXuL@0-E#-SD*_M!J$jG4fz&aCxfTzcX5^vRK(}DpDW^*{Y|4cd&z!eEcyt z@6u~G-EKwsHh??xD}|Q_v7UcSu^S5;tsT=c?nWEe*r_k6iGFVIbFX@ZrXpURo){p< zhW(fBG{gKW1B3t%S}=;cHh{hr=Aatd&I>r(2rTap-XXdtUKuP%h+83fkNU{UId{Z^ zvbxuoguk%-g|(5ym5HNd|@HiZE`4 zbeOl)w%~Z;y|OYJI%_UvsFn^eNH@+e!4aLanLTu7x$vo1hLSGt*F=iwldxur*o*;N7_V+IClYI3mHAoYuyiY1XqT{LZ=@}-by~Li- zEK(qxYX`+)b3(#pHAF%PTo*#9(!s+Ah(tBAywBq3Q&`K(X53SBgP_44fFvu5N+SlF zM2Kg1iALf|phd}kAXTJ_t+9DU@jHXvxcxDfoyS7GJv6qH=eSQ=l{g1Bh8K+p7Y~9# z7nf|4AH$ppSZc+yy-lET*XC8D%JC(w(IM|7&iu^edYN}}_4r8OtvR1F*+SWI#V@jC zRu=Gem?+(BI!Jm?_!i}Cb_;1;L@LL1m!K_qK3;b~Mi4LGde(1BQ^;iSzARj&;b8eI zdy<2%QhgG!X-EMEJz2ck3cPa?uHHc0Q#$+%bU18@Y-5f)|?#Y*U;6Sl=M11*`jZs&1 z*2HbiXkMM@di*yT;N`MeKdkw7w-NF_M7#KC`gGRjG%On%j{OftzI{I^IKB=P_dD04 z0=$ll?B2(LptyHD;~;0DaKJgL`HPj`3`@KBvtI#cI<`9LFvFawtHXRg6rnT4%0u9F z127jCThVlA0f$G?ENmE&x9Z)nFl9N^2T|$6Wf7aWAopyrQqUoEp zw~|BW=o6r}J9d~7H-;#9yAsd9s5UyfV-2|q~^IqyKoF^3|S%649|jUA&@ zP_Ep%)I6{{mROv`JS%;GQ+guuD*norWBw6a_Tc7yX!hBI^6qn9t>^c5?SlcB8yb=@ zM%zv_AIe*QGETDLRBZ_HLg^DewF62ngN3&YKRSBOi4g`;f!L*Llw={gv@cr9^u(nL z#d!c9Ckcu8)csoHTb>bNVC1d^zjlWJ*<(Cv>-qZe)xF29bQ|iE+5`jj1UG3K#53q3 zM$?4mt9JO3nc4x9M5^2)?=*NhK*1o=lkpb#LuN+;N?%z|X2m8s*{k!#WxPYVeZ{7@ zW>?^r=|Gm}ND**UdGEY_^gCjHrTbULOSXe-Ds4Xi9qMFq_Ip9 z%#(3<$E%h#EmclvyU!vFySd$WAIW#BboV=>y_Wx%Srp=l38k{7T_`#0YhLT1CliPzYbwcbw|^z)(bk|p2)^!Wv&#Lk zJMoF?%#Hy?4)G~nI>e4FE-G;zBBR$X!3FRV- znKxdzlwlM0cViJEt|6M}jYX2mEG==WMm0x37?L;85WG%t{}Fb~ec`;<9(x#U=J{TB zE~gK*HY2rpkO%aeFP6o%_ATN?CHH0 zB7Xi7UMRsK=h#!>+ACA0bVA;Q;P3uxzIiN>Ngt^S!7)t>n;^eNfu(Cgl-CID-|V6< z$4tOgaSQ%h%x!_*HpnWy$m=z2Rh1xrKieTf=F$&r=8f-cF)BZH5V8vse5s0Lv2IMF zW!e>D#(G1QJrv#%|?ZU3>pSmU3;#iV>o^O51qn_`((a0C?T)rq$D{>m|?dm?(OR zxj8PaY_W!RMc+^he4T}X`OFMHg}-)(I1qzE#iF`avqcUQ#ODd6!B=&xs1S=Da zC9Nt;Bi_fJa~E_-?67MqZU}O+4WB!En&uWeN??Mm{Yg8-vw9MKQtL2meX0abm8Uaz zG$_>WvQd|hX$DJj8i4sQF8*26xH-K4(ZeE6!}q=C6BV;gZqVM0dOi=y&tRr&z(=jr zvU-Vm#a~%_2EgqFukH5HQ~43r=0R~Zj2nh6+C;=`>aOJVzDEx7=-(be zU6Nkyi;uKG>d;LJj(|V#*#536@Q^DYWUSkT<2WXtUlcYbwTk3TKQ%BQe;U6-<{%3p zz*5>jA0$$$4rITS>8pw!3v8zAy)K?+HgqUEXVN)=l1YrS9I%*RlCaQ46#37&NhN>M z6%z+gF-zu_6tCBE)VNJw+T2ookfU}v^ z_~z!)`iDHzV)me55Jo8@C-3MIEAQ+|9t{^l%g!BbpaTvdhb0LpBaEx(9OvY4PQ=P; z_2y__`^o-@Sy)G@v!AkHuUGoY?=SpF!BKGSy%bPkUFZlq5;C*5_2^VUQ-kfyw&2>t z3K{9UAbz{EjUgt`J;3)2kCxjY%Y|bk8Zsf-fM73}vVDRw^9p68AXO*_a-G@i6yB zvo{0S7+rxxblRAN0mLUs;l?slx&qp-#w091HEi-wo_Je5lB~?;9MY)0VON2OEqwVT z)WCJa;5?9y0ppt^UjG>kh;_TUv!-U5S-0YMR`n)yt|a$TS4vxB`b1RsmJUi=*VlcW zex+3k1ALagjpLS$4#P#zbCm#XAIaz~rC<9~_O^bukj}Afn?5F;)WyRF-a(K3~61PC9$w>-jLK&SXYEP-le6ne`5s7 zK~+x0#3&7!z#(A#DO8JxJ1kFAwxi@ttoyrahP8@Os(Eln4m9HgUL{d0(+EXKjn@Z{ zyx#1e*I35{|2#TWP#IZA4g--3*31Pm9iVrcaN}~QLQkk$u8yD%&5Mx^m?XS7;YPcd zbx9j&B9njHSv3K>Q_PPTb^GrW*B`Fp0W%lwu^?)$PY{SdD zfMulF!C$w6CovxZs8lTETK{43dYR=T=aH%=;ailVLAXf;Xu7j(Je`?YLX~I`M)!+G zIY^DD5PW5w4t&6HE%u;d7A>f*O&e!XoyubMn%=I{bJ24ZrQ1|LSw)S37Bb>^S;9KMve2yLNgQule703R*Q^JS7j4NQvoGAGHO!US^dqtwbk!a{gL) z?$YbmYVs5MJxoh{P-FGp2zd4?(Ed55*&g!B8-hX7&ZHoC8vMv&OIDOxGWrGUB@?Uj zKdqr2_)jLbI;;dcg^g|*r9~TEHRDnJ-0dXBiuFfYZ7W0!{Ei@~*2o=&IvzQ7wy-ca znEk6vLjtOBk&yzlr|5vy1yl+kqSUu4uP8HymM$04u+%+t3Oz=fEwr;^OE1v8NB`m@ zaL&AK_9AsDufpRIv%;RLv2^i4NKp%mbJR2wd_Y$0fbvC4I>*Vm%sjX1+^H(#r#Kb0 zP$e#n;(ZN7f#l|3({>8S5-!V(tRfY`zv^Ri44Nb4KY43-G z57H#k-|xOIkGq@LZQ)dwE>@z|7)%U{aqNVL?RamBcFxyE2L z_w9V&2bW;sa6Gk78u|sSCKENj9}CK1I=!l5e6v$#CH~xWxu1jH-q6OThd(X^>PZ#9 zJ#hjTiDJ=Y{`=3VWln}S+DU08uS@=NSzrNaK%Ek2rDtV8XDX_CZ;4qw=?W75m(to@ z%-JH3C0q&5fNE6My)S@z7p-(mR!e<8SXpsSEj)ID0^bho@4t^;VA818HgvVZX!ILs zm>By|4o6Evs8dQGiYsMw#N|9yU@yc~T|on(XEJ;j=&B1-I*eO z){8RIgeQicgtD>>&23>E!r#3FyA!-rA45L_?bk%-f={W(WgQWJ`qDv|3fQ^G&W9p)wO|O{ z233qa_*I)>teB*HJ#`EqtscAY{q5hYJq{6?KIRi$7#=?=%R^)Hi9`HJ$(|=gxjX`F z28hD_1xQ!!T`Kh#nDp(4`L7SHxs0d>kC1gP+!w5=NQE*~;%gq7&AK$3lD1wok;j+R zHJ=h^8;4W2SRv;&3A7ucqW+#s6OgLXa>9Z{#5qx25OfDs<|(DLENrxa%J3GQfvEo1 z8=DISOu;tPc3Z`W@f+0FPo;5t)3vsGDWp6G$25GBb=660HPy}cZ_1T$R9-*j?-z19 zqW@&0L%r9Grov?ZBi@6%kwX6cS08*mtPB+oNe8s^}h?O<$KB2T~ z5uNVZQ$Oeo#rfue0jc93pLjj5$LSkCho1vs)YkLgz$vM;%j?E63Iy@F)=6)P=M(|p zP%r}5v-UnDRQ^@v)M@l=F4TkD$Y9K5w>f1J-rl<;a}~$OCNwjIVRF*duCZYOq8ZK^AyRWGq_soLIq@m-qlMswdh}SW-ALS;O*-omJK9 z8v2EjSj~f^2IiDpFA??XV_>ZR$Jjl@2&05u0&ae7+qP}nwr$(CZQHhO+qUiQ|IT8P znapOEwXUR6mAB4$2!lN>vO=a!%{Xa|7*dpuc`FiZcg9dEBN5RRq>ARGFI^bWORn0| zwxDR#+)rRMfp;}06hQ}|tL%(=U(xSrAH%kVLL=iwtv^t~!S{(P&q+NK?emTV zwG&{2C(Qq~OyfiLq(MXpvRe8U_Y4X-rcP1}vJV>8uB$`qs!)4Em>>3|{2mW{^{3Qn zfIs#X6~gIF{O+Fd@s;u`W>D%sH;@zEVDL#OlF_#x%eZQzo@gAXDApD~>W00eW@3x7 zRJnto3g(YbuBT6TNhp=voR&f@;=(B_2}^$UR-${a5*L4c{1$&l{@M_bnTy{He+9pp zHOhKgv#-K*-#dRj?X*CvKVltp$5!7;R7#9t>CSEEmOICR^mI^ibNqrbW4@KBl9js+^Hoyv0lqPY~1hNYsBYU&MJ*^5D8eu)qP4XyPiaU7dE zbMD?gB*h(zjebGE^9x<_^FA<`D`j$)r7`U`QnOgn!SijIgX{39+KT9+xW+VGMnSRL zM2Dob>Ts!(R6SX)ND|h<95C(=HE}-k4 z>6|3(VJZ=!pp=x|A#J#v*Tdrl{&&na$wTf`*iM%qN|bmY4vVo)&SY5JA@!zpSCtnC zTj7n~X-9FP)|c8vnbeN4s-mY(BY6qD0(I!Rr`(pb3k-09adkwMmyU7vE*_?E%%Z%G z7z5wY|9+H84-u^bGgGXumlqj33?bJ(HI>|s%0(4I{Kh;SDPk6BpHD<+QYDGg& zavV-c8Q;T37xeD~MZ+=&$`KqSRJh(hS*U%p%T?ycVQDtQT$bFY+*wu8PooY4j;TGX z7Bn(qEoy#&h5)atm+nc7=aN+d^*+RWI_n{eTlR8mRd3wuk6f)`j@NE3vq=Ht!avQT z8BS8OCP-letS;>9f`fw2+a~u0q5n^^HOi?k$w3-XX%%-x-=JL=U`{?Cm%wgYxM7ir(Kztcp9eJ?qqsmHsYysm2WK`;xpOHVA53q!6mjyVk8~t2 zBgbGOqwVA4p9s&Zo{COLTU8gd8%mJ$H3rbe8ab?+*m4F}#<`)q!V{E+3Zk3#|_!P}H3bDPYEP9#m^5Lb!)}OXY6ousN2vFs-Wd zA>4}shOacGFBexRJl(CrJ>|{l%<$6sc6VL{-7v19V?rC1D3Xwx@E81V!~tvs{$Bg0 zWyDMlMi!;?E*$0<$EROuQEJE|%A`orVXeQ6uo zksvoec$J(o$?0UK@Yu*Ta4K4~WUmd3LG4}aW%@f|>0^x#J*p&iTESYUw;2l!M0Z~+ z66_efpzDR~zz-14x(+Lsd0!Ns*smwU`aYnrn@%mc@Xv7?RT-}mCZvVIm&e&RNymh6`g3EbxUdU_)T=}|e|I{& zn3vn9A)k0L`r%4CHJU#N?L2G3SelxS7X3u2 z;j)N8)4)1!jZ;(ij%mX?W66Ybu+9DKz^`7^3eit*2B;Zw6O|yV+7iP(T=p1;%wUnLgLZ%YlI_RY^f+*M~HH+lNrT z6I>H$DLGq0x{Q7miHy=C5M*F<(^mM2Fukl!h^YN4!oAleH>uF7iBWKxsv05XalJKD z)cYCcgV_M0yL6JGsvM0|D3sHEZM9RxuKF3l?Tf~1Zt-iJs8GoR^lP@@R$(I0JjG*S zp%(|oJCj*0L05p}R5Hz?#K@3w>p6|tMU>LV6g?D$O~w)3v~F9I1L>qv9XwXBzh?@B zJ=qW^3xwCG+Rgg2bv5Rlk`jMJgnIA~GOD zg#4GIMHHfz-xrIX*4qYi1p2W~b#L_^10DI^K4(CY3#Q#1PI0VTE`$!{-B;ek@=BQK z`|_A&Oy;uQ^y3kzHtqq*O6oK1l?`Rf*WC9$?w)C2?ixo1f{7=ri}?AzEq7sAL>fYD ze)wi0x!Ru4h>>_pW;rg@q$SaH$Y;!Wq(By##54D;T3lF*b~L(G(|6v{9|B+3#t4N46Z$c%jV^ts{uM@p20)9A* zw3*^nivsxY+-ha{io&y6(KK3g0*2-ARwdpJ^qN8Kn`TlJm?mou?P)zO;>-t40CovV zbW!RL>S_uec^P>(e0Ul;h^Ak~zk8M-0XA`8OpL?wY%l$5_yP4)X^&~OGuln;ASV~C zPAM4;+9 z7ynplBGo+O zvoLc^bEBd{&kZnWr1IMt(Y3JQ8Po&2RVpHdRLn-TFG!+DhI9jaZHPqcLX41X6!rhehd9>b#w2Nrv2+>P3`)PN2I4?*fusQSjLQdIH8tsMZb1 zz?R!N{hbULKorcF*&9r@#;WrxW*cLYTEFmTRoC&yO}1%Kv8${&OOQ@ZpWnwA8&)Z~ zY!+QohM|LnYNQMJ2{TH`9mECAy=v3qpdDLSz0T&nfO5Ek%)@%?(&I$<*0R>qNqk#% zXa%MZ5Vv{>NwA&7Wkc>)g%eS1Zudp^ZKbAS@@tR8G=|u{cq}J_<3``&X9#Scmh{&) zwpSag)sC0J0m>>3p~lJEMGbYNf6?`>$K?|^5BNSV%!c)zy~)Tfp4$xjm%akxE55H) z1_jh$Zb?4gQtopl3>%z*tOv_z3%hKhbvex(z4hIO7QYv>3F|4?B9zi~2(&IiLnfy0 z`ggu_`$~t#5Jeo4o*342=03oR{38g4Qf^V-qkWPMl$R-!BFhL@njr6~m6ott9xCFD6 zzPXpUc49hB>on=R*ap-WyIGS*Bl<~xY@l%~W~CdG2p;kh}&laH2Q!NJE`g#Zq#)aoZXrLIhmW^aH}mI8EN3HRT4 zhuRn}vGPEL0dq2* z3Lr*9gGL}yS3@uFjTnQh+4;#SES+P&A7==ltBYUUleR|&M=x5n;9>^ak($8JxW^gb zQ*IQwPl0h826)yZu*Gd8h{d^;9+>6gO+*v-(Nge>d5Ue*$xNvm6{N=qweRJ4TJci>Y=`T)1MU2=ltTK?@(e198tk$}o;Uyq}LDbEL zSSwa=t!O5UUh>YKL;H3tDFA$2$+GVuQ{>hhi5r>qJnIIrx z7CC(k2mf30=~?aSWG}Kymrr}FjT9g6?$&t~UKcA=yj6JCzK_DGoq%k z5sedWlU_oM^!b!z&t+#|oL~GQ+VgO(lTP?pF*`IKOp(a&rYr5$r!_WtNl;>6HKHJI8~(riwhD z*3(7eUb*uD-crd)CYp06?CT#t#_GA0y2s#PBOTf-o3XEb9xIof9VJM=jMw6J*D&Pp z?4d<3N%5{ZB=k5~w<>JBstLtIIpZN3RPL%Iq{lTXU?1tXFEP5>0K-&-5?bmMRzw+% zKAIBD9sxZzs%Vtfcz2EE;)h$IyEOb|bT;pc-`^N13skMg`K~ zjk+==8u^5R)7_YL@kaw?NEiCx)6*;yVD?(7N6%oM$m?i&$XjfR?X4gFpmK!&@$4c z6u7jIa7VVs8q%QA&fLd*KVYMpgidG^{pjJ*N)p|kf~b23^bEJTO@u& zryot_J@QNxW7v*cn24!jR6shQd?){$YfT3GxxTa`ce|M*iACg7IW>?ka1TYg0xvLr-#I_`TGDSe86?XD0#++w2Y%=xkF*A+Ux3s98$qfm{P@n z8b?L1m1+iLZEnS)u?MaUVc8=(*GyN#*FG;^`(6asBEeuEK@=NGgk;Q ziLee>%OfN<1j~nAFKayYa)F1z?J2uqRV=m?R7c{WRMTh4S@q~>Rt(rw(P`?=zIzew zeVLBp6^G2TGk*J&$bTH}K7s~tMR$fz&6L*ALG7-J9%QA1_A|R)zgSE+TRBVU8xe!& zXOKI|2r7@7iyhWvEz|r)?k!N(dep8F3Ro;hl_eoJO%5SOCGCdl3?QdaMU)YtA1@VK z$X($r+nHL#MgB?bUGKZKS?)eo?HVa>Z{zum0!lnH+V6ytrut?kD-w}#lpQv`9;h(m= zYF`SIz7CvKfB8xXWZpZkCrM2B@)xbBn}KSX?;#8EQ?dT&T6CPN816=34ai#jDZx5m zWf!^g6AjET%_&2LtjeAv?pWnFC;X_yECpj|;&4jTe*q>-!O$r+#MDHRzDWB>O;85{ z`2u=BoMO&Rf+On~q`{n#T6qFRN5&ypHgRvA5+&&pfp~dGCWY2yL(C-xUct*~*-h^F zkvVw8Xyu56xxwoFgEaRestJCFHvJq-kMLXyKVCDf$VprkUw?Z_4E#9|WceOQSwVKG zMWTh+Wdf(H7{;y@*AcZz(%fm3I+b@0&o5gWw-Sup=Iu*z(wU-mPF6(PGpbK|ng52I zLN+15UeDm(#RjfLiG80s1|IE+Dn?XBg5z>dATCyrq;yX`5@FSl(XYmlvaBrrn0S5I zSv-m30;;f_T!RwHu67K)-M!iX$Vd;c7kGPO)?WY2XIidoTD&pR2$0?^}Q18c-7 zxpPRbK1MI)+uWqnmwD+!-lIcR)iUM_>D@ls{QAyMt##XKyUy*sl@~*Pb=NFF|IzbQrrtw-igTpq>Qz!t`kb+g1sc4vpW|xveJ%^9 zGL{Tj{)JqaKToI4?nY_5xq0D~RcGO#{2T!s1PozM^jCl?r{$vmr_V>5#VOI^l1j*^Dg7sj~Gdo)9P zQ=$)b^1%i7^oYzfy16?dLorBkVz*(aC~{_zk9ei6*IKG6<2h{C7}nh0t!A@|DfY&s;iewi0Mw9^J{1YbX63 zSFvHP{yr;tBm}CSJ|!_<+P^IBT32VwYx}A!9P!qMGH0mA<|q3pu2G+oFG~794nZ3QHjcE;>Xdk0AX>%9%-wzj4VIu#*&or{}NB0IhX|e??|+BCR)Ec zgd#;iYttX!>(OyqRGgqwP3*^=bMuR>j}RwBoDUnP$aUsWv%CudKTE45DMFb@sX zIo&?v#Yu7Rvb{3i$q=C&xoK!6nD7wNJK0a=q-oil@T`(-Zs-MC2XzOOmlf$we%YRw zgf*`Mg_nk8!6)8OAkUR~MytG@TJ#H>lFGP^K=pkP;9*F}d3}sSqkF@7rwr2P_g+=A z+z5>!*gNm4lYValzD*QZlUXNGDvZj<4f9k2uW`3EAm1ckmwFOa zsaM2@YujVMaU?dozB|g|o4xAxQc3HD3*Y3;ugYQ8{7L0kt=TLlXnXp2ofMW_H(G7) z-UE;rrUgQ;HX2}KWW$i6;52+fyZWx_HxRW3^1ZW`QM9%Cp9?qjl%afKF1k>_X#xExldyj{!g}>u; zmexW0bP*jCDLw!$0-`@Mhp0VE8ms$HwQP6pR3~tV|4?R%aMR}(L#E~~3bm5&=1dDm zDE`SQH5qrIR%me*sl=N@7DcY&aotWWPJ+qGm0`QWWOITBmRP(l9f>mTx;iVi5j->E zGV(PxWt8-cq&0-4E+#rbI<;Elskgu0R>Z8*S-w9upNo&AGqOJiR=#jUCJg%FCWbYh z)*0=kTctP@91g9FYjPqEgv?`2n&&HY+YE3LChQfQ8lrS9`MdW9Y+CnLpoy0qpIeNSl2`yYfIyvffRu3dZLwBwvDiJ&!0peoQz*2UDApl;iS4Uk; zZIVaYFtd5S7_@8N1tCeQAV12B9{SQry8*AR{HF=a4NBjpDvZcBnQElX{0zJPT|W%E zFwQHDg5Qu11u|iH?pe!KH668=auD0n`|(}WxlY3Q?ODlkOsxC!2l9dfdFl1~cqMpK zk1Q+la?0s`-^xDNDrE@8yr^^?9hm5Y`JOjn`t_~xs zkIp|b)P`s$Ab!?h-s?ri^syvy)LmARdW1 zy@|Hp{7=%^cy%%}7~^`bh9md|t<{w9IH3m6#2QAjA|B?Sr$#7TVd4g@o6zt*XVTPV z3oTantW@96SfHp6$*NCV+exJsM-xP>9R@u?d#)z@&*3K=M=&O;&VYxcDFb1|HV2h( z_M%%oK`F8&Nxv_qzB^m@l<9;9r-j-zJJP-82Gf{RGXi za-jjjebG6-VLtel91xR|-Rc4DW*(;^dz~Vbg=yg>=uClha-(F$VT2Kw|DVNUo z502!2AF>xsB`hkG%~BS+0;YtPjys`NLq(b8ezW%Cos!G2D*-5x=|nR=M^n0SB`D-I zoHLB%APszFH6g)D101=99Xg7&j-n)i4n8J05A92CyPR=0m&O~!@QbH3#r%^9y>f01D z+Ez3cQe{-(bpj|6TmX$>^}Al0F%oY5Evse(7pGFWdnUG(`F9^B%mQQdr=y|K63w*? zsWgSVvmslVlvL23x{iH)g;d(i5%_!&KReKF69Lb7t2$!oT={!fJ+@7=0gbyzMc;mB z315RG%__#;;@!C@!XMj36%cB**S*O?##!*KjmDl%o-e;7Lrvw=Xt>lE0hS2~yYNrP59K~w9YN*qjH0phte+6xq+W7F5U3Cx z8vKiRxL-KCFBrFCw>m)%50Y5Dd8)AddGN3~KlNY|5F11MyXmC5Is8wnqIP)=cfT{W z?R~x|Z#05MHFmUXqFJ2FKgG@JD=520?xLQ8AXN}(19W@@wr$viGtnWxQzXP0b^@cN zg)kX;BjYckDblTw=YhoRSuIMlpx_>G%e1A-M~Bd7j-R#RJIn8kS?K-o8-tT^Jh-an zA@4~6J#xtL9385~peV3!?aH9veMQ!;eHk|??jm6~eT!au2edppA|cur_4FNW-1ym zqKqpCKRhdqMI@}ZoKB1|VvPZxg2cI$7h~)K*Mpr~Fw!JuHk!}g6bg6WF%kwKEe`Pt zqOv@kxur;)1L(9Wo9>+f2&|p^$fCL|IkBg$kkDWHy(6F%y;^ku3fMhbY>%mh_EZ0~ z8ICAVrb?H-r#i{;;M8^$(Eu`J;pY6tnZTJK-Z6-{mQChGyGdim7vdhb{XA}eu9{0f z#U=%^&4J;+stWC`q%JoL>ZtW2m~6h&O$hKta$cCCZPga{DF+rK>NM*l%Q$2rp#*X7 z19nx_h&XsO1GQz|BBkwbz$Ta&61wFoTt@Fyj(YD?Z#Bw1RJ_S8d(j8@dw ziMkH_)r0>VjJRnwGGy)pKEo6vfhh!rb}3BVyS_3tV!#t`Ap?XfRl%RQ*~8gr$;^7m zlC1e^E3t{D;3RHR5`9l5|WcS4b88nRYQ7`r2x1~NQ;igC( zEZpMd;vt`oB4pMKKU>i`SluysTEbF45SFEzi)IYGI6fb*R?yc=B9v+2x#Pi7vQ0h? zXw8}PI*yC&582LNsfpYo%G-pUtsy$5!f+1`(Fj_01O8Wh*^>sJYH*EjVMtr743eMP z=oc2svx5^O!-ZbLI>d>Y_=j3Ggi8taXB!4{b6L7y;|z1d=*N5f^9ST6^iue8xQU z#3}vZGU(ps;A9Dc5D$@{P!ZjwdqHh3rsb`SxcwbT^xx5zC#w<0_dfDXDPh7>s#y-} zjA48S2Brai_~vF{C6g!!+Eo|xMILE7teQ6ZcvG4#*0U=fmo8EuDLCR}094s^(majS#u*2E&;Smv8RwsSZOa)Wa41DM8sP#1 zG3-rY2W`mdW$mLW9~T%BLsO7V)?4kWdH?lbnqT-eX;4q8(o^653fj^67)<+l)`MOh zSWfqUp(sV${L^Mym~W&OE_tj!K~6Xy07k!|i8d+C1I9UFi-RgTSV%_;$A}NG-X2Kn zlaenZJ8BW-yu1XITbl+>M`t`C6RD!{Q(#JSZ2X)lag{rF3l0*|EJ+6qszULoZeJ}quz)jx6VAdnd=1|V8qkZR{sPpj zWv<$@fcywD%F-m~Kb~OkKMmV`1O?Wud%=frFd)5-)f9t{CXy{MFbh-^WJP0mTX!PH zmQ^XBG2BBeyt)t!Zc5ye!b3v(A0U7oNn)l!}!rPSk!+1p-f)m@}hAS3mZ00{BW=zX(*miCH3; zp^JT4jA*ERffn!jYAU?hhjj3jY$zf@UEFjeF9H#oE^X+CWm}ac|~F+u3Sy#g*UuKQY%%x>r6(_;N?KO0UFq-oCX- z#X6jU8Mt*u`ZyW-RC*e5;K9#FtYE7A|C&$_v|+(>-fBBzkE6#m@tDj3LR4~C0{dB_ zK7`U`s;uEccsuso5FO0i z(*m?ao!GGzzp2YpmDR~gBb@Uz5YlR73#QEVp&0%`q*wS9Pv?^A^utE}NG}GG;D7$9 z6g_cZ>ZJN&Mouy#^(^*CO4fd8E#dTDyAa7r_5?q!JnAwljD1F?}4`Y_$FZtBs`%ld6;|)}W>7G6~1Pe0ekN+>b*+!pL%!%UUxp%%JG0@9$e7 z+T@fBerRmwZ=rZKf`b|BZ0<|Q6-~@RP1ai5l4u_Ll|rA11WVl?&IjA^UX zE4?&{&Ln%Q1$=?qMx;gxYIAUUmxS-eHlnyX-p<4pZ|K_@Lk>8I<6t?{YG)8J^McB& z#ap`@Qrwb4bt};<`WHShQ2mZ95(!AFlcLKp0Z4aJoxx(KGClImQ$}Pi`}G{nNA=oS z>68q)#+7WK=q7=fA9=Q4qI83e>KcrmOAkfa6tK-2c9)NnxJMjIQ+g}UHC7bT$-5p8 zPOsk#N1XgDNg9(24T}(DQMFEq-Hc!f*r~tVS@0q8ok=XpHF@M2t0y8Z9LKzmY zvX+x*ySnzqq#Wz`(Ej3UNyrHqKDEYi@PVIbOT-eax}K2U{3Fa7m_cu?NUtrbTWJbx zamqA$ToTgE{BpamG&e@Ai|S!LQjCk5CHHByTldp+8HS08sWRO~W3~3HW3#UK0O-4# z;I)T&9AP2w(yt+9sg8S6QtT~C=og}H88ZtWzvBfJbi2@XM7z6G|~l|I=JWh=0Ery?Xqn6hDr~JihDl(B;V) zjxm`uv(^MB-M!-OqZ;cgD0fhhf7cA{Ue)n%En?GH>6Gld^_cF36M!_8e`xW2a6wl*H&BOt&j-yaz4&pW0yTJbxDAUX~ z%DD?~LxG;T*(lg*e9nC`UGk5zy*sGOmh^HJL?3QJwed8=l>!KAW;Rk$#DKxMrs7gt zFBL2}`JNh55fDI#qQ#A9igH91ED9-HpcooRCO@JT#PNDCz%vA?r3EpFxwG;jZSDvY z=H>;8h>x?bz=kX^?`-TOPxwB~0B%spAiF0BFy|IfF>`Tg@I}ge@PGLf^9L8oeCwX= z&WOHjn>=_1MqyPiAN5J+>o0N5{P&p|obBG1>ig7N^pOJC83^V@H7S|j5 z%<()i~XaE7J-|5)_F(<8G)x;J`hoU1zXtUo}?0?U_}+f`P?0241srW#SCe@ zDJKVDX8FCw)?cIp7IH#t{g`W?al6Wk8XeqvRZGe?T_-_-w3mI%Q&3G zj^XnmZ=*9izugxnYtIUs4g3NZVr~-X;2-u)pC)xhdKcKF9?Pd(ChRXND9~X5xcAgU zU89^{_dVcsb-^hsf?T?$HNkZGNRU1y-89Y_YithyFgk%tvVVwd&WXp)cp5Uq@>_ud zbN;&`&=b;u0yd`jgias7ZA1kJKq4`Z>kvnJ!cCtFi{f&U{}HTuqTt)I{8CU*he*uc zRF4QhUwrH&biUVie0Ku?yzEdpW;^4DK1dG|PCc%>FyxnC-rFQGDP+9(rqBtSi+XRx zs#T%Y4Ic&^7c39WMRi*4+2X>Lul2FbK$f94czwMo%g?cECzSU8je7(eipLD65TF-0 z3ZXq9rE}P1d810Gf2|r+7LB3FwiyN_N2C*tT@VczB9{$YWPovgUpXa^Jm1((7W`7( zVQ4lS+T8koYl4~R|9@+O8U9!OFP*fBt(mhqBR(rD6U+Zz{h!7&8!H3r|5Xwk;|!|2 zY_&!w9^@>}l{pcglzZ3x zR_k(?+4B2zy%%eCXZH7MYO=a;meLZm;h(H8PfQmt#}9;GS3&j<9^QSN3?DyyZqgD! zRFL0K-dmLj9vd)JfaEt#7ZCKK^eT z0W>Y3eEloH79jHnfF(USc)%PboYPBa5Ds=ixz;Z)5W6)8AislyLhjxzfCd^owzU-u zsJSK)jsR^rmQ4)-fKNINdhqkF8hET&tax!12w&fSymMX)R3O|xH}~lY;Cm1v96(Qe z5b#^TM&NHsw0x5rpidoiJYK5)euU_E;H#nQgxpnocmPoT{#JZ)pp$*r7T^KE@-D#7 zN=yJ7HTdVahEY6V+e8nHLG$q^hb8xk1a zVzfjs{r`Am6LT1We)->3+*SSX7MRI>x5L%{cxN4dmdf6~N}=_^fm(48JRs-~6@tGy z`f@SV;LV94ZEb#eVxT`YUr2rSanzT~-S57wOXv^}L7%_un*n*QFFlg=j;=>6!2#P_ ze3g(sYI*oyzI0%42zXR@cz6^rAbwkb__P|LzqEfYL4F@pLNH4pYtkbd2>`_Uf!osJ zQ|m{40{rz^{BE86jo#`h{NjQ9-FYW(6U6Un#_C=E30d6$g}VQhh&`;}L>%^#LbCwQ z|FQZ2eKOT%;&at^P5D`=B&?QW#D{S5|2~E52P3XS8J7WzZgTz>OyX_dulfJC9r3Wx zfWIyB0Nwn60e_1HrIV`|EzI!byuYde@rq7s7u zdia*mH~hMN7|{D?L4)z+XaJSme*Qerv42&0gaE!i^+8cDbkA(~#IXBfHx+)yfB=0| zmR$S<_+H0+EkDs%HT03;%_KNIOP5;ROa>h#kc;mf4 zD#snDnZ}%NzG@m!$+{^t+CCQVCMgx{ta~v2p2#Y97ufcUtvu21&plv_S-)#{zM}(k z7%&&MR@9w#wnxI9AIImoyHa{AJtfb=220mm*eFGoA!;SZJd9wBrh}qLHT1TO<^-wRuhOFosF7yb(Ej-|+PWYRK0flW{zNJ2lnms~zr!)W(* zs7jE1YqDck{gY0?F=!HB%jQFZPnQh4DO-v?$P_Fwsgl{aZxwWHKYxGE(N0mgTcbsl z1s)q7RFLveG_2#ItKfL<^(?!0#%J$PNi8Jl>&*Ar?TLgF2+Le;9F7`=09 z537ce#l6~0RYJ5;I%k_PkJ$Z{UwDvzK@KQwB?I(dba%YwPFEX3;V@YIooQE&{2fS?QQU>XbGV6ICLxbzi8V1B9LxKXgq{p2+kO9k0(vrBavS5bs=%R7yt@9w<>s)G}kfh$ILOL*J#UtyC)BK$R zx(q3d9V%kqAuIICd5%*;pR)t;8`}vd*X8@`wI!#=^avw2~-T3 z$AWJjj+zq36V{_6cToBV*l2iQ&oue7n`+-FFrOn2P-><#J2Hj`SRd1`@#@)Hp+~pS zROZD9Fg&o)YtSN0$A5m|xw*o-aF3fz!dsV?E*6niJieF8`ds_kU;R3TfLe9QhOEqx z)$JDR!i(H5p25c}MLVf0ofN!MNUd%bPX^Br^&*@O!$)kvXF)nMHW4yc?UvwlWn!2!yC*Fhz(#P^guo&FWSvXh2DzlQbo0*$a zpP~)d)VyjuID!t~kF!N2J+!BHXlJJfEgt6^PugJvQCq|VDI*??`Fp#thHwvbk8XT`5Y-bLR zjb_@D<<&8ksOVx!ThGTI0NwyaqvB1g8X7ue1f3xtqEU+&)RI`Y3;UXU->2&s|_}GuCl}raZbV$t(#@ zZHiJ$n_1*v7`P{wjTV!^jFs7OLn&zfW3tQ)?j+(Kv96uswmigXJo;aK@2rJWGU&C5 zw)bGx_WOrMBz!%4rbU~wqz4JiOzN7bzCr4?#J{jW-HnZyJZh8E8xDK-(%Yse>gMU` z=Jw;LfxhHRkm|_Lgd1v1YVM455MV~98whQ?ALdvhHr^)c^xlT&Xc_>%JUw8u;B|rT zR9>Ex7?`@6X2+v#HK^aRh1c**DSV&l2W92X`lp%dx7GL#X8!XtKN#+Lj0hv_L>6b$ zoGeFB)Mg)WY1`yKRJ*$fZ~@g^Hdb>`BB0WafhNSDtHaIi(mfuaRKbR$nZi1BHiBid z7b(`vFJ+r)wEXWNp|yDoQ3Pp}kjOi`9MTOLPa)#Eaf^HQj#|U8YdlCu7Q1)hZ>p0u zO8_sUxJ$YGm2}M)L%sllQ`11GZ6TDN!eW+$PN2}h`sfqxoDU%uK@4A5H3)1&c2Fj1 z=+;a6Xb*I_0=CO%TkSdNVx#JBRa@-i_l9hE^2BpjRGiz)UOwwb4h93GVrj+t4S?O4 z9Eu#o+R!PK4D8RdZbXZGk0>*oMZ0sA`wr%Uiwr$(CZQaD9f~H|Rf5 z)8#V|@(&bq4^F+=X$@%9a+^3myCEmYj#q8YIvotBtSyFrjp*Y7YXpmy+XEzOS` z7^!t9N)9^?*H7|kfWhdM!S31HBoSjJtBx>3eIH&6SA?juLU_-BEYp!H^)KT2= zs-LTi6z5~A3W`vx^3-_z;BHV{_$Tz@a+!wuT9>9+%MGhUTi=T!Zc}mg3S;*6+i7>@ zwL`i}DuB8Rdv(u--)b0GuUewi{0oXp4?yN&G^AoWP=O=OePn_#5=r3V3P-Lfp;jy% zmqFnZ$%T}>esCXKUYpiAsz9O!hs5grpjJ4cUMTS-%@XW!294LHHE%R~QT9Cb+5bL0TcU_*~1YZ|L3@+Eg&7ft{Bo=e7-%uN+(b*q7 zHU7qZvknA(ups zR|j1~P8zh@Dw(#dQbjV-o)hQv73}U;BE9n)Or=w+s(wBa`=g49MN(D&M~RKC)B+I; zzqTzYPl+$>lR|*KsD$UFZY97+m3Gq-5y?M?*-@3Y5?P!kn_FxL2Aiky?)&4y)~>pF zVYonzKfY=h7y6 zXE&K+h^eK}a9N{rZip{;L#B3?i1c6d79fHVej^b*326mn;9>c=P zr^26^7v)1BqD8Qp1WM_Oy*Ex=Rwkq4Psxh}%s^R;4P=p1_=|)~mQUWstsy*dOd_Ai zb&_^+!o6UQplQSEJLtVDJp_03<$kP;@%b|Zq?BLC{~|W_R&U{a_PX26zF3`%cNG}MV_fj)IUp8kk8qUl<{kG>P0Lt z39mR&fEiZBx7;+~8;}&n$%Cf%yZ3YVb8)OO=Lb9Q(Q>wT#OsP7Hlkc_QpFEyX;akt zp*J7@Q@&hboew*#b88tVhr}WO-b?aWNamb;F}uwzArI!8YbpcLLkxOamSw#f=8o%r zv*JS>-mAroY_i%|wybir%T-RX47v;hKNhYjU|)C%JF&$5Ir-vQ(Lfs3DpCZsw%3%=;Ab4C_- zV(d~(nHJ+Zyh_^{L6GMT|cX8jjZ@>-Yt{~xw%&L%Q{fDi+uGEK|*N}BxU{p4N zTHGGF0SvRGY^U2(Ar{ZsKs?_hzn;C3qv!KMcodH5CI;Pu`nY=4hj8duO~1!TYihVgm${YPz;8w29MEF$&e$0mt@TtXYac}6+UrxSRdfwkXlY@)J8 zwIjzRv2KyH_Hc6ax*OZ4NTJ?dQ)yB_q6uJZ! ztl(?lXfs`)a`0nJ{9lFAm6A;pGbl!X4Hua2e3yjcx$U`a%_l9K&KSoCCO;~!7A_Zw zZh8skh5RcEr({F6^jNMQe_Fg0xYGoJ2`WQHk}1W$(mEl-!GWB+jdFf_OD=J6@r=rV zO#Jq>8u^1P@2k8dvz2w90*JRryQ$QgaNY+-oJdD*7tXyK#WD-DfTKQ97UDK;`gs%@ z)wkd+4lZ(Gx&fh8rTZIeaiQp6TeV9(0`1{xw$|! zpCY$PrIwys`-{d)&_xaBe+3M>blO6XAslz4=nI9wj8&I1{I#Ei9j0ar8P*gBtGLZ@ zZKr?_Y=tKV;S)=CC+t=RhBI6+cJ&xChj>sP367AC%x;1#=n_4cw4UxCn%EhZ+8+mS z0%tNkw?UcAO`R2#+<#B5)tT%Oj9zjH=};N;D7(|K>j%dNp5t?DzXri$yeNC9^_YP$ z@CC|c{E7kJyW67<{cy$@)k~|^n}sBYDC%|jJhhEj-QaP0R=y+-$Iq(_1N+6ZNj+v!*P@pR=V!|P-AzamFJ;6%x9?8fp{3)hTvYEEF8DW7LOE>3#uS59eTDaT782?dqO~X- z*XKzejz0|-pJ`1#xSVD(#oweS{68aqx+$``?Y%?%isV5(X(KOpEmbnJjnBUY?|3d@ zrGU!u3o3nRW#38ou?~;t^c5N&-qRuskfi&2hWDBIu73ywd+xzCnEF!4L;lGO9=4ZVG`3+=8F2FpDseAq1Niurx>a zDM};z9)_+B?8%vX{qQv}hcj(Mzk+YJbaOP`-DSio5h))uk?ZK-L1*oj zl1tK5QQ205ZZQDjDGHbRcw-x46G1eCO2E45&d3;Bj_8kzU+OApwTJ4o-|HlW+yvP( z@lFx(!+vzMP&(lJznIX#pv_Xn2wQ@|m~5j(0$r&qI8E`e<*|&{DodtN5OYSTY}U5l zWOt{r#=VX(scNANmJOC8xc{e&O=7o_8B5V|`UUbC+fYI*iuj$SI9^!19i!LF?8NL& z8yv#{#~LpTE7ros9kX02`^ny9p`9n1@p&*EFDkoQKjcV}Xs3AgFFRWawS6(eHb*E3 zu2@ZOioG=NLYaP857ue`+`jD$s#(pGbqj1f?oMVs~|$qK4Jdbj6L!A2%G4>q)h~cV{B;3L_aol z&kASvQXM-qBK^4Dyq;=gTYwQ)H<2ld%jzb?I4`)F6C+U!iy&4yJX|u)X>-8`%SO#8 zo}+*bZUd!fiXrUsEc44k?RcZbww6v}1%5)8AZ1m*PD&I?Jo#e?QRO}5?xr4io^60z zRp@mncR!-krWL?s&uG2K=VskW1w(QdEgT|2gQGq<9Ob#03geI^muQ)H^!F1pz}+=f zUQ4+|6Fw}WQm8%R%V`=4OD{^Z+_|A%Ew)E@5&tT1N@$LGHZ76&waihF1K+NJ#!eAcnid0_oC@-4 zN6H_DTkdpc?8@i@T94fn>uN}gig+Z?lq;sS-rRhX3vBAc4tarLxuxDJm1mAD+}4%G zeE_3eQ2C8K%AiB_kDN`l0wkF6_Jlo}0$3S$&UgBvogk*_f=++6>x$z$gTvqnk5)sQ znUo7IPZ7=p7mg`|e318LYQzYgoCL#hqQ~UKRx}I?Va1%Y?c3rS`o|HGBrDBQ(t7uv zM1f9$aDU_3b;&mF18-m{8CYZQ$zxGHaQuw{2c82=Ml5?@#lb+s1yJMzBa6P~92_z4 z=4dNjPqf+v!%MYViLYEi)YqoOhA!Ry90h)gSfgy5tu4aQ#UUkCq+N^t1#rJG=fR)h zB!7x(zD)_p@4Ncmy`rsSru0zj3Z_w`jA?&+o#=bA-^8v2&>J!K3CBTlS& zSwC~t8ty{`xJo4JQ}|3s4wmp}OBJI7APWg|)g@U##=!Uu7iaA@21fx_rh2=Tgac__ zSIgwwKkM!!FOcLFH}3Sn#Hy_ z>h9budw5%ueD+3oeBLhBWCdk%U%Qm0YH7Xv%43^4(wmL_HyrJiWY}N7EQWe0= zB%6~|GTrj8Qq?lN>v!Y0BOw;?SeO-rAF>t{9wXdco1eSfKfWJm?tC&Y4J2}U2@dD| z$=L6qWpgbr+!{NFyU1+Ag9$w1|EZHFFL7{eCmI&Zjij8h5-25!=MP#*ql3m1SenYY zVndpwjsZ1wEFJ zJZ!pJjcq0aO}8d`DL<@)T*bXS(Xvv$f}ufYrsZVK=JzaW?Pqa;^W92dk~#8IKh#?e zb&+F70^{ToT8^0Xn~}GuX!>?BJBEDo9iuz!Da0eQpZW05*v?j+@jv|iC3I8&wX_Zx zbWq;Fy-r^BwDS?zl6r2e^>t;(|6gG20m-_(v)X%(#HO_j zw{S)11?X`viebVWjbY?o@CLAjoRdZD@(4XyAc_8szz0J*&OV;;2KWMg`&M6TG_6nF z^S-ZrU-&;a%+3C=1jq5WRnrYZ6omwkbi8{67y)_8`YQ7i0zskf1B1NZXJq~mT_ECIY|!6DekZKt&Q;5$^-Bxnl;%1NBpoj#AJkdpdbc-KA;#;gPwjQpxB`yNf*Up($|)jk|B?;M}r+&(v8kQJcJYBf%qbDhF3t1 zVBb`k1!0fj-j%Tt@LBr%fiGXug$NA8pTIhVfhd6>z(w}$C^6jI>4wn)Ht`DTDuL(S z0{ef7t-r+fLB6K4*Va^Q1NUaQA;_YD@rX(HLt z#5=f!^(WeS^gSpCbPD&EJHMWOFX>Ql4x-$CzD~l!w6%PyhShYz))C=;EaMeb-h~GT z-TlOFh$H|B6_h6=5E1}ApaR{4@Z9}u_V;grKWx3>h_CDeu7VtZ*9#{D-b8K)%Mp0> zIT9ej0$g0f-#&lJ4)SSu`S}CrP-DQ>1+NPoy8R_21`xaYR?C07gnNKa1yjD>fco|8 z{P{EsP|czPhPr=ce|L=ZxImRPS;%Gu$bP3NDZ=kS-kctzLE6Pa1AzGX`H2GR>k0dR z^Br9T=LI~!!t1EF;eipqX>^ylzH=ML2>#T6VHyxfyjbcq3{37vW0!I zb!H)Imv=q-YpW&_F0+mg-Y7<$o_bG%`g~!)yDA5H3E8+7NY)SOSH8n?e6iUxQsNc` zI|To98Y<`s?)z^jh(Ndr?-1KjTK=#LDX=`v`Jx>dgxu5_9$}z@1nB4r?Ru2!{Zk79 z(&t}R*%a>fi^l4o0+k?Cqz6)o{Q=?$q1mk)eSih=5Td8Ag<=?2c2_}B7~SI}P=M;U z26g&I5Pah>uzs{h7C`KW6)}C4S4TaE3+?LqhWJUOUEf(jW9#Ts4Xr!|JOivjK<gZUkYyoBz!Pa<8GP_q9U4>3^CmU7)C4f6<~3;% z^7CH*9dLH%+<7f#<1}a0CdG>?<8G($oYG^y`)yhy6t;;eY{|ozi`pjPl3gq!X=WQ| zHI-t{>4!tVLfiCx=(sGMwAzw)LOMXCiL$JSPNPvBusBXUxy0P2t`;VDXp9~F(qaisA}iRC9% zt=&Y76H$268RVr+imBb;%{52r(e=KWv^kgaSZVinE$YY!T;xADw#Z+-LiW2&^!6^H zYgW|a2Hf?6An7I);dNTDWSpkiS}o50WlFGt)PMQOz<2?<`K~?4&uEHTZiH4qe0-K_ zu8OcQrzEb7ylg;4HM{1L0Jr3=!)6E>g!9B1Wiz4Nxm#MvS8w@?TY6+ zJbZs~Le#Q+Ud9B`48;73WZSj_CH?(XCP(tTOM$*kOl3_$9q-G@4WSn0YpIYv;rbZ{n;gptHOe$Q@|~WHwW!Pin4RnCSBz9e_~k;_ zZ^-ljCBh(0JC@<3Tu zaHsjaK{XEX0 zeBQ>bi|C$4wb2)J-QR5Nw+7#+VukC?Xxxe~j#?I%?$DEjmqI$)Ldm(K#;`fQvemw7 zUMsbykf<$tJ$zF1SX4|%x~g~ZZdLqlpn|3zX^d;aUA#7;Dk#VxHEW=o&dmihlsH%n z5mNn>c%kPBh1Q(+y~XNM%pY5dy%zIXK*S0CErBVi^lpuZ{**k|XN!b5Y|8SFuWa*p zXaM|ylS{#!tHqh|)wChbRef8_9pLwf{UHC72iDEwXGWSU^k95?y*$U?K<+(B+SMd9 zjUH<5*!P*icTLsvRSG(F(~;%&n7( zle(9^*hp3O3}4Utbi9Nf&E)KghI>~IWo}yC{t!kr>J-VHd#gOWu|Cjhs>yFhc< z#GBsuSK3BZLd7R%y&nUFNKXLy;-5s&%d^BESCy+9pB0M9v7PdvJA^S=Yi<~Lk5@h~ z6!IBZEq~g@HVZ~;jPYyJija`9?R1S5!&r51u2$UrMAk93;pP5w1C2^5U$s7pp1i|B zCIaefp>{#4j_RSa)4mFs6k_G#R9Xv9+5~jdy9&MGS~^_8n;LCoq{Ye^{7pdxaMZkS z-XR%GHx3o7zH@5Lxihkhi;5kLy$C94WbkkVb7bw%UQJCLCrjh5#~*b*5ou4mFSqK4 zvfV127PX-|GyMsTfD19D%l+j+c}6e#Y~XIO{PY5zRBwTCMt>-)Y&doqe}=_wRlY4kV**^izV? zb!nL1uVC06AGV6As}!GdnGiMenoBzhG(MMIj(9w6zN*NXRV8Y#rNW<+$9B?q?knt( zHQw0}%jPndopV<&C*K(|ep%|#_BxiWO@x8cjx|oD%sF~J>afhXbh7L)AVjfh-1WGiZp6ZDzn?;}zO%oQcp38pbOP_U;i z*>|PcR;^gvUTHNuX`;z+YV5>~W=xx}uW3V1MYH&c26@=D)4gP8Fyd$9| z*hP4jmF8!`{x&Q0t5Jk;KM%)uM)B2$q{eS&6;sZ>&~M3^gs+oOIS^m%(=5}nN!*dL zy}1z`?7Spbv4fdjfD7v0CTE4c7<4J(#MToeJb@;2Bh$6WlLL_8&+Av-HNYOFkqKfQ zm43trWd^uJw+a18{T5%G|L;Ee&quCJEDYkiGrGjapW6$^WDNY71DgxMe^#T+OY37* z&o71gg7w0pp^WY`t{g$_lOkC1eFbP2__(RHcwpM0S_uqqOeoCaI^pU#$4UlxuwnF0 z@H=ODs-YnEj2`3VjjZgC{>|4_-P?C17bAEqi7pFVU_mrFo*n05^-*!Ms?lV#^B={oTI(n^B{dGF`rXDGhju5Z}ligUBOU){Yf>`$+A#5p<~-lq#I@GtrRj3=f{`WWyqQak#a*lD}E%ihZNs7&G%x+w%OCK znr*-_DcTM1wOJm%Y%+2CP)obz`_z3qct7s>;0lgYN&2ZCHjRyB6K?7Gm&}j`GvA2w zm}Jbv5qUuJe9UP$Dq+LvMlFY0hDb+4HGFG5&k#H7fsLZo_{0DwAK( znlC5t5~tmIzNYly@mnKLh3nyx^FrSksMDg;ljIkd`V~a_Kr%4MwRd`#9KUFd&4O+j z3F^^%N1eJbAJZHM47-%*)p2FJaLyakoQLQGX;o<_oZF9)P~&Nyo-EP=B^oSayCd#3 zFJE<}yO9YLxcEo+fnmq#N!)xcBTftrc8d}jkL=!vwiq~-XU>J& z>xw`ieQI-KawDCts=IIZ{ptDm9&_P8&+y8{SS;tl6Ove@a=1^O%Qb#?m$vI9Tb)1# zgG=j1pxEbNOZhUdWy#vm2Z^7A@lHJFWYaBB9qfO-z<1Wdk*;LkAMhHK*WFU~bVa|6 zYbESCDe$#bQwnft{_@)v7?M14kx{;#G zoW!;VrOA+kSZD0xtMX~En4tMLildms?#bB`=R|k86z9Jh$h+wsTDM>YDmgocjk7{| zNrfaX#cCq=f}}COY>v^%)sC$ATCkcC+R76K%}g2#d0fK zf{+u$IQvXl98Hmpa{L=&Oi^lWvRyH)y^q|0-joZ@hP^#Wzh(Wm1=IY~3?SW!GI+u@SbWK_GSKG9Fw~VfG~Kcat1|u9X~?sohf+ z7}sTw9I7p`WpYy@rw2#z`gr*OGL#X+U1A@W&K+}eiE?m|lZwYus*7l-WNARAy~#zt zoEAo|{ZD9n7h0nEl|Q?J+TDnD`eUU{#PN#j;byK;xt-eRPn}+McIEuWT?wmQa~0fY zt4A2zm1dTlxiXT|L63nFwRd`LQN4?iDBX=y&=Ftmf>deKWHspq{x%0MDMp}guZvzm zb#M8R!mmu#KsUIu>#`LGvjYC>dcdH$>*($6i*Dq`)AIUN0nci@;@)JG&!bf}9>*1p z%<7MqdqZT9<1QpG6)fq-{Godz4OlMm_DTqN9wZ`wJ;$RO;Fb?w&VciIYBgI6BgsHI zoNAq?;e)|aicCRr?~#Eio)c->NEC-g{mS@mr&0lJ2@*fsS=sKwA1tIu8gQo9gfqfF z+EF;NT9sfjVVQis<;^h>^oMUDur@GDlFEJ}%OP%t5XUp7);tX?cU%ZtbFC8u(|YN| z;P2-1MJ|OoM)W&LGq%vVHxW2D744uTDbhzrS7Us8=l9WT*^=Ya;mqxIjQ-_F9shY* z$*ZSJ9G<>^vcDR`P7V6vYN+k}VhK^UHBeApa_C(hBo{ggdT{5teJnwUB?Gyl1UJgVaBoZ#=gHQvZ8G*^wio+Uq_ zrXL1!i+UeyiIp*q8GG;}g3a zr@ON={Ag6r(V`uj_?)QdXzWJvn<))pKYS$Ah7hMmbjuIcKRpMnHby`Ut~zem1}X$_ z3d0CoA^mw?d$J_0`kO`9L0MMhu+y-L&Tf}xTO9!?82MZ6eC50gRp~9FANjb6aX1le zTftXuB(pHoAiFeYPvAwYBRSV=!el}Pf6j}cmL$%bf$OkLguKI9VK#lyBA*!ThtI>* zUhItNPfl-MkzJshM|{_lEpnSD=o`V)jTcCB}n* z`^!0SSNI)rprXg`_`yGNrNm@bk#zj7<^XGg0KP zM7WJh#B=n>>&^8>Afmbv>vzd|4&w&=OZozft(vqR1WebA&Ri8}kjV@G%{6hRF+#Hb z>MwlKtIC{T4rXLEuU)Z(^tCf?`h*U_M6p89$hKw>C!1>J_ptKy(nAPRjSyqfwSuj^ zunF~g(UujX0{MrvtPWmOI*LgrAnV`e??nSs-K30bgyL?P(v8;w%5ZngN!5inJrREc zZY#dG^7G?5_whq%S0U|GYColwS&3NU)AR41{oc?k7azGW)!vT(XOA|&i0?Zy>|@ZbSfNR4L6O@|G19+ zUtIcRA$|fUVl~#@B6Y0*I5#d1U(3npscTwK@m?-;(({Vt%+6S%I{>v?e6_aHe_> zvSvKvi4=)$9;u;|R=R$jTbI2}-=I~FxSvcWmi?fWZ-?dh93d;seaL#ExW>Mtl9TPK zWyou1&F$WqP3W4I%}4dGVJ}nPKcaf}ZZ8f5;+OD;d7hIS@?^Fy+vj`DXD5vGD*aA2 zadW=I+E>h~J!g58^ajsyH{u=bXGX^>x#!Lg>l| zaC*Q?78kt?+!qLw=>6ID7@ZcWynPgn{;x0V^6B*$B*Gc~Ek>#(MjOSoHIB%Vp6R-Zr1WmUll*S;E1pglg(} zGkj#^?_$We?gZb#XGJMOBlaxA9xlLX0%lM`buFc6$-}v%Zcp6221O%a+XK7V!~W!K za{)Rrg}_c_Fa_i(joWb+HPJ+z>ps&{|dCBCXYD z+AE{WSebv3|Ghq3RmOL8a|xW+QZOs8|ITpZlH#XBid^=_)Wv#R%Ee>xf-cwogK)(A zS3A|toQ0J5+4%6X_Rhj|O-rfQZr8ziE$NTSrATe2nLLce*?sfcaEpT&YK$4XZAG4 zzUJV%f2OTBE{++XND~i`L+=O`;4DQ5PZRsgV!X1YsL#4~JrK~aU#$U-06Zk;W_y-B zr1VfLGCR?Y^X+qkivH58=VkYjqp^iRk^Gg^9196m+Dl^p*;$%X4N^rN)uTtQd8=Cu zQe~(s^vNhA#=E8-$Kj;c2DrD`(5hA7X2KA?_<-To^cXb`*w!^fdSH zG!d8^M}Ke7ZWUL*<3C)w-gcYzydlJOl9R*bX2Zc?y>UupEcBUnIbx0W?-Ut2KjluL z7&9VIHy-us3*~Dv%08>!&1CGmvW&_%Cazc_SC*oUa;2x$?d?3qk68C|Yq&DMkB_sa zVkq?z&=9j3dGapQ2X-aXqOokG1}u5Z{;-zoK^JWwA$9n)i8!|_pW9rXoi|MCQ>yNb zFuuw%Tze3yNKwe6S$s?&2G34&gl1!&m%A=s{A&VR{2BkU(x)9>dWRIts5_Zz=P(~X zezSKH7}JZ#VNAeFirA2V$gB;3uS!1|zOmNxqF=VVIx{}p4$t6<6)<`zdRciSXb+;K zWniROgD^FjnyW(IXJu(n61P+4Mb=!C0rb{8^zb_MC{qKTHmNvnSb$&q*`7-yf%}EX zdlqK(1*%Sr7o?4U19thcW4}RTsfU_U7H9Jc^9n37IcWT5?M)-~3S8}*krXa0kas!ur~~ zKE{A4xVTY51<8$HF$J+9A`RS9h=D^7FG^B{ttB){VhGg46tu)7@Zi8AgZk;d2+C$! zg+GU(0l?3Kg0`s0alj50Mccj$P!bfhcG>=XAfAOjf=F0cR0De#f~Fjt*ubHLfnJE! zDBFM9NKg-9SjB~q9I62VQg@R)h7GrkgM+)fyMz%q5Fx@m)OXMzJxCf91xUD{65a!b z{raGw0O9R@e{xXZ_5gA@sA+<2%#(oUuz~|Y-2JG4!9+}*FbZS{2~fvu(AXB2z>iyp zV}iz8f*`^>zy^?*An`B#E61lg5!iz}GZ>6mM~6s4FH|wfJn#Vw@pfY-Lb$=_wTQvK$$dFZJZR%!3KI1s`TnKHMU>1Ksv|PUyB#c*3<;;uk-lL7hXno! z<{E4egszV%E^dcIyaf*V6wD3rPvy9G4gZCY`U-MH0sH9sw;c%IPP88g1<82}xgQ_s zF%YQHOu;+<>ks+U0TK}bWC%rxZh_z~N(lU05f^*_@4wnUB|+j7uxgO=A{wx-pYJcQ zad-?aLZs{aEAs2xH+cD9)xY!u#Gm}fT}BN21oR0585A_sgp@RZn0OIckctY+U|(Pg zQxMUA3+R_Z9rhvsWb*3*-CgGQa{a0f$m2IF7~ySB%UzN4zm<~iU!;yd8X#~ZzL8)4 z(%t+i%b!T%a- z@o~Z(T)gZl($RvMgP9hS$W03q9}?ET5#R=P1m6V?!69mtFA+?94aoXy&Y%T`;1n=M z=mXGo&@sRCnR5CH=-Xc*AJ`*m`kpL&Aek%M=wjAUPmVOJIV7syD#=6)i9kFIuWQj8WRo~e26Wdn*g!=p57_+0u8OYm#!pksk(6+csL`lL(Qh(VsWI;b z+V!7>r`TLfuR~6H+U`Lg(rs`G81HFrDv&Gvt6|}jZI%gVfI38ql%S@Aj-lw4UX9cQ zoSyBSzPy-3+@PPksQy(GU0_`NuxvW{Q~boV$Tz)WH@xpyC5cG@qn|DV^H4u|P|K4s~h z?#6W&BB@R)fPG>(z|XO#XgIA$%n_0$EgZ(T61DjFUB;;?SeAbVZ&ti!GOiwzj3{nj zX`}HcDn62{f!1$QS3-}U4U!afg;nuBN*vuGxx5mD+V1oeA)zAXA=B+FOGrHFs@Dlp zt)T0Z|BtE4h1o*q!!5oYEu;bH_?Rz>cY7JFqT4s(E8qEU1as6J({Cmsy=#80{!JRFu5t@cUfI&?=Cb! zMn1ju5~Rtd-bOSP2V9rbiH3FAdI#ciCznTT7rLoQJKP)m5TL9G&xI6!=R`{;K%fM*Sx#PyB3%g{^DEjEO0yPF0UQR z&hsq!0T&Vdm%))rz^73=o|;6`M+$!PJi}Vg*&a9f9M^6{B(n#`c+h+9i=hgk7kb0E zM?nA(+S<`7wy}(^7&+Lxwkn`u_6naJfnMsjuGh>2+F!#|r25l%*8oGir32lyhGPOp$49 zYMuuowOd82^&MlP2N21W6Wg!PR3IuvDh?%W;^W*ow7>pg(zyjRlamC4DOi%agnU?(d?x`EG3wjwYxr1 zOhm9$hyWRqJ8WoNzC%~=aDRk5M>O!}49~kG2qqxfOvsv^{mk0*6C=M0Hf=|-t2+(Q za-bl%3hg+f zE&&_Uf-n5$+nRfh1OkH{R#@7QKwNxWq6L&cOiep707XL^nJd1{hmM(-=?uyTZ$%Yime zSQa(cAE|yJcG>8FaBd2Zuo3a3b89t%BhJ}Rh~CfVyeyZSrU{A1&&91unX|qpE*zkA zjcqHUr~PItZ~y5m$Q_DY8u|(bsgJM0t4cG;Rw#dDAqnP>E3v0CsJ!~Q5VxA7wO;Sq-G!XhYW=o{8T>2-RXpk47{>zO?#qtv`w8PB=fM)P zpJE363B+5p&PxlywnU@#Mu|#{R#%fxp-Z;r`{#c)$$W8lr&N~@$!d2_n}kcD#)>_8 zH|q4i*>SA4WSMF5m;$1y!o$6Yr}G(Sz1Zj4>#E)#Mp6k~tC2PCVogHKRPVPo<< z27j0WI)u(*bUZJx91~JD`iDj3JEgMbkSy0V1QPSI%8x0hHk^=>?b)cWQf>5(5w%@F z(7HB}72-x?jolf#k|FE3rgYHy4UVD@dbtjnF)dWFtE(H@Q0L~4zwSw0-p3w{RKgYv zDXmpcUTE5EZ;LlK^|k;DbBU)1h8!OS|4HRZ+qG+@8}+|(yxRTB*;PF~ApHDT`Lv8X z9z(L4+&leineEkM^#;60&v}~}hN-b1xZ_`{TwayJflE!~(g2)+-xZz5-hboNcXP?& z=!C{Ra{`@{&a^O3k)7J`Et5I8k#=%OeW;?1a}T=H*J#@!ds2H{S|YhL-Lp$y*jw~Y zBCPh}IZ35k!_C-0-Zs|-qdBrOSNUVIB-nRWa(Tu&6EI8?R^=}>1@5n%IRDly`R84=_B11VB z-1-O{fY$_fqlsNwzT~P9d(@htlFStno%}J!%9gW_ub_}Wt;mbPr6=&}?@=b!R3p^X zhNdpSy404wHt`YH%^|jbNE;Ry>o9ZsFz5Ye zW+c3~jWjB8BOIhjk{-n4+KOa2eZd6qOpibn?S`{+jP68l7{2LTindzVTkaTFKgfJs zg#wsH_3lN;tw?Eal*wW@@Nd!XEV=&lceP$f3mVBo*2!?3{Qy$CIq+fwvI@h z)z)V^iPw#}2r5)Q0h=FK98!vzN2*b9EErn)&Lu)kO*>aoNC8{C(P1{tCSoyi?()mD>;=uN7VvVK6_}aqwn{45|7ry{o|y< z^F+c6v-+T`G=W^(SIGFwC4BQ{u@ z@O|PUP~5$|E>x~25E6b0(S{#v8n^Jylkx6px&w^kyc>^HB61*W)ruKZpchXVha8Px z$Sxl{CW|my4=dk_$Riqr2W7{bBGxk<2P6t?OyXpL2`)1(kKf1BcQ4z`;{=rlv1;?? z6f@)5^+v*9^38u!NghCXp-^k}_A|E~^+4%rfxM*&VfsEO@)xucz!DC)c;cjfEXiyP z3Y+1Xf4;G|h{NN%;8R^O)E!FAChsPJxy&phoHzl(O3W?7_jUlWk- z=nZkGQM%^CE9+B7b%~MXG4m`q#Rud1!k4zw zHx?Y`myk~RN7~zrENRi^bmf{xU}H!5Apy}S3fz1RB-an;E7@In_!BBzQ~+miQWYX1j zhC?QPBD>Yg7^4<5xkt>=NW(bteV_|R_(DDI$|{GgwD)d4TwkXhUrumbyvch z`L}M-)^s`@t#l&M<)E>)v~48wd0L$RI}w6jD%+}2h`=R6^A?!w(S>B6r2*wHYS{5R zwcmG6CldoN2%F3iGj4i<{Ty&U&fF?I`m!whaT`SUtX&nakR0G&H0TB}m?90tLvfve zsW1QJvr0?`VDE^ffTtNx!`m+Zv9b~Eo$HilXvRF!81iizR+*2l>u{Zd0<@clO@?&SYE6zpsXcrBaeOHder!BlZ{=zj#;MDpX$$P1RGzk)97MR z+fiu1s1%f5AxUbo)+nO7NbUn(cZx*OH33*Z2abhvT}!Sgr3soWUNUwK{gkptd8q@2*7RAj1eYs9`N}f?>N92UByFw#<;cWl zx9IwegMlt@Pj>;A8P}l6k@+19Oo#=X{DG|u53DzDA}_GzL|Rcz!}O`GhY^6NJS87%s?J&V&C01a*Gs7u^ z98TC$>0E0t;%b?+O2Gz9b{uC3?m$1=tlUDMb)|j zP=$otn?(4IodN%>yksUECQL#i8oT#)OSSe3K`X_2a1iUl9lEOZA4b701FcIb8=a&8x1NeH%SP7Ew`Rn=VIpQk*g zWdu;TMJZiFBX@+~t`ygY4Ay?7Q_pu!y~F)p^xVH!*dhS~c{4BFqp`1q#eCH$P!8>; zN3UBHPQP$;zRb_Xr4>i4ufT#Ryh==F0)^KfY^DT^ikP|EdE(fqUF(z3%4k{uuDi=a zy=@~G#K3Q7>?PT|F^Z`nCW=Vw8@!+Y8gNLsMwRX*nY4s@V83clw{t+r=#l6MT?b(_ z(BpD_rD}O0*-?2huIFSnER$q9NK(iLZFJ?%%!ftvHzE;&^mb~Um-CeLo9ei1A}KrW zQeAiJ@1-J_(=%>mq$JXnH1?agyP~#Frw%-9EtNeRG>FK`UPNlo z;dDnGBUg>0!WfYWuhEBV8bgsL!NPP04lh zB|62>BOT7jq$M~s;D35_?Z!a+r&qx^FfF^u>&KY98$kUTuX{;&lD_}pP9O=z2ZtQV z^f!r%eZAH&5EYVu4mX?3R5x17(>E|eWqkH9Y&kh(X?p!kC#?1$A6m=Hz7+!%v;nGJ z><}xq=LZs`Fho92h)9u5qk6rK_z)@Pt%Ww7Sd*WW8{qctT4o}OZzt$HXYeI5V> z@GMmTs(xsD#GarU)OO!lg*U4IBU(Kn99Z&X-`7$)fijNgPxK4*z$XO9sFDxXc} zBHNoRsn_6L_tEK}?~aPMo^CoDC`;_q*7GBjI9fxH0v_i|s)qh}W4SsVla2%(e%^Z7 ze&<1UD~se)`1tR(k~>?qUzwT zAKfTexK`W7W5TOU5cZJ7QWbV3kibz;ArlzyQffT5^XJj^o1J#sPCgdDF_*Hp0LT#( zu>Xiub~d~}M}?;^Y#MF*dNaMmF?*-dgb?ge`%?WXRr>`iO7gC;mNHbkxv}`m`oelQ z=Q#=!JA+;he=LL3eMVV}zUsEgWJOU0Ot@rMBhQW3i^1#q9oAB-XvDzw9rt%;5xd9e zy$wy4ZjIDWM1ZoqEwyi+LxXblj>YZUc)< zW#T@>e>kQA-AP5g)8;c}yw7KYfxXn<{ss8AdsSNFdt{<(`qfwTvQYoypLXD#Q?y?x z#2t9~Hoszz(osq-3qP(e%H!SC6x>&Q=A!yfBA4ngEq#WBreMJebufieen1;&9Jxl@ z#>{hB9v|^ye3?Dgjz^%2WWGA?yzG&*MkP<@zJNo$^v(u8Z|uj4z|43dGkjN-&|Y4` zTX*fgAw^o5?T;78$%9wk=sijbj-X%Yy|P(gR5nh}5QcKv>MD&7dx;@O#%b|i;>Nk;2=3yn&Zj{0V73VvlswbT@sbB8w!}># z&Qm|1`Y4RP2CD@qSSvpK{Ppf|$g&mPAeY|zLSn?!DV~)Y^GQ2iU|Hwo5LQ5FG_Z^L zpO;|@Vf=K#%ty=JLW-d>}o@;Qi;t3(thaO{^vHL9kf1=*R1t=Cn>SqVd)Bnxk)Qt zjzb1>?GJL3`_8b|$0*+~rw88rz8uqsfnJmDMRB-&DO5^svbyVs(biJ(cX)KH2BpWR zo;xyJfJYV!EyOj{e=oDS%RKkVPH46H0!J5ntt+-Z`{zq+y$dysN}@t*7o>#&R9uv} zv0AnzEljtL3h7H%wA6OT-M=ZxrNM~KQ^pVkbBRf;H=3HULvM0jUZxxv_nTd>g`n`z z47C@;43}}aL7^qNe0QJ&|AK)8Y{dvx`$oq{Gz|dQ#g7)G>h`?l7Y4DF3FFG+nKHN4 z4Ve4`(u4^FH_8q}K*&Z~Gl*8A#SesWD(-0a#aCeOFV#us|2j+X3gH)NhTmL{W)$uC zr*t}4mCr#~ZxVbu$iP;<@7|bMVAHd zx=YIZ+5;9mQ-@sYcF>VbJAF7>erSKC{{B3tSCk=wj_+>_aqlt8rTgYh7W1^*^=Xs7 zec~qvx>x_-Eb{;ELlw5Sb1}7ZaVGc=pHw2Cmo+u9G!(M;AkhA|XCPqZWTj(bXCvTX zVWi{WB+wPLla{+-S4=DSo6jjqawUw_ zM?2LT>D}yCZ)dUgnKofJmCb+BsxfWuZVDv4mC>Mm zdLE{SjnLH@Q)3`#2Rmq!D;#6 zWireAn-(yDLczh^Y8DVOlhr{cHBJZuXP!?9)KyH8fu&mR`clEV)g`P0I?C}*TplmLvg_Vt0821#=^Gfxn1Y3W@T;4`RI8FQZYRoGL<7 z>A5C!44--k)`~1^Jb^Hr8ZP+a-;t9$z))ReA#ZKxaSVGZnI#d*_4XZ(Q5x^(z?* z2Iv?uw7z_ImsKF!5SgAZ?yp_Gm)bQ<_h1g#BlVP=d><(|_S_Pq;n}VC?uI97Qipw6 zhI$t}-9cog3ud>U0biUX^S_jZIB#3o(&_{vHfIxA3LO?~h7E%lg3b|tF;EGsllXo= z)KRcOGSjrmO`e9jbBei(K864M(NDRx8c~xa712VUM z&XxW-%ffnsR;Q`!A^p)H&SN~`Y3@h4thN?t8?ff59Xv_x<0R3(Q?UJofg6_nsJYzq zB3!Pup%v*JFrVKC=yhgQSEL_Js%e^-(Nui{K;oj=$=V6&imL5)vkpO;TeFyVKKcl7 z5fV6oh-h_g+mwee^`NiE+R|7XTL9``ZxuxBaO1^Qf#gG5u`GAhFPPZv@jur4snM*R zEJcMH>(p-VX*kIGIduy)Oo2f1R7L)*?Gv)c_^n5zfW~4uH`;AA-A?V))Uve`46wg2 zLfbot{oL!CgtvECSyO8-!=6)$wAk%DJwPi93~h7^WrEo5WdE$Wc87hF&Oy5h*^|Yj z0WVds)_mLkOF{PfhZzN;1!GcBl=ddUx}%X+R{S(Y*tp`N6nfl^xFLMA5uw)dV}ccZ zQ=qNgI^QN})g}lG2}!7lPig^w&=vA&T;Vjfy_Vt$zP(l#n$dYDZITXhJ*6wvya9|P zygm$?x-BXLAA(_?ygx`@o<`dtnt6824-zi(p8``q={xBc_y~PgK=Z^T47`VV%750N zPo#|SvRLuu(zk(XMRZ$7GaaH4JVF>lMx>bWjrE3sSPSE?8BY34A>=7WcNWPv z{(u=TU+I~47kTqUu?Q}7d*iX;(pCz2Z&_MWH>{o3`W2L)sHSezxnc@t#_JKF_R zD_*IH@MNwTc)T;~S&2L7rLfm^*?q}eqLjVX5?Iskhtl(J_gj7Lg^^iKJZN>ya+!Fw=@wUyqfwaw3cSD))a6hIQ-9&oU!S^ zoN)Jq9v@fyRa4KNXC!R*>uYX4wA#Z!IAd_T*yncEBPd432N6CV{lb*G#jDw}s(S}e z&m0UbXF(MA3HJQ}=P1ur#S`BW1quZ~Lrt^yFUujeyU-A8F%<617BGsetpPc-7|L@B zODu7Z$nokE;eS(}BH`AW(_OGLd4EKKA^O|H4C>@gwgR>lG+^aZ!$^G*Mi@}C&>_iA zEG-wG0+b7hqMBdf-j);+Vcxee*t_vNSX%D{ax=cwTRh_Ey( zkwt=FWWI70^{(yriy1_1^4EAO6W`MgNJ^~lw3-$?Hf%d#%Z$fKf~{@0qn-3MgR`o* z6~xD;^^eN2B^ggTdPdiLzr}6yZX8wzyttu#3oldj;;(R`dorfM&;fg2#UQTQ}DT(8=0`F=WG;1QTrTstsbZ6c5S9bBaoWz zCH*w(jUpvg?d*IU8p$))TmjvD*!=b4t&)k-Uc>KFS=O#H?Qa{(-rZxt7dsx4_i#r1 zq4+It4V=G!>fKg7Ucp_~#$vys-1*{S-papi+IjcmHxE8-TdQshw1Yx<5Wy_#C-@5U zfMSiy2l1g;82oJ|xX52K%KVIYFUE=R6$3+ngTXyXX2x=w-2WRpNmf&YeG5DBSX76y+0kxa)ngDT`` zqtV8Ix|3@hB5iGNZ`TBZVOd*Xy#oBj1p-MY_!|TUjkZN9;NT8KB5}u4J2jR2{#*50 zRo%;H{kda)Jt$CII!R{>-2g@@pksKog`-0Rpy`T9Y)1!xj!qAbjtNFaF&Ua;A&j~_W(-a-UZCz5vUzhq#abWy&Zr@M`z%dDMUaN zz)66m|i_&=o<&jRK#p)H?618?v(=RAL0z$rEw06RlN!B+llzy&%2iZ!q^C%ExEufQ&&|(x0fSZk+(0%q1a$U-YWlThJOgkyFhCa6B@P2V z1~!1X5N_a_eApivTnL4P6)=E&?yoL>cx;L_*pt8efNnp<;xqgM zJn@=4%W7x`2S84to&~>(`8XI*jh=a3^ryS&mq$?dZqL8yjlf+S8{hL`HRaglz0_;l z$R#wdZPQH<-~3G82r&J#!^5N$1Rww%zyf@1a5?@YbC0gT-<3x{!e3j$1%228;9ft%ude`JfdC8@

wi`BA@OXIonU+V!w72C$9bT}8j-A59o0ujqcg{uFEA z1{2RR{B{7V_Qj`ob>%fBFBi9Izcnd|fo}j`>+hfdS3F-j z0CskOd;xopgm-<17Jz^KSMTBVP1U&}1m5bL@=u@Yl6rnl03LUt2Y}vgHLw!QPl5oZ zehE7<(fQM-AHzR?GjIGmzkVCO;wgUBi+=4zq4H*C{4X+pncjZS0_hCQcl&7bGA|*$ zcYs{S9_iYD>M9A(>XuUjIW~Xlh#3HhzI006B1f0P}?de*r@Qa%O%51_0#JfBVhDoH~Di`N)I5upf9g`TDYc z75L4Aet@9>I1GQoW{dYjJcWM>{oG!EkbhPyY|?YOPZEWy7j{Kq|4!74{B{Dne`=U z75P8#+t`XkT1&0kcENcx$S!4WTZ{d(iSROLIMe=pJrpT6SWVu5_Hcn`fN&ME3B6S^ zq;Pme8CanrYQMixezH9Kt><|$^HcY(QxiZv+#iJT?)J;kv{+XU6S~~uRMIlR;3lP_ z{^@|9S*^a*{Q4T-U7{MVn*)|V@Z9~(wz(tOnt88LJHPjENuE#6Oi&`y+mDxJ{+Pt+ zRwdNDqo zY~^we2EnsS)7iiGiUA z?Z~K!d@_84NVJgM(za&BE6MZq_t{N7VzAkGO1z7ruz^}_ROYbqh8lSs%HE)PBhHb{ z3>N|W^fs-XOOQI@TE!`h1`p*6+E01Ot(k{}9d_v>dATySJAH*un%pRVBlp=Ab~iG~UdGu11Xn!-W6IA(TvgfAlr#2% zW3xRJ&YS5)NtdSR2ZrfUWLk-P)lD9OSwb-_FW$q`g&O8cph3sjh({^mljM(t`P|Qs z+QcNK8OF*0p*-TA`nstS$PC)_V#VN+O6dtoCvh>ac`at#lE2}7oqqMmz^jcIf+rq657Y2X5Ry; zlytk(d}&FgJL$k=4I?&-Sh8<5Q{#Em*Gx-%241TaLFfVu*#Vkbd=K!S%t{4b?fp8Y z{@5gqtyM(nGDzcolaIES=dEjaHx3Fj@N){CaEqYb$^fopG>@rUyd?>o`!g|1o$ghS zjq?p%@xtsUz=po^=exe@!jjS~`FC}!RL$?+!^=|znO8E4+6_&(xz7DW&PIL9r`~$E z3$?e5@Ib^WMOCv?iYxhzX7Z1l&tM|_*n9O>iR>6mj+y{ulS z<@ESMY>P-``XwI2k*q(b3IA#r)!QEeR&K+cl&*)PlPYQx9I12)Sbj6f4M8}I!*>U$ z&L79zLS~eN~_)XzddY8mPO$Qfq>0AM^G0@~? z)O^YaInk0g5O$bd4uP3a7O4wr9Vom_PXCmk;j8CuPbKW{HBcb?8!Iv%a;3+`zNQ6x z%*K`emfkJ1DD#L(CG!e2+d<1gPiW?!UE)kZ%3$EP#pOw@H%n~2CbyLX7sWgp+(_S; zY>9N~2x|jt^{#qnpVTxTriJ$oYm}c44u6jHmGJ7GJ#yB__Fh$8fjVzF4Q0 z{HLw#q%(!+PjfY!yGXoT&HbsTwhczziYt|1jn-r#Fgw&?bYNSTIWDKJei}z>kfZI@ z0ib-n#`x2hy#Zr5>@!heFt+|feK2NTj^b>b=1FpPunbLD*2EV1{Lg>*734qTwW;U8& zFYG-ZS$pJ_Q>9XwH0y};DAhu!$~*enW{x^ZS36+5rRjc^*yjd)6G*B2U1t-cSpBNR3k?68+iKp9CUqvs zh?Yo}TM%T1DOg)u0~0a@-p3J(p9p|^+g)*}1_?>`px}#1?|O;y#a%|HckyzUTH+D; ztX4$<7Eq_+vRd&d$m|vIt={=33zcc-jm7aIgdQ2!WOpM$V#3ku6j;V}$96^XE}Uu< zImCY~)UR{k>91>r<6Y^x8xzJdZWUsT%1HaXGX~H_sUBjjP+YjMe<(S_ssYx9*BSM0 z#6RFUZMI(pKGo}yZd2`KZ1yDx-la6p4swc|Ps@DMDR#gn8qH7J@K~b>)4yd|AvOlU zdkOY)rSl=901ME#sWmqA;d%*^Id2 zljb!%IveY_{I)yMdiVFt4iY=FfhKsa32G{+AXoJ!+8v_@I`URwNF>;H-HO%>bmw;C zxY5$JOEv{OXO+YC459^+O;<@WfUzi{IO|dXAiDN0EJr6clL)HvB_8e#yhE*}j0q|+ z*V@JkMql@d(uoTW0?Sl@5ckg$ex)uUUv_sDz*hARH1LPqBGF=A`)Gs=x33~oZ~5BW z2M?32$>>USO4nW35r)a5ufl4P5xyE9y1%l)f_{k2-h_^gFDs ztD&f=O~CX>?4Q}Jk}_pQO5`-NB*?IO#fCx%x%m~3DY6Y-+$gK`<(;fAo3yM;r~#XI z5azQ4LUyy+D;Fq|>u(gmoZA`Vhz{L_1>R$QUY)d9eM_N53(H|RT_-&m6JBfgaQ|G{tTy3>wHMkl zgs{jGGH84LV7ddVnjkdS@|Bg-yf-FWgwESB`+4%1H$mai0zpvoJ}m^1=6mMxmb`rv z=Lh1zdx6eV1RK6L+GQps6v$lx>8sWZ?ixaw5t(L%&aacucVWkS=&BEDC+-D9d;MJi z(gC60V)hTgA)^^x<9_mI{1kd7#(gf~J2~Dobge$yJqv7t%#{T>mCj_Pq#0;91eNWl_nOc*Pvfw2h8D};;|O1M(*o#XHA zRvAppYUK=NNrEh&TRJ)A2+fovxRrj68ljbWcjB%1L_q4^Wb-`1t_=^kR5@KeA25n0 zQqVh*@VBZkTjUNQ{)xpPZ%;_1z1#bf7<`&u(kA~^4HLMj5}2V3>Em_@HV}0rKxwmq z@!|cR!3h#dDt)ln;|ziaRX{oU>=_n^QBog~)%x)H$)F-98xH6cI5KK|Mba3?v34A` zCTKZBq|@`>Lr!m>!H;5nK3jwXInoVO)>Xdoj_~w3G6xf_xXLhY|0rn7bHd+}@ONj> zmLdg0t{Od|Zs6BZ_QJ;#jE|CTpUrIzF)q3b%Q0E3sl{eTHE*9QJw5+~u%KrDr5G>T z@!)>#pVwho)$4;u0qxR#A)XOzAX`F~Kew<(88Cb^F@;B_XOHR2?d5_@aM}mhP_d$y z%{*o`CpO%Fn_QI?5S%$%n+Eu-{bL&T293TJ*sGCZxY%_i!_XZ1Ev{&30A^60(HmOU zXgdlz-)v`M2qH)CQmhvzSC!kR7xBA2-&P#Zi8^gLYvhlEWHhbp6|deWpgiI6)KM|_ zIks5_yf7UWDA7f$xeY44HSREp?i@?(z{NAfL)v-*cP?%t?l|_p=6B@PLQ$L@HPlUP zxEC^P$R#3&)2z9`B1d|IEEuJLR! zNH#TGE{$Z|2z%i-PU=nD2e%HB-gK!t<>pe~&XK=o;G-c!fFRipap0svKU15L-rV0| z?kuD9B{m>%xz{oFT-Lq`lo_0n}aO>oVdz=ssB1lRw z>8w*^ex}ji4pe{F?o16&GHb5Zdk)Pe%_Dk^=pZxz0yW76ziinlN<|x_qiZ z;DplSHo%)##v&YQl9q`ZIMirr>93VCzC~TE%Gx=DA%Op53~on2le*Lf^S2cReNo} zMTAOZY)z7@pD(o)p2+P4?g^>xPA_qzU%!3gMFxRVnk;GJQnE^=1&9Rj5hj5SJ~8YS z6*vbeWa{$}eM39>HO3W|NXbrmROxO=GT8##zm6zWOHl>(U1V{l)c@SMJd6-0ET7#^ zvM(!*HvWOeW`Eo(pdoCqtGq7Bli4{j8eP%N+ZtPiIlmhS!a_cM@)MLq>)~aDK%%qK zUt(zu^?w(`XMalQ;S>x720+(HAg_GJ*Er%J89m)U3FUUOzJ7D5_2kPTmBDUljWaCt zT2$QExOht}&WiDDY`3?21HOT%ZKzZ5#BFtzUuk-6iD0`s68lj0Nze>YFqi*OP{urA z_Hs{do*wQM`WU$?GYUSrZXDir=JO{~Ij{bcRLrP(lcStUjGxzV{_Z-|O|51k!j&O1 zk?1YJTk5hFHC!!%!wP|}SeWFo99==`k(?yQE|psGST!u>-;|^zZ;zbE86VpDE~vLW z;Fej~ko|I+Y)2Dr^&9Rp0wDM*amzU@-e|w>?)iibHou4!n!B5qqiY7TzyXsf8FEhx~mGSu^bNW-gr6Zol=}q!ghg$>9 zjaG(S2i}`8K7r?n8oURoyib?@S_Gj;K1X6h0VKdD zI9LA^LDywS2I`4MYHL_x=us~_B9O@G0o*NY)LE=!MnOxq>{Opi`=hw0)tI(7hX+R= zhbL_>(r|#$$B-gDC>;B1g=lxcpc(ryz#PU4sAsUVvv3IqsA~)Vpx67aXig!KS*n;C zwt6-i@@nn_!@+v3-}Uy>=fz}*T)+bNV4V%f?6$;o?sGncN5-M&nqwFgu>5hYsvsG< zX_^a;7#NyB<$lsbU(IX2p{f6#WU!n_2cQfiV{yTeVz&5daaQ_)7i(kDu`xPk5dbHM ziA0DIojB*)6U5#YsaR{&M9TCfm0m^t2R9Ql!Eq0aMq9jy7xRI^e5yishiTTa^KGYk zv%>AfyV30Z$b&hnvT2UStrhl-bA>A$>iA1#T{y`$exd0=x}&E|Yf3C-37YU|Rdt|9 zd3uzP(R4_sf@r&|`Fxay!24cVg=Vug6$|}b`uk%g;E8B)pBjpgQeWS8+jthSyQx`{ zxUZZieNa>{KXlTfo=VoICEWZ3Ju<_<6J6^{_6@{Nk)tt|~4j8i)HHRUe`Dtf&`O z2jv*myUT}Vfy6BZaBjIxAR|IHq+R!b?WeW)I6Wy&lzQXS@LJ9T#9q#E+md6}svuLM zR1a1=%Y2cytxcqb#hz*}Dx#9pNF9eUtLxsH!=n@JYW8+eN@s*=K`ae93;1EcP~IMz6>pKWV@OuRv%=q z@Q2DUrphayIB(^leUD)db4fVLH^{21KTT?LJLHqy})mtjLP~ z&F7LoqfY0Vpq4UW{io)H5{}V8CMGxX5puw?8PI)63D$^rZiCWmqPGQFzU?mey|1EQ zYN~znrg>NuBcT^?>nfUWd=O)uIy{>Mhnt$L38{&YH42-3ub8JV^?xdejM)w`*V)$3 zS@tt@1=Ul&S~^AXyg-$%}_^E)Nvo37J)n9 z*=8jf-V4h`;gwx}S&n-##nnGh6M z2Gr47W7{SvJnB`x6o;Wfb8W`oy+x&Tso;adqB2%oyug6YOULAEshjGb#+!!s;fdp$ z+&J+fWu0dzZ>uU~r|^_SQg8IZg0fMse7c9VLM6g}aIvO>>bFWh;{TL*$=*pBK2#i3 zqe-VLbhA2C=u`TpZkj_uQ%!5}Nq=cT`k`Z@iz!}}Gx$9o_t{7H9cW z8=S9kIDZq({?T0qpO8j;gAx_CAU@WK>fqc~%m&XIcE!RVqFr&e-8YnlGU=xFEcHyA z67nP>Qse6dBYQe}AAcQ_sAhbD($9WXZ`A*-S6g7KA2){8vM?FNHsJgPo;V`-7!ETJ& z<}Ee&pgnf9KUl7u{{Xbho?aV!W z4fV#CeX-$9Ad^JX|AaYr>@s8pt5J#Vx1*o!$_(|K>^%0e*W(n-DNEOIP~8o(TwXg~ zjMR}2Df=MV4Cm=W_ycU!EqGVBxU`7B#S>&}RT>*%g{d?=KW~F~ru;oTcLb*$|G%N{gky)u2%IVJ%XsM#wN z_9)G0jCUeOqF}`#)LAad$U5M%3VMk_tDr7%_i5i9c4Qocw3}d-iv>J`#*cRfJg=~i z6%Ia5_gyO8;w)+B;x^t>p_dB&E<9X48cthm|N`5@0S_knu zwCoNCxB=djE%622N@s<@u{LsihQ5zQ$EuvAO3@R=uMV zcBZM%l7vwwld9*GX<79WQ03ezo{b|tZW2cD`Oc0`QH{QYmUYhw*M^DT`L9@*0$~%C zno_8uQlw%`#FmP(yl@eY4#d{jog=H>2QN4gN|9>4tYiz{;B zAeQ_4EVamT<3d?>PX2jsu;3fUqKPg!c{C&U?lRlv!wY%ja9m=RnWcs`H$BAC6P3mOG;{Hd@rFJ(g(cQrS;LYOo6h&F7E^_C#OYPWzs^Kgo@Wuxj z7qcU7&6LmC$T+5JRU`b-@!2f?5dB41MwSZFQ7`0gIIdXJ5PO=ev%lp zK~*g?0*J9lp8IDV)A!Cgc^=(`Cr68pkRpDahB$raqF76$Yo2v$w2Fl3>2rYCJM()dT|Cpx=5sR>-)u(I;X$;AUDexaD z&&orRFJBcKP@%J(XpnPuHVsoZRz~Q5Bh3cW9(=^tBdrqSs+Qm8&^;wa@^*Cl{2Cv& z%LCm<$jH2qAxzXOI2Oeu~J~aB$Un3he|XPjz<|LP{3}=Ib z@pRTY61(-76hw&z?wRV=T~|SSYipK6(oulF-w>WJ0u2a34Jn!)zQL-*S4FXD7U2<|`dYcgV3dwaB5bZBgjgO2jv{yZe92^7YH>Pw15C>Z@AoRMvc zjY`vs+V?=VUDR^1-VthGobES@5R7ko9j)hkYydN7uN6+XMlVdoGTWyJRTRwaO2Kv? z(&Jl2pj%^K<(>#|49J~x{Q(wyA$Q{zbVkQFhZDi8B=jDlRDVkF+A_Xnac+;cIl&ht zVp1Gi!#4T*4biASPV*h+3X*u6B|{tWoJ}n=E8Q2q3&q^3mCQHaCeuV?h9kPTkPkcb>2G*1*aCN+dMx!7)yRK6?QP-jB>f&#`8YqyRS|>PnML| zf*VzkSxD9^iJwuA?zV!xiE>UAAmK@bM$3MNzcs&Ag#cB*1I#z4iw6=PAV7;$fq_6 zH40njNc_^m#}d#URj>B%`2#ud2P)-tpMOJD>uMqL_KOT#{7eQQW0{E6?iw2wx-2fB zDELqq!5`B>@paV?VB^z|V8=U4+-4fqxJT{S9ouN5STbJGG0?yH9@{H~kk*hIupB4N zRL|o38m*hqT=i0B&@cz%y25fwp^n`BGWzg( zc558hkNO$1^4KM~{@Bhsnq9jUDyA6OqG1JwXmneq+Q_kQY35)7T~q&pE>$v%U%n-0 z%nf^d*Fk@Nq&FEi(Gee|HuOX5J4K6%yxo?D-83W7c|nQB?oE8wp3{=|=gx9%&GDSm zYOX$pmekd){Sp8uwQUuII+uQQrR3jyc(ZJ{^&4a(;-Y`c)aFtI?di~fPotIe=nbV3 z=gf+-T+wrp47HB2e+K^Ms+n|Lx^cAMcimVW91h%P9cqTLu8J{!fWDPU0%9Y`LEP|; zc4*P2rFWJ(f(!nm!jaJ<2xMV_xT?j?A6UHE?Rx!z&dkx8o1zO#-ndWUSVURj?b-$_ zHtUDfp#e?m&ZkdwNvZVSAf20GNuTY5oqSKkTK}tUTiOzSwH&`0r9K~o7FeFxOkYMI zOk`cn8EJ|Bt=UJ$A02CqTjj5Q3+Z9mGLg*i^K-PU*5!nCw`MrTqY4~(MKpRbT0Fw1 zB>4-jn`9N4cnrlEC}#DDzM!df-2)#3$vVH)=eSlkq!H?)@X$$*^Y0hhxq7DMXCjqc zM+AWFHrCfIbKO4#nA1JL9G*;f28!6^1N()7S=E+wLKT{BLdGQs-%(?RbHZW#e9Q)RPDxdb;vs6jQUJ<Yg}Af5jZvt|XVT z7*lM)^!6l8;z?BGUew1HjRPSIkFiVaUD}7YPlK&ehoRcHEL3Ta>{gO+=*GYM{e~(E zo>RE-x_2)f#^)x(*~Qy=Tf8bDs2!U7H@k7&b)rfSqoqW@grW9a5W`$8WqY=lZZ^NK zSe+3%g^%1=g5KBD6IcNU0!gEXj!8|l(&en}hxhIzo6x(u(;Rl%k{NBPODYsn!YcQr za-mTnN2V!*j*|1QJEXXDol%_v7g$N{9k;-mh>L%}`z#Ng4u;%sQ zc{N>`)DB>dL?WV~(kB$}%pwU@`fZqS6GO<%q`MX#F>e%*+GuA?3D^d%cJyib3}C69 z3-WF8-e`aoKYVnT?b-{JtHD}UYr_E1PQTg@1J-(s&@QIpi4bR$@F@%ZY4E_?OF;No z+;pft3HN7%{&-WJInCORr;VKI$L|qG<+RZ>EQeT$w+ZF5*Z{;n4?C0OmgNbR2KI*< zKWj_Mk~1mbMg=B5z7tw?$^-0rpvAUkPJV-t~z9OFteL6T58oS*G7 zu^6+}cN#kdb_1wl;n;Kf^Vm~(!Jq4w`5_Kb$Tm*v0fdf8x+x!Ysp(-%+(_E^__tDN z@$lD) zc<_rSPnW94rOOu6-c?{uLro-!%DiZL4&lXP4rx zeJ1qsOBBq?w_eWH_<(NSz>A{{QBA zRJxGs8>)>Sp`j(V^)AMW-X|!@CnX0pW-!%t5Eqma709wP?Xmc;62n@ST78J*ejOTQ zWwOv||6!Y5X4V+*GU|hWW=0@pPa7_L6KKSiQ_IrG zM+=H%#Z=|}qmAb06W!flSg7Q=Sh(XvU4#9yY~kriiPoVOl;LTPec|wyDa#rM^Lm|k zMvE$TDGfX62ctf@2`t(*YvDbT)0zt;M}4pjKBC9eq5@e;1XlrB9F5l}k*ZT3-luNv z8pmPVjBZ1CZL7NS?5KP7X}fxY@ABkubW`>gTUal!`B7Y+vN=Z{->rf579JvJ$|?%K zBGe9}7%SMZe)01JZ=^c~<|CmDn)T<(o2hR5?342^UW{lDFmRTk<87@&+#D0cItlF5 z47r<(nkkaR6f|&O@}{}rm=zGyweua7HIVO3bh-2uP#Cm1(U`0tVo@rdnoK%2uE8-I z$pk<<&bgWK*Yl0*s1o{LaJCyZsXY6;&f09Fc)hkdRHO(ArI4(?o%4jYC9QJO)<9hU z-TbNRP-Tj(-m;p#l&hJlf%}^LxIgjh?_{VsB*1GAj--xg{^Zg|8%Obep8iYOYDXR> z&r}?qLt*pj;)^|sOZ2zY>Y`p@CUWZ@T(9a=Up%9lmNC z$Aumu$W#AC+B*ej8ntcOv2EM7ZQJhHwr$&X(n&hD-LY-!iH+&EYG!KY|7PQ>`giY* zwRhLLYMsY*oLD@$wsl-ib|3dqy_~%IL6mj={#y{3HR~i?k+knbGf#A9$bQA{LM4XW zdsb+FGtxuW>snC>wfdDg57e0}bt+v;u;(98tF&n~E9jY{$7Qd!7o|F)IN!se{L0HZ zu0g@GNWio(G6PVMr}0#rONW z=l-y?EFXrCR&h(=2v_)>Jr3Y-`?zf(HcN;&3cOSt*9@5}+sO zC?)kY(5ROZcd_$X2p_5_?zLdG=8ZQ9_2TWBO4@m$w?Zu-h!hm$NJN4W^mEdR4Oh<7tlj8Gkd6O zt*~O+tJ2LyI^eGR6A(R;b_$pGev-eKcm z&d*Ija!93L+jCedloobQ_xSZ2M(=E;*MqkA%@cEV#0?RZm?9{ye(lV!_ri6!W~DZa z`WVU}W108DR7pJZ0^lJ3O^EG;rTkwBXtw`00nN(!e-O~@+$fp#ZyQ3fJ|#5lf)^#k{Tfj$;e4HKFP!59Qap`v_1a*lHCbr;@10TDO~4oE&VvgZV4~8b+JKC5 z2je2rM*{L=$0wS>rGyJC-tUW4!lZ*JKzs@%(Jy@V90bf10kMmV0--V9*7MO#;h#qj zf&7umFhmg#NE;|cGfApJ`~W*HYoDmOCRWuo^s#-5En`~=o%?rl4bOd+Sm|OgrLpm zaTjS1@Cs4)OFz(D{cK;s&A~PJSfRe}_kS#@#X1|K<>l2P0cbzG<)xu_5U){EKw_q3 zrFZV=DZoGpPS%kf>qg;kZ?jLicPPo@0vsT0f2%ZfGrfzx3(-|2q!&A z{|{lpW*`v});H|u&-LRj^$%yrPxbxJ{c8Yc>B;`VJ@3>H?{`3G5mjl-tRcuw69HHE zj~nwVwa^deGTxnqxf`-$Dda_8Nj4XiKLXl(yeDH!AbB8Blpq&MP57fkKYSur<|5(P ze;ldu*{~>aO#MbleFpTebVz4?#;PQ0mRJzqHdDhy$v~A| z|8x)_p<%U?8`kho{K#x8HWAfmBFw1N*8#o^ilHkg>cY^)@4$B1_BoQ5gvl)ZfZD zC;KK<^@8-#Gk5-jx8L!qOlZ#CpSJi1#6hPoq0;PvCWb6TL#M>!QktMkE{nsy_7hG0a1 zW!3&AYpH*XHoB^Y;&qhpT@;a%?n zN9_LEEvLo4uC=~(wo8eFhN+D6C%HLX{idKMZ&hYL@}^&>%c>&M z`H*l`^b%!Ww3Q}LWk(3^MgnRXJmj6d6Md`Z`H=;_+i-lG$6&sW9j1!p=3<9RFMO^t z(QKEk=wka`(Q&Qzo%wFsZp<3@>x0>0baum*m#k8jI}Inv-3vA5AI&*S)l>WL*Yf9f z^uf9G#*@0vrZ#O}U)!4@esvkP7M3v1z9bL{*kdE<6Nr5kGDW$p@YFzM{AsCobnURc>MRNGA zQ_F&ucy5lG=Qy9(Di{{N)3Pue&IVb##Id zA<_D@?QXpYCduo7PUe7xRQ{J7`#u3Wpkd69z7LkH)gmY<2{@whx@8Z^3Kj5kco61?5Uz z;5Xi$^;Bo+^I!V#P4`+uiqrMg`!wqv#Cmb3CVXl~>RHOszs-E#SOy}z)md?W=_S@S zi{X;P3&%C6@8!Ni`>A0vq7RJ3SdM9qyz36AuHSDwhqES3v*h%-*kciRUIr8Jzp1>? zC)iU+Mzk)JCD{KI2H24O+x%{nUTU;!k@4TwCsH6KtkcqyrKS|nZ`Z~#lkofIQBMIy ze`ZsNqTSm>R*n=on2@n(uJ}EiVvXi*C0^ZZYxQ+cMSK}*AKBARUsw$Fmv8i*I63;p zn|=Yp_ZN_b3+J_6@98{vzT58G3RO1&GI`(K_fv_S4B56DVNAhEyH8aCoZ4YgLObjq zyeu3sW~K}EHQ7^)tv$sVbFGG>GziL@!|~U2#5(a_(49d)J&xSMV5>Ut>+fv08ykiyN>K2Lf0Qae@L$_fQXV9 zv1p_49eblBR{JSki>%Q`_{sPI!=5H=!a#YbVy#x7G}L7Bhpd(Tn`YXn^sg zwm<|+1)O-Dx*PpW5Nm2@yP$UFRr!>}sY*n}Z0KX@P1s1}SdH#FgDFTX-y?W?bRyI! z&EdsR@O7P!Th=b`+%F>icXf(LEz@!JoDxG{kCz#p$0OV<>U|u@=qy8j`XOG&d>zxs_XFJme}@zLtu81E^t(BFn@lnfCfE^ifGY&`GUcIG}G>h>Uh8|`8# zq#|?VR9~A7Vg@OZe(h`)vjeu{XoD?y-l~H7g$2Mo1t#+um)=nyZ<2hxLX*$FigVcg zG^uF&pnBa-I-ag(Tf({W&S_{w+>`bZD~Ij84O`0<%cK8n`_mY)KT8kng4r0{Ah^L$ zwQns&Ml>_+c6RnlvQ+wO)_VL3dsd}@!)OZNf_ojh+pyck9zZCC?<&ndzY zIiL8kC|d7|A{T-{tyS9dZJmx`cvbO?OS-$36f2Qo0C`ehXMHB;t-yg7PWbGe^Y2~7 zidPE}5_K~$@^6*+@t7Z5>nAy;%+0HrX+cj^l8xzl@8g7GT()9hJ~S8(l5)^i`>OtS z5;Hj$ab=57$$$orPg~^aStl2y7il9|YF$@SmI?JdnK(L!xHf|xp?N@6_3{*DOaHQ$ z8j~s%jk@`qPLG>(QPh}i>K@Iya61Vq5?CjmG|!MJr*BP{os@0n+#Nb^5W>p3~9J}!?KwwTzB}|fN8`k`}l_3 z@a$Fb_BR{FzGNOfO;XxJ9?)%G#IHf(RpzNNR3&$2Hj#2|@Jr;Iw*bn*=EhA(R^ zV@$b^o+4|Ta|2FnA1@cAKT{(6LY`kBp!A4_S4o&@(>sL@KoSxGn(wE9=#U!M8u1&K zT5t8=gf2WJjM%d}zNu?`1#-OX0E@ok0KV596Sl9W^_v5Ts%Gx;N;{bizU2;cCWsvr zQpkPUKM(#H?FqlaPGq%T!R7rSvU z3V9S^CM=#I>B0jyD112_{bQ1Wsy~*$$D{GI9vFrFhnLg&*&%{2*pt>?!<|`yQP3r|q{o~P*QUjV1Bm$$pK*cwB-C zTUq@6Ktew*y3tG9=-ABum?q_G){mFVD=H-C8X%PdskaB#2HB_D%@}2@t%`hTjWk%h zpfa%=ZI}I-AAr-xkL^5?LGU6ZPHDGd8JwN3K@+0oF+8IK6BMe9f@+G=+^97 zViX@C;H-vK@CPIdaQ zjf%f7#my_Z(mCJ2=Mq_Ej{BI%VQIhfM9uaoOyEPrxn6JJu*OeAHMhyiFg{fI;fbLX zwX2_+p?pEA7YYaDBGfG1s^%*+RtMSS4@(OS;Jzq>9zp$StzkF@%#{@AHa4-HyzixS zuDzOry24l4weJy63Wfj{rPyi$l0oVATMFldve>v7RxORJ?b2gdS_hXD8^*KrPL1sX*R5 z_Nkj5fF)|34l&&!C**j^;*&Kc zLChplA(wv24r{c?{HzlPTDxilS#;7amM3Jl5~;I;4*<;vPR?$@=TbM|g)Q^-FzR?! zqS+ZNev-A8Hj~@fHmvBD%5($f6aiBTCXevJGogr4VrwhTbCbcy*!mKGd#dfR`_Bl8 zF6Tv#-u_(+7&ExuxExu7wL|vTBA`LjRI3%({?%4^yQ~Ua{?H_SY6tdgCo%dexwQO> zafOIesGO6#n^t+QMo~UuuCcOuU#^PAQYCC*VF+H_vV;SI6}zCCOW8!C8>G<0fD?w8 zLmvL}xW&Z;7aP~BLkNM?`rNqN^|@p|w?11*ORwJFE4;iSVCGEPGMsUh5`jwT{C754 zw>Wl9s=R}YdWf_nQv593m^SwHs!ZB=_apvoWRC??G@Lq z^ddUSV$8rYw9`~t)T7&Q;PV({HwS`d{yJJn6$mk}e{ zH>!Xj(l4i=uS#F_9P)!VN_Ik<1!wt*oT)L~iJG0?a%3gI4t-AuUOT9QF7V_woXuQq zY)X=+Gj=GLXU&KRepP=(mGLUNrI?Efcb9YVTu}yQq>0$a@4B@K!eXZ*me;n>a(z5V$XA>dW7J4q zMsLgtM|`igY%;L#m8WIj5V@=vl@@2nv0+LdxOO%*p^0b9&u^wxXjl7OkViJ4wmmJT zuJTw{ndNE5bHyO_wBOH=GO~lo&sum`oRG7)$1nft?n8YOLj~vfZ$Cl@BuVS`C}V$3 z3!Xf%8w#lTdid1oUr@{YB)b1)F$?hDI-@EvAE`)PaWYfF!u5VgxKbt{}7RovA)Byk6lHO2PUGJUf z;bWHSZ2QaXDkQI_f-ctF2f+bnjPsXnn^%gyecmdA5w~$nlPc?K%MRUC{rgvYRbwHo8EyOPh@UkRHOTTR zzaq!&XTGAeU8?K99M|Nr2Q6-vPF@w`JxnKquoulMfZNXCd?TLoBMQeMu8zNuZ-FAN zGNhl)3xK05`{&E<+aF7%A`eIBS^vQ31wklnHEnBKx(~J4Smc9)QXm-Z@RIay?sd2l zAf2#thwV6UG_~FhJ7x_go4=Qbnpzm3GqyUzflrU@0%H2JkzAx`D3OdWm*Hty#&g z&1L{%QrpeG^%?mELabH^11Mg<$p3od*>H3{a1jde}oy* z19`@kL7UakvzJ)S`@H0y)`KXr4cd#8AF|?>8z%kmS#Y$ET)TgMgY5$LBW%!Ub@7C) zm)l>DmSGgeQpC#bO8h^LKW;GvnjcCcDz!EX5<0S1?Ip~?nH69_8j-e~uPX_F@HpLW%zQh%1}Wk(6e$?F6K~(_rtqQ~!%6$o5CsPNw=a~0 zbtYvd|M;-)h5npW`a!a>ti2nv2=N|mNlJDWh6}u#v9vpVET}4Z+T29QQJVsjQ~IFPr3jFO^CWqlYQZ z*zuDu7n|f~`OfUN^;nBsC{v$Ixy|=Y)c2~$md_BI078NLB{l&u=0&BPLz@GvTl z&7UHOx@qbdB8}av;@4Rd(3_mm7#^>|_BEjs!~zfg$;#PQY32RXh@I3_h78qT#j8-& zqvy69do^K%JVy>#QSSCx$*Xa#{yNioCCv}p@4lPUC5P*q#`l3ZD+3)kt1Qp%EkQvS zl(}t+xRvQ!TCCt`#hIt3f*TCjK0%LfHe#ZiTX3C?vE?&9GmRVZ#*LR`oubx`VSj)l z=0_Fv<9Im^m$f_$mTsO}=viB0r_-)7H5?43(poAv|1|fz#2GZiR58>Y;be6;-gI9o zCX#TCHh40g4>SO=4lS5|>HoGjTZP{P3Ncs{asCd;km`ie%-;B0u^>45=Br3m3 zVoe`Ofpw|=bWZ1cXEM&M@swnR0;##amuFEs#(;8(G*nF}2~2VA;41!ST>s@TeVQ(c z;Z!ED<;pK+)7d$&L0h#8744p{yZt(_lAvFhWOj(w*L9O}Oh`jB-s9-VpG-4AIkn2T zbH>1HPvujqU-DSVP#FQZ^!V-(<(%25SYwl1_d8PXG!awX)ke~i&>_gN*zIsz}!kz=z#Zc93|QM!@o~SRZHb8 zb4J7}(vZhnrFnhmoA8?F_3!a2WU!NrdkhldUCWR1@n(7r{lr%M4%yM@OfBK{xFmY( z)C9GqNa5`*66|}&bthjPUU4ukV>55l*u%}j^rU+5z*)prB^&Dr{pRt}iix?ATfh@z zAq$`}C^)rC!Mgw+s07X5m0xk7G3CT(;}5B>V{@lXG6cf^cl`Nt&g?{IUeeTE1vg;d)gVF2z%5%p(E$!;KIVylqS7^Ik5Z0*LHY z84Tgty2ca0ZXzzaw(%AoxAnkt}J~{q<{QqV6WdBb-_wR)Nr{VKIr~fzXMMNyD z-2Zndw~R9pe>nQIV>nO(mN41E2tgqQvL*}>6x1L0x_1{u|EG(aGzvdDJO6I=bXlZY zDve5p6n7@d^zLqXvyEgXpC$L}5Fz4n7Xaw}3W|(1GHoDU|1v2jKgdGC!G@Tvxyo3- zbm?F?fgN3|^>XL*eYRpaqB8^xy_=|iJOTBayWR0rcx$98&OUFT(IPf5w22#J^u1ZU zI``>wn6*499@~Fkes#q%g*8lJppjCiRs^qcdhG7*e!av4U2~CQm%%w@QI95;vgz92 z_`jiB(0aZw3`MeL_3(_#Qy^i2+^noCdi?y`5-D!PM0qWDA9DyWqJc;iQZ7eYrGpv+ zg*T0aGH=KW@k{_$_;nC@k6@W1Vv?xDBO+=aaze)54E~NcXSugTg@;ukX9^okHoh#p zzhsUV#M20MA>@IWx0^s3B(AvOXA46;(I^h~yn+iQ9^J27u80FU1OmL-#uSgSJTiJm z&;%suHQXhXJXT8y4vmL1Z}R0H?n*FC4ZEkQ(@%Z5Ohk7VVAO*Y6ANa-=17{9C_Esj zA%C~+JJ1p1Yv>#K_Yw)TO&!%f+U(EfG$z&?H3kV?a;{<0NWRJI8-7il(l|WTw7Z zIk(1MLQ@-JrUt>fK2KL9Upv>>kDsA47j2)-5k9CC8JBrP915x>1MKpJaexP9;-=!8 z!u>qPQJ$#-s$*{FZJ?<@s)rS5HmJMnF7B(gPHZaF_d=P-+V66kH;D*M$&Q59BVILs zsmrX}_C2hs-w~kp(kJf&O+~q`e6=A#OPQu8Qn5XmV=rt8kUK^y0TBxKNJ|nHd3J4z z8gs@UrEU{FiT1}9W=}r68FuZ4384SSoR~zLFOUK-Ga3*W1(MiIJXQ#X(K2;L1s8mG3JzZ_YX zTtdZE1j0QRR!(#}w zF0Tg>A|hR6L5Zyi_KSrFjs$I(V{V1WtaY4BqO;GZ(Lans1r|RcEIDf}aOEIrg-Q@d z=QV1}s9drGSPkwHjk5(1T%^~?9ZI^bz+b#Nl!e=jxU?lPgWnkC+zJm(Y|l1uYzID# zJ-DzXH5VJqpJ^ftx{b5eBR6+S4O(R>AU)$ZnA`%(s?5*#D^`oL+BJv@9SJS!EI~z8 z{G9}Zmt7=vCQ%{Mu7MM+Aem)tt2ve;bp}g9Mh=DHl>>Js9&!P^YGa0{=(!mk_QW{* zw`SxD=Gxs_1GllK?HXQ?y!D_0f~`Eq*=mYCxWZ5@0lNXzqxshFSYTOY?6F6pdZdo4 zz|fr~7TfjGX|zd7Er=!3xr|3BLRL6?&RbHPp-~V$hjRaW-)KdrBU(28=o8m#tUQ;k zwi0ddd?9aJIR0IP;{Lwa&kGflM#y#)Plb9#Uq6P6V*H7MO1rDj4!>(8(bvnk57Vv5 z6&GOf<(fQ4&afUsav!ov>@LO8c)21mXV4zCw9rugIwupJuQ9A4vxv0A(f)c42=)oA z(QLj3VBP-8UgoVX)~K(U^v>)lnHrB{1-ew)lzjoi--B^IbL)*8H`%_M7|XZC-U-ky zplc+xY~nr89%(<5xHxo=2=nS(Vi8aI;{7hB$j=Xx_4fA(*RG%%e@7F%RV#4bI(-`n zWeE_}GSMRL32#cQ@r|k>G0O$k7Rwc{F_Jw@yU*QS{~phfPJA79I>!w)j->Z>FWuDs zyRjxpW=&)UA>N!j>K~3XghowlaG4q1!&L#U!S|sK7^)3dtN2#&p(!G>!-E zQGbRpBh|KjGjYLOZ*^{551x%%)4J&p9qt3hP%S7(vOBsk^8GWe0tN!$-N*%2wsVun zVWl)*J`t$vIAz&;0xvB>9g~6+9Bhe;0>X+*+tfOs^(&mfcj!z+f2t_~tJRwjpAh|8pmFi1{T3s;W_^E^u zs;CJe&yEXCh?*BKJr(f^NF$aP)$wAjNHX~+r*ksRBB};l*hK)Xpo&D4iyC_&bv8Bi zy~?Wa!O{#Y*d{lIk)_)u!+@s4FVTN=uC-^bnh|}R3ORl(&1&{=ds1=Uqq1W0PA;M* z0FR(4^1Z(ub(-|U&SEGKfZmHr@z`ui6aI1P$3t~tD^7?k+L0`@6OL~1zk|r$4yVph z1ferEW*#3N^3ti++79`%V`HiF z1IbxdQ1V}gLeBr*g!a!b$@-6*`kxThzXob1?*AuU#mU6_|FKJYfUBX}?sDcW#KDkC zjGf&i+bfA+ne>BkV1Y_-28Xf*6A?$c%0z|Aa7tAGFAx(E-zfk-yz*cCdjYusUS5l? zZ~Rq&M;T6&|qb(JRYntr$xzrV4fX&AY|si$kN)#R5~ayB=8{9@8d|JNsy%h0Vc`7 zUL+w%;0W&|pk*Wif2qtSSQyn~LrEaSP)s5cQd06;O1#1Y1o1&4BQ7DrSm&Tl6B?0z zdmvRXFbMItFH-P?ZdjOOVp_VZ%S&1?_ZJiqqC9jjaG+kMRM>v73vlswA$;JzF>tKF z?Vz@qYeB$zl9puqk3KKucD z11LGZHApxYP+lXvZ#D!7%W5pp{>-=U{2AEbP_M%7&~799K1#IjJcuS!`1TT9(^Q4+Y7q=XDgHlgc!&z%p^<(Vr)P} z3l#Ad4FUOX+b=+giiGM%h7bnEE1Y5Cnh0n#SyHO#Go6|y{bd=*4h71G40QH#x=X1G z*NTVi$l3SP{?nni|6$IffpPK~0P)=>t&Sc90R|Nv3=~|9LKGMo8H*(Z;{x?=fkDc2 z1z-^RiCPZlB?e*%V2@c}=)-w_`*`;Hrhs7FE9ihj!WtF<=KBF|hnE5Y8}R+tKt1%S zIQ|2_-PiOf2=u-CW$E43@%88aA7DqQ(ZD-34RGLvsNbQ2dwxR3g6RL*Tt<1v)PE|9 zXL5M?X|*ot$3m#=&)fd)5zEY=fP;5q3oasJ2oOGI?0Itt?ikopA`Qj7dIloNb;z9!g*EH&ybU zAO7P5P56A&W3QE(!0U8~!Li>}qYeS!1{>r#vH$$!S@m11xdK-9`C}bw!oL=5uP0HouLm5_oSHG1Bjlajd+kn1G)?1r{IMay00afE3T5B(n zcVt{45T#poSkf=B{MGf|C7H+JFO*B8HpB+=gJO4qi7HoT?FLxV?&-CwfZ#+6ulU;A&oQ%RrmZ0SkF+ zL5U2LR(Qe+dGv4nLnOKbswXo@qaw-~Oks37y^0D_` zSoW>FzrVo{(nG!C*MxoBsHz}EB|cr$hDSKXg;xwbqjGI;nI_=?{#GC%S1R+>wYQ z=n5eNnC~c1wZd@7({C4W|KS|^Iz3N0qJk)R<3MLTOJYwjkRFP`K$+!ZxIKoO3hjUI zX1WF}cF~i6NmQXtF>O-%21Mx?uCa}lc~Ieqe+_5BiqJIa$@hFEE}unw4V5_s4b2QLW2_Be&YyDjWAHuy?hL8c7ds6?@XGN>Un1l?bbe26c5dC)V9S7 z$m!IQg5S8&T?Ggl1$-`iFqiZKRqu}``Syev^ep=kesBLuHPpV}OZ!9L z^p$g@(oNt8+R7ZP_MTEV`{KuGhPZMme^jiTw%!!WUG>>IGr_LQrcq$|QBpTihh)%e zR)sry@~fL$e!)rIZ;#SYjUd>^4{e?wnh+8Y*0w$Xc@q3*u<;-`^I6*gL-asSc^y=z zL$Q>`UjD3=S!N`%mG@Yqx+gO%sQGM5ygO}>6svsLq=Ut_t#4Ma#vQMB9!~$!akrS* zmZPGs+|g>Lp!V;j@xdc~Yt@PqS?URZZF*IS>b#rK2h;(lSqegdfl6LY@ze@lD@JlS zK#A~Je=W~bCK0b0ow(pO+ynB=DWw$QQLHnb)L(4pbe}}Z9$*)`$6q9y9PnDT%p{_q zirZFMI3Y%V*>w{}6u&r8(wfpUCH{jv*d`BtXhIhgn0uWkn^Avf@LA(qC3h0cybEjo8>H#kq)4fs~pmK(qdaWHH_riF@%i0sUjZo&|}kbJm`cxE*utyYbjEW}BA) zjG=5;Uf}9|t7!BbGp20v*zDeQQ?OL#lVg&Y!~XTe;MAMGO;(5Oz1D1rNERPKDcsv1RLm9 z1KV-!5@^$4AKF=#zU189Wxm40^)X2@mR zxZhxi4#mY@5=?zZfr`B?a#K?#gjgS0XzZ4MVl_1XXnTC0gF5v|<$=5itHk#|Cd-~j z5F*#{E1tG4=dw8uk}~0N}V$n2}Iop&wkqT=W9~Y}M2nXpg_pT0CiDUy-$?AB7HU9257W3RTzv!@8x{6U^NBT>VZhp)UK$?#TOSDzRB z(~?q{{9d{u=>8LKc`rN;roHv_u4LEqVUhU)$rh;YsPq9@Z{M355nwKg-gXraap3MU zjLbtggv{5@@y*Y$+scvCPBZbumuB|TkESY0iQ1zp)Y}V;I9Xe~7pQzWAxOE>Szo~x z26Ncum3q7SDPs#NvbJud?2)GRsTdNFY8$_emPJBHNLQNbLVRBGKEk27)h>fbUFjwk zPUpqX8yLN;=&g9iGG<0#O?9lSCX%gGR#Qo`?kTPop|=!nWrXMPSg9OT0q?TtfAjm9 znBNv5K^PZsXP5Eod~1wFB}Bzbgg7yLVp#iiYN~Bj!n&r=S2z5Wd%){3tuwkl7TEVE zqeq455R|jQS3GsuB+I@fw+Pwji8 z8tAl6((|k9TJx7S=DSlY>CVG-E%56cznFGAt-BFx_+FE3Z(DH=_!olsZi`lCnp@`l zdsNWvOgh`f>hiS28*W4il266u5)a<`Nh6Gw#-AlfZXr04thfkc@T1{_Y^#IM;!#}b zK`iduN=6hjgst}^2@DPFe4b=$9&Nj)r#}_G-8?U+-^M^i8oRFH3~HU%`Vkwp1M9qpka0tJvBks|n6!J2+L-!dB?qr3((DheOG%9|j&0!&`Ijoo4=g=1tChotboR@(0zE={ACB zuQn#X=UelaEzj6C{+u0Mc;Vue##)cI9ZVi8_}AaYN!4=Qr-0_WM?K&_V4{d2&&^Ht z=GUmCc`UE(-iK6zGsybi`d4IxF(W?-A?VebZu4-|P!2jw*qF=u4Wgc82vpxRP_NxI zB2~|NMK?J07>YrS*#G@e3L8`WYP87IUTD*5K`vi8{`H#MoSrS>Qb@Z9^xK{{mvVOS zHoxFC2;CBcKiRF#0T%G5Mg7**Q)i;B@|g~?tcf&&LOQFIX<2o86(m+CN@b5foB=i% zaxsRwuT|M&eCKfVa|!V-h$?zP*SQ;`2FPz$;=)BEILcwX`Fz_iKjEvLY0KIofL=%h zmH2N8qS~gt{tn}E1UoeVaWnTwXB7o6g)X0LxOjn5;~b3xW$FoWf2G>p)vp-ay&d{! z(h*=G>ivc zRv^n-1VruzS@(he_OC7Y?*VUGVI#=TnoS9nvM>L|>puhnbamwB52CE*6rcU})U`db zBrBcbt!o=z5*1Al@-Tr-EB7=Sb;=gGmC4kJ6bMZ8> z0D)t8zSZqPKkVfUN>PX3__tGMBFw?uBEeh3xPv22ni4-QD9u_YDYEJwnFW*{NDb8P zVWY6#Hjrr6V=m(%Iwt_-H1uc@`FY-pwfzM;#=j1v?u{G*kaXSGTechH&?F>hw_&ha zIQU148gGJQ6Opq?IVYS^!s6O+yMmw9Omfz&`(M@S?0F47FXOqA(-n}bn&&%kcce@5 zOzGYR$fP(e|5`@pz3;?^s75*w<%84(sB@JtwTU*+W^~zS`ZnfL#gilj1e7)t;&D(E zt$FCl6_b~GPxV6PGEe;VxM1sDwEDj0M}Ip@F^+%-H~F0t$r+U69(9@}`SsK)T;(Y; zObqljOi+ao4cD*v2*TA=RGc_Hr#Q04@%nCk(iZk)BraWSL)AFZY5Ss5y~G_xN#>R{ z6&fUqI^~a@Gg1iVfCqpOSfrpx7ptH71Eeg%><4pf=)*N(SWb#%$uA2?&n|VBtm_Q^ z;E~I3lYT9P-Aai$7t9`7W!t|zq-6D766ziC*<9gUmHi^Ib4tn~C0HC~fTDoIouGor zFcYpUc*^RlFcdTF?4UtmKFeN(-9eSPzJi09Qx(6wz^`JSo-7f3>HGqaDH z`CKw~QEFC}vezB|>c=vyk8d-(s|Hr*3Qn`R#{RjiKAN+wAli7E0)#Gz<)@_Dziz5f z-C4}zG9j-H&ziq?H)w|$w!MIqGgFI;FXcDb-^(u%>$tHAL{jZVe}8t zOQa@u79BpMwS4RE!HM6WKX75~2UCrS^QG&vVLO%w`q6noM4P&+FhgJ3C{3@ln{P=S z^qq0EXV8TSuO#spVrjXofCSO8Sy;)vxvDW4I|x5s_A?X$n!mP0F!f)|JF#~A9{$+l z2omVz%nYUtXEbO$ziRcRG41;KO8DM3UImHsN)Ehbtejk7eEl5+-PE-3?FnOLH0xCv z*(;jCCg)1Lc`$5eH!nPbnn}7EOnxkb_7AXXZwN;DocH8EjB(1B8O%xu;RAVGuZJ5F z^ONR0CWmF)PxM7@WlzKS*~BoRXk$DRu(s&g&i;MK>2fW`G_J<4n^>lG-qy^Wa3_sY zJbVYMo>VBS3-AJbg8rS*I8P!2$RoacW$l9G45&s8a#;jPYtL`BUuE)7hjP&Dc>t*4 zKYFV5Yo(XrT_XY1$g?VL0j?aHpl?H0CHuEqjvHJdnv@tNxGk`Z(Gu$KY7=^I9gaJ+ zFD?o3f-%qDgvi@Cc9g3!nd9}4?efD3g5YIOI9d&KUzBy$c{jk9YXQz-)}gM7r2mkdSt<@Y1e>{sLIeP+&bLD zNwkYnozOi&9v5Zp;LwNZ0+xa+~e+170GT~@h`0Ty7UN$1d-?Qu3Gr=)WwIl z+MUntE{3uFgT_kQr#w-$Ivu;JKTMyRzp1k7ah?`0hE1QPR|qa41fQJq1c2jzMI^rb z(MV#(@Kpg~Tb^Xyc5r4qKp9*3gzyttG$U*AYFUrsUQZTOfbJ6rAl>#4mfB~gd1PI` zur7>d;`FmpR3M)9R``q2|462JxvYiR94E+UoF_@&y`x)p(nCqGn7J8_J-o>i@<{hJ z-#n-qXB#|J#YZvE%I>tcrz|QZ4xdNWN4nry?-tyfsG(Iy%PnXn@Wv-~JzJo3oY;@c zAZ6+?<{v!HcrB328!r5N4W;0veSC2JDCzxQb4P@|^`XmbpK2(}%i-cQmXc%lg}h8H zCZ(e4Bl6y=p#a+Y`_B13vdv2ik5dJTD-bJ84}pT>ZUUl14VQ23(v{wpJvqvQ8V4JV zC;n*40mjc!O>m6`dVA-AP^D_orZzA`6em^@cd>rAhm`d>wi}a`{Y85byyI7Q1-3QA6J0BQ24PA% zj-~Eie`$JM8VSiQ+Ek~-`xn=I;Wt>NCBH(K$qeF2@KaCzE#^O-w+fC10rJ1Co~t5?@9Ok1#ZKg70*@wdBRkN8b&M zFIAH$s7)nGsgMa~8-DosQm5fepP(-wiRcBst^iDXX|?2gQ$0c+5sL^wxk31z?lJII zz5EaM-ZCu8Cwv24K}1AA>6BW!K|orO?rvBlMY^O}K#-E|Ryth)rC||i5Tr#)kWT5` z{f zy2fMf(yXg}{!~nup;TM-#%uSpI$YntCt*$NRpOWQtI~$Ha>Iu?*bR0hc7KPO2#LSA z*^w(TI@M}~)@ssJMXlRCy2z|De0Fgph_AOh(GhIXPv<54!IFe}&L%#i^H#y2*B5QW z!1*V-w3^!MUG!5zdo!o*PbjF2KYM3Kh%WwRX5Zy>k(3wwqAXg4I%n`ZiJQY^Y2+uZ zy7J~&`9+>M9?Qpc1=Bk$Ic;g2U8`BSwRwz9>hbrbY#U$AQO0(5*MOr>&6v^2siBO; z35vGkbo$w`bE<8Ev+WpWQ6n=kqvv z-MgA@UfY);!cw2_hRqMZT_x!pE$lqfdEk6sLBE|rvB9+NqF9u~;N|V7q+WgR?lO)L zS3ePG#!McalKsd&`nXH{q1gAffoC}7-U6C&y9Xx{kAA&~`j+8v!PJFo0UL#*oUu@6BHQy1a^+r?Qih6YeFnYd z4~`v7iPqn-5(x7*vF&lCkE@6EO=#^k>X3fnTn#nzZ|I^kb}|yYT_UsZ;Ogq%*qWWJ zDqg0X>RsbTONKNySHVqNe(bEp+JNi(-IxDxtC{!PHDq!uw)+3h_TAji{J-k4{x=C2 z-_4!QK*1&N=IrT0CwOyM!v8l#*#BtC{vQ=#H}^sRuRV~q^KjR&c6;vZ=;G{jbAR*` zI-cjw4$f}cE-x&>)pj!0uk9?YwdAG$U#`AWu(q>(d2{PDINd>8^@Y1V9pB9@)}Zs+ zo)#YeZk$$hyt#7vf5d49>K3o8Ej{RX^zE!XUeXCY{@+i95CGTb@&2EVh1kx)HXxpw z>c*1c3?lK1GcAx)t&BulUgk$K@lAGq9D%;fSKKz`>z)@pnYX}t_Doh|n}Ia>m8?!O zL+h^p+V1ZLt-7Jq=>WKTuK2+2Y{s8l_jv)Y6Vg~r$p8QI-w2#1rlcHiPuDgyG}MDn z3h%RtY>1RKRpa7n;JWGE0w1kn{Lf#TU`r_LZ7N~#ndsNk5`~EvQ-dI*_<>&75!{jr z0|I%<@_ua;0}cLk2=V3S`ppA@@DluAK6004PAV!XDS^DlAr>GO>Bcvs!}#HDcMG0@ zXJ=;@M=RAv5VWeXtZ_vy78?BV>2ML&mGvVlYileltgyFlyTSE&EG$&b@>ozzS=_Gs zviMyDlaBGC|FwV(EgX+lR8r!vqko!s(}o5y#ms~EME~=z{;04(jGd=f>Dd4C!4LKK zxDmAf)7QhNQ5PcilanWf^D0hcF#dg7)|bvdcox(Rymj!cZ&VXMK!#{%^9i{G<^ z*$JX!V`JmurY_h^k(+c~XSW)IbCq$=2E^l21N*IN-o3m3%>?&YpQeyRicSiQf%I*7 zn6Infg&Todlr8ZO@@G=DH8uH1@A?hd%gV}zhKAJC)Ly@S?Ko4{`g(`5bz^5oHDPsk zcfQh4z}VRMLc5w@OQe{&E1HZ)w|pE1M+tiW{hce}cRMog&0b~V)eY-+}t5#+(iX`DYAPln2Ja%QJdx|DutBcY{31F z@Ib=Mn7VjDQ1{&n#beEd=IBwTWGVrt*@h?*4y`i0`}e8&trYqanF2oj~_q6aLJ5}jj^$?_G!Ve z4G$0RjTFeUsAaS2f1J&ijXpcogiqW$o;uUmXQDsOE*lWhfER_`MMvGUc_GjYCA-!V zZw|6aS3{|)s1)w*fHyvqDx+2Ua+U{2FK+EsTlR!9l5jBU4uX+6L6)!6#IPe~PPxzFY9j*U0P}dNw-fo>Ce2*>LR2Pg>^)iu*Y)a48Buh0 zG=~iTy_fGc#usMloyYiqF_O-2OjJyLdhzY-g6iQz`W7B=Sy021i{73d`Lj~5z4`MA z82d`ci}9>n0bBfQ-)l6=@z>`MqGpu_d}3l^EG#9|`nQyxq6GQLQU!44W(|A(=W(8v zRJgeld2R+>a|#MY=$bd^$6cViwp zWur@7(JA9FHT0Dan8d5C!9kVsTFMF7E8|)l)kV}pM!EOsSGPA2d_KN0kt~WYqds~P z9qSuKtRlV@7~IYI5twuPJuY)mo(?yMUgi4YBKhI z0gGbXepO1V1pP=Vu*Ljq$mPinE-tQdqnmY^R*?o=u%mFPXXy!FY~PU{a!Yj`bN;*aJCn2?w!K(!C{*Gy^`d-s#M>Sx|%h{pH#vLq{89F^&;fFVyxK`7lldrcKa%EZwVdrN~if6}S(NRq$sN)k8I` z$1NScLSkE`01>)t} z?ed^N4AZAqxptU(?eQ2-w2FK=hFN(YofYDN4fs%q1M3CW@GCw88a{avHbm-ibcp z?^9VNRn?p)t`=QUB+;Z?7t^+RBYYt_I_?!ZWzx3m!0#k7DQm!0p@D<60o+=lH$%71 z6KMCvajr{Bpf@c4Ce9RozAu4d(H1lj;N~9s_3Pr|crdfOPG$|hh`z9=Qy@I9Q{VxX`lA48kyqo{#WtG%txHPe?13z*kloNRF)J5c zkW}%w*s#_{XL}vXlZ%YgK%-QHzWnXOhYyMEbkL<_;=V_hRo!JRT5QW)WSfZaaQUwx zSY_`HdX{&uo#tCIu333`EvR+QmPjZ(-i?*qT)J zM#7MRrN~m`+uy1`oAJnUH~$>n7%dY0YdRWhCPTzmL`0*#aB~m1nE6&euT8czZqrP5 z%Oqyi(%jwY+7d8RM|NPUN*T!fn_ z2yt|!;nx2064R77XKlE1|4&a@_FR)^h5z}%(Hd|;EUK9@0cM+?qj|@h6Yj5HR5-td^U{4Ceyc%>%qrnH5~%cE^Awm@AR+Xp_{ zfB)=FxjrKB?C)YY0j*i9??hKu*Y}vYduDC^8M_ZidCXMqRGPI?{z0g41r8?71*DVb z=6*zS+#~_5ms_5!xQ)|H4Gp#zO}BX^P}CrV@p4AJ94*AT=FD9C^~D~nlj62l)fQcp z!cHK%VW3g7hjI5v*mV$Q68if3qBCXMB~OZu)5ryER5nJ7!p`M4HZ}xohYAT*gdyO+ ztm8=GKul~RI$Og~wWYA@Qu15%W(hmLb4(Di4BWRgx}9f(apon+{PyDZ&7*r^yGaITJ5;3$ z6$ZTjMGllSc)~iL;lk82U}kp?rYbHEG!2*<&&V!X;xdlrepv=pd;nuMhgu<`7PPn&9Bxlzk5yJ)Heuhgn^K1S_e`=5wRJniegg4; zJuDoyzA|q8=b(d4mjhj>z%PnU#3JPco>{%p`|WW?Fx+MAf5BEBwtXEO`A9L3{jGDe zoOII<(~^Y`mJ6iOb5*UJbZLSeMg~h3|H5V0Ue^2DOvn0Lz9q^Z-u)|L z)?jN5@E@({rsn1u5JS$-TfO&z+?KH?k1|K;JRll8%I+CqeI=?yPEyyd@gOfaLMSnDFZF)6PevT@8 z2>j40DpS9&pP=O&`nEF(njEUrV}FxjR9_v>ppA*8wPR;B14?_WNK^eTx4dQFM?|id zR8(;2W)G^IxV$OMm9`%(RJ@XBlzT`1_~nD^i;ghdonK!#Od4EP`crapa)^kC&QIO< z;8wP_`pCcl9v%es<@F;;|Ayz`__9&NcC!upMapUG0nW~Q82A2O(iRmLt7Sg{YdT6c zniRENI~?km_{7JxQmg1*&If&j+4&CqXwGW^$B&VHcRe{ZRgMK(@g!_*_(*yLaueM> zH+5Qlk3pR@3F@uh-d=HJJxJT(7aJvEz%#(w!~-n-7hdqh~0zz0dZkH>S$u3%Ge9M%T-oXT|$`%V71QpI8Kg|5I%ykE5S(w3-tR} z0m!>jtTzj{`f7#jB2&6_q*9x0qx=!4JQi{$fmgaG8Y7tCNSoQRw)N;JZ#0j5X=$ml zstN%^sv-0%4K#~YGE%vW4`?UKb)z>iTJPfG7Ffu53PGWrpfpQTm!uH&V1=v1qTpg) zyVMUJJnhOk^KJNPdo$JYy2K7A2@u+*G6EaQt1qFX_MR0H&s0Vrz7-v4){n^@5 zCNpjE=1YM#v9`ij`blcsL6G!#3(}<3`s=-N-3m$}hhC)9ug`2K_cNLp;KpCt+Yd;w zlWjVCcs!m{8_W?)6Ant6f{9jYm#7_u&9?X?IYIB>4_e|(Mnv2#UzNJP5+L!q5FXV% z%fi0k-*E6y6E)V+(TSBRO9pv^%XE!3_*SEP_$KGI`b`K2GjPTgw{fkLS?|0s)OYH? zEG%EVYE@oycB_f#bbHR}4Shd>irRp~<3r-e64+1sIiBd7tocA+FST-K!Imv5c229H z{6LH_*L`F^|LJc`khLhn5V>e&WgREQTAS~sqa(PR`rHPef-XFC$Vxjk()Yi_iFSbc zfHbz`K&dFc-lP=y=+Pq`lQVX?|3ku}v7Wl>J%72}M?^)HwKklGyQjh8+D|-5OTlaY zwBBhh^z`z0E6o;F)MR6AE!)L?lTpwgu6{3I+(4Zlu4x;t#c5K*Q!dYIm+B&Q7zR=} z(k|J-s1;@5z1Y4@1Au@$CRp*?p>8ivAL8r65H%L~)tPH-ZNSlpyx-|A2^yMZT<`RK z@w_%zr2gsmxjS(e^6?Id-ie``frjHSM(NhK8)GHF{98eyD`-Di*leAGnJ;rR#XoF* zuP``^yF&74h@LcCdDAr`Glu@w`3uqG)6)g`-h8VVmKlhBWt>8GqoGk7pk!y)tL&xy zkuQr|ZrwHi%v37sDSxhZDQrBcO0(dti<+bo$rjJ?>RDVV|7f11q@>Bm3uPLsi_&xq zoiR{84)lrDx~~pCj4d2kF@&GPyFNS*kENATqw!%kTNy|zIW4nPlTDJ6^FbBCbN;RY zAfhyLtxXAZB#Z@e+w;87p~>fW@+3^@byE(=Y1hX}hLP83vjP!H`$7o_UhO4Bq z0a%@bA^!1He0(KW*+AmTE}T7%=I@?$;`bG^ulXhv$5Rm+UT>B|tis)5WZvxN>wh#U zYl&n<=Lg!2-B_$}H)`GXH2YZE0x+^g{nd|O*vBTw?5b9Vrs99AH8GO2_d6c$yPNAe{6P72|a)6Dl@YgHnFe>JOFM&UEQ znp~J2&MVWeI5@9m7$>^{H~?O<;Ry<#wV|A>%XF}y#wMI+8xq!}#ypmKsObzDT@SO% z4xVnF91P!A6qh<*P9kJd(#W*h_#`d4iFo({%~QnEhtGnH<~FY5oWog@gwu< zAB_{NNVNuBzD{6}E!9>Od<=yy|E#v`Apb-C2hsF;M+sY-453@0=W$0gQQHWPy1F`} zmjh0E6-#0OuF?NP>ZZp%%&i-sy`+s=#ZspG&p}P9i(kLA^K$N1iJtIJU{dYJY>!WG2Tv60TIk5o1FN;Mx zka>RShbbw($D55!O`|yKIig)`RmjeCK1-!EZmvNoC3W>Y5qIVk^Cs+4jStdb!Iwez z<(;N$iriNEbrRdoSF^5GX~8<`eH2!Dw%s(!Ob}P0Zi57N5h-$*PK$$XzrjMw2c6 zR{r!!4kB$YkBJOFh$k~+eWvQGaoCXHy8FY3dIVQXXoWsT9ewwz2Fv?Vp(DK>V=kQmA zDzcNLxGzYW=H1RmQzo39fhxL3zse{D2Dkk6*^V9FL)HZYP%!{zq=~1AU9Vn7QOQot zMPz^DJpBE`h4ga|e4-2TUk&jv*b>RhcIh12kEuwm_~@o>tm*AvUn(|He{_QX%Nz_0 z$Vmd|Q(xhkDclnJ^V4*Kixy__ObkJtMqN>WmwNxdx}XF~pEgzYgm9Svk=NJ9{#q21 zPMy_F1MayrYQ$`@^{do`F7_X$RqgVHIm8@|I$g*&xapS6k-m|U(YLpF3s}jzE7iv5 zWh>>zW;31AUb+G)A8-#C1q70gh~6Xzy}qGM{!+>MkZ2z)J={bld)_qi) zB9l1P4-(g+lC7pg9)g?1e+qVmAtT;3ga4j)3#l2iL$39w5sSp|=xq*B*Zlz~KYt?6 z*YPyPTTdlejn0-Tjx&{maLD?mLX=ecbw-^3FcEeyIbPU$=~Pyp;Z@4sx+#u!5qW_Z zY<|S4Z?q?nY8r(Sfdv*l)Nf~GNZT(De$tSXMyfFXQRanYN+%Rt{-zzU-h(j1pcdtH zd{9N`3#iYsr`upU9|PqL`YCg&ucD%IV^}}fXS}$vW?KH-D$fEZdO&hbL!tv1QkhZ} zZET9G{dAsM{I0H5>lC-?kUbzN@+Eji_&l+*W?^`dqy``_)zucUVzOXLF8)rTQJ3fI z>_+umSjIV0*8{yemhy2s3!lhOGMVz3AdvSkaa;byUn9>~f}wAq0Q!KwYmt8R#O0}p z@l6#gdBv2}hu*tJ$AzVNe(gu@7JD1JkIQ=s1dge2V&g&L?>T&3+kE9@-F6W{K;?71 z&kjkjEI@Chta%>vVN_#P1oo3V3 z%$y*`xD_6kw6qewh54#W_D&y(qSs2MWa_aYkj~`|U1mL~VI=$NoVI@2?RcwCCh$6i zhd2cWM1k%>V1kY|5d&#F#)gI@_CJC#5Tof;Fwd=z7pJj|mdo~~vE$(q5C|RRb&R=% zr$^;Mfx=M}dO<&BdFvrb)j}??bWL^Ao4P;Xa%(LQ&TVdK>@zD_H*fTP6@XYeBXmov z%@Q(Z8+}j+1YG8wws+!ms2}(n%pmTR!&f=8m>Fd-Hl|BNr0qYxmke{LkIUg{!K}S zc@}-qQfFOWqiF!AuI1LV*ft=Evu~KeHZbQY8?fG7VIc$^!AWE$WKAraVSlt9Lm|*z zY@ispoZ`5_4j|&u3ey`f1cFZNvjU(W$LTkVsHZ)t0Xhh;%!GcFc68SX4XT?R0(pt4 zNQ6V&M;xh({=2m(R(Fvb(?WTqe!BbWe$WUWnB^Dba0%a|Qma}7>s^l6d7bw`6Fs!> zN{h1v5i-x*9S9`o;cqzOp;_tjgTw}~rW0m$uj~Z;&StkcCWxMT04l|Zd=SQc%~^IZ zbL+*FGRdXsJxi+GxgYf}fQ{c8{y0!VlcFgp=dsuk24EH4?mbw8ciAnK8${&}unxS* zU8x-DYL(%>s{@|J#l?O~>PIo)^nFOuo4nT^%PdUc@eL&0Ch4IcRS;}9SP%sT#T{O} zo5zmAuq9BTng$*tAR%DC6qHGiAinN^)ZKyvy_%PEb5~-^do5ElS)@!>hizY-2=#*c zhKr-_ThVMH3VA;vGtt%2F&(dtC6K6|wt&lIn$|{v=tFnh`<7G?Na^owe`ckuW>yg^ zkS?^eiPY^XyUFL<@^0OjKrrgdmc?CT+^v%DSe2F2cfMK=ba!?x`yI`FJ9ze%mW|fx zE(G$H4&Y@vNs*(ijOR4cA#yd{<%kr|B0gh<-Pf@DeCfeAGuVz+QXH-no=Ab=Mk8gZ z1z+j3$=52rKK{fA))(}*mza?etZ(!-^kqxUzP(w(Y{ELl;M1FF^M-#HagD1AoA5IV z_5x`<-$Fq^+NU7c0=^i-Eyz0@#UB@SDzW~DG~h1S4yO-Y$~I)d1( z{gekhuaA`i<1GkX)_VAC<%X(!_NvDi=a4zqLu{ns?Sc1 z9nHmVK~iHE*qJ4v&wM1_Gxjko63SG%wH8C|Cs>*jIw|J0ZiZF{j%rw8Px<|VBbH-c zG?qGJIAmD3uA10jGGgFyCx1Bv(oXl)a56q}IA+HuP|~9Ft}GT+T_T>}qn4HO;P1;f zsH)sin(c4px+gQ)V-mjb67qIXLHSVU!g`UwME#H<1$D@51xpk znP%LR+!i+k-x%M6d=k$!)2*4<1H}o6ZnRA0T4wZ3BcKWFn*~1w)7&rnQk+{Df#*#) z*W%+&pSZKVEiHXu^!aMtAQc}wocxytBnZpRoR=uOKxz#Q1sp6YbO8g)=<`e0Eyc%* z6ga=OZWrv3y}2=%U7od8H1X#obaTMrs;a%cJ$)`95(dPJF_8@%u;>CP+2K#}ZVU(~ zC}^jd(tpQq``-oLG?`8hYJx_i;WQQmc|AJ=UNCb^a}Nn@$`>AR(|}$l$}KgoIAyhK zkW-Q5t$~DIAnuNsuQ?Y!BxrtdYWC-dz$uH^>un94avUP&PNt$HklmU3C7*8oc>8tT z7yog`Iyzshk9)wM)v4ahKRrHPqezK_zI-5=4WK$%*?7_`_O647cBVC?D=!4Hj?sr3 zdEeOmk4mh%88Xnc$;0khak*ZVQpcB-j^~8c9|r;sOgo3^$W4cX<dPe_|pfbPFEc zs@VD3ROn#OqWJyV(*TvPFq|?9JR5I~BeVMfs_?+eo%*Q7ot>SW+OGgg79^coK3-kG_Cx^s}8GM5Qact`%8ni_FQy|4< z3zFY!QA02?Fi=xdhu%d1_-SaPox*N5v58ac>d=sf5(4?$4JS)VV>(VBXMHNIQ=&%m zEc2!oSVw7!eN6ICh@j}3Jx!0u#T4Xw2oGy{R|5ISH_gS6%Ee#%YJ$BhYjC>OcFn=% zMWes$WU9}{-g^*;5ksXA+*KBIF@o6B?t7--(Q0ivl#n|S@k4*VoA(q`MP@iSGd&i0 z=gKd`;>?+#&Q8I`X0;?QkiFCAgLGI(NQmSUQ4t|O`Na4ZFDMX1Io{n*-mBAN>v6It zcqC3oPbgDnJ&+33K0-^MVnarJ zek%Z?MX*VIRbJTDps4<&<3f0q>)_u*SH^X^P8IwWLT-yN*xdtk?5Sd9W$q6U}|QVL&@ezI<>Q%GLQSgOI}9+x`~BruWcz zn&YZdQrADLQ(iL~eRZggM!lKJqxAZ^Mx7p;i|NVB2Cq7{8F&V7-Naa!P*qSUHTqKi z;1Gc0fq+fJ#zRwmOLz-r%&fpw+(8z)$;9~ zm6Mu^(r_?H>|xG?TK4Le_Pu9PeP+hrCMI)ZkSP5bzLE>E)|*Vis_{)TFx5o5S` zaT1c0P*1V|ltZ8L?=?0zAMP#q6F#?)O(e-lPo3I$7o@l$q7hkkZr>3Mxwo-!vOqWw zP{}xpzc;|pn>%8D)&8zoFJC?f@B4Px-xIDp)>wY27i?@A48*_erN?|aVM-iAO@ zpfaw9{rr4B>x?b(TF*lmBh>eox&SY79%t57^4G6^&WAK@m?9>q40JLU=OTLHx%))M z=_LWkTlDrxJpcl?7nj=C5VK=AnVsY8tqpqFG3}!wC-hpwM9aMU9Ys`sEl~F?7Npop zpS2Feys&Ref1e8k2=9@x7xEhB@Va&m34v%hi-15aFfnP;pTB<1BjMKpZ~Wv9mpCi? zi%=HIEsbXo9l>eG-{QMT@Zl8i4^YtCz zjo#5c!NMhNabJsdIol6fgK9vvp?Y#PPn=aWhJy)J#$W^DZ`fM=;AakN2qap|pY$_O zT%G2bF7%Ju+F^1F%>AgtfIw9N>HJxeD4uF2^i;u&c*5pjnLvno?@KC5u5Om&=a1s@ zj>pH;%i(qx%H%T-{yx_87GPs50~xBcTr#KO!9<1rbY4-3%k{Vgg@--DmGcfnA=%h( z`Lb-nhMyrkG;CQmo-&aJ>{tkwvbL15SNA0Aj>yC>E?c9MQkjGy_mHyBBm?u1OIf?S zyHUbLQdfV!T@Ih2M5jJ4hpvr++?F~KH?STn4AqH^M_E`Z0HFIQuI|1P8dTtKy^rn` zv`G{0@hr?+JTDkVE9%*z_D;8^)cFKkTIP3<@q|68Dkb8+E~9r>F(8G#nDx}nT!4mU zXIBBhCJ6!jTxg|$jahg{q1_6+Vl_Lq66kLdnIVEUh@{i_3rM^*B;1^e} z(FqrC^GwZL(LEogesf>g;pcnrH=;nTu}wf|WQ!>nKja#u= zPI)O8m9UeJxHywU?X-zHAyfTKg4`!PJQc&?XHF{9u#F5uF0$+oFR%CJVim-}_HQ6x zB6aJWoIC*>%XD7O6=oJ824p;B;niQO6B{`wBd`fw6A60}9y^*I zv2o1mxs_*y>%b9wNB;(Cgq|NZ`7b?4Q0UK@Je;nPymKS~r%Ov&w2M{xT+b%LN1!r* z!R$#NbdqoUufYJg>cyT=7%JUV*sUcmIavp2<+>6Gf%w6SRtC$xHmY{em*VBka25{_ z_^B``u$t9+uEJWppJ6aW;NT2gYUb>n*{$IbG9)rurh^M;5o@ceGBTY&qo4$s^#+$k zVAiI{k4t=&8pM1AeaRbSQ(@1Ouu@%v5{chcK(v-rRdAor+5J%EHrpH|XeK@+Hdid!O~ zSI6I0If&2Q)s{!{z9&4FX=A8!O%mhXyFTdbK&@CGK}Jcm$MZeWF|v>ift(Ve!+Fqv1iz-<_6H=fAs0 zO=fFnRUr^krEP6yTqu4Vk89&w*BgS-D;gfqp$KBB6*KY^fT|u=Cq2jNU08ts>5c)C zR3I?%+x-UU4Bg+)RTf}=2+0q`FKhog$bHQ4YGlE;+9R&}lI8EVKr6>f1~JcUP_?T0 zR3(;XPx%MCIkWA}?QpB`PTPeEmTq2s0S$OeL{*jJ)?`(f6ri7tzr0Gh zg6iRIy}mYRRsqbT{5x{`t41Kv0t7R=GXp(*p98V_li0u4UdlxRVivA8$=@uy+H6=i@9(65k|QXBB%TAuM$h`97I{1?xZb?b{p4)XS0lX0JWHc^M;g zrVCxr=;E4$@Zr_?z<~1p+d3e}s>E%n#vFJuoN-5p1Y&OFJ@nv2eru*4k*}8xp#5P| zsl7JE5P^O3pkS^EO1q85^To~0U!|IiVq(pJ7g!NS8$Pr<=lFYWtQ4N9t+r|w{bntk zHc&%_!^_KyyVtZ0X)DXkwstQSR5HP%@IWkPtY?o{)N^%oA^|zZH%toU7hJY?nvF|- zEAFN>=1wO9$NQDMXGGmup^s2X9;X{Ptu$l`wC)}(yM z8tyfN050ypAt5tC@j#m4Z~-r}Dwjo8qTZ@-ork?SkIQ`8 zmGycX&@*qBw2Qyk>$wBDD51YoFuf`kggm46&~OQ1Uu$#BE~}a@BCsIx5E~)Iw;L zCu9md>T(21+7P<&GHsS&9Ax$tcID8(&sT?A!xcZphi)g7<{EPn9_yR9oy0=tpNR-_ zJbdDJQn|FVdm7MI;Aeh6^iF%o?{Eo({qqe(=^elu4j{T3ue^)}0-)t-yz1(ACRC->w!idQ|#-Hveqw(!yVDqbs2{mdM*;&jm<`D20OUO-f@Z5hieWI8$i89)wj*C1cY<* zLRJa3uJj767A~f+)pHML6Lo{ql3g#86{FY~?Ih}-LU(u;Z3K}ktRm+xqwr}&?@rrV zS|)w2%xJ+C?};zQfZUIoa!_(tdfkPCgkmYJ9^S)MWA`bvSyC_>=6XqJVTGa4+v+qf1zqPgTY*--eE*h_f-TX!B+bkxN z?y}nLi_(7?dR*691}hD99w_>_mil)5CJMBfc?LVi2N+G~IKF!I3h>LJD%+^)H~z5S zHM27cZ!+#dcyBxBxx44Ee)SXdm0AQ9R}&ONiIPi%Muz|3`zG$FkqbYz)|9*QxBFKs zuf-AxOZK`~`x8;C+IMQo4_ z_x6d6w$Te?O4PFsw!<@hT~B&FaIH%a4&9Tu! ziw{UlDCju?6&j@%O=-C+KMS)3^X8IQflRrd%I8ko zvX?R4ExvadzFiJSv(mgQa4rw{)3R~*@3JWZcUOmUIA-Z-x3xoyc5(yX@)1JblbswD z$w>YviHQG|yxMOZuW@AHo*?tbIS%`6wdO*4Qm!$^>N2AA%u8VXo6g{Sbyd|WeICCT z*`h^N0ye!Rm{OW`DFC7M@bQn-N+--1%^2PS1a?VL5u5We3#>I<=1t)@Fi2GHqwdP> zgI8S$I^mZ|nic}(*U8o!)&rP*5cw>tK0h0iX^9fV!R ztWzqclyC*c+-rLVuYiZxU_37ltWD(U z>GiMC_0We<;tvSI`{o5-d8H(Tod-u@mapgDFH<7AnSTLx)qQQq|CgGbegvV2wWcZe z^R7>LkRZkQgj6LQu>n`N=50JVww#ISr!QtD;fWE|&CcZQa?dSNeVx4d1q1^8{VgnY zuOrGBZ8i{M!%M7mD$t4tW z3z1;rc^0X%QCTzbM>tY&Ij(nCu9Ko&;a}Ut+uPfZBz3Ak1ns6*AOmOJQV#477R5HH z|7m+yeH?I&mDW0^Ng8!(ec7>sC=x02o-|`HZKspg`J(|NUOMJ=LXFO{l|wACf!RP}sZ{-a-GDIZCsD<*;KCG>E5K7-1`lS_9GEEnUXzU68cioi1f|MAKC}+$ZK*ky9R*nzLSUt`?JrKTNw6u-=vrUiPvy{$P1MhM z>u!pv_@K>ntz?MYj_sz=)bx5}%NsMzrirZGebHxC$ELs@2Nu+5w|a!E8zhQ8v~k^r zyzJj$!()|*I~kaN^#aK3LEj#hisg6)4r9x2%t%|lmJcx-olofJO8kY+&235vSoRBgaE11-`*3)=yaX6H_ zj)1rY;e?Scqqul>9)8QBeI463N86Hj9_~NMi6H`X5?nj6?i5Oc$8&~>q-8sQ~j_irkBCU9ep9L<@)Q7VH|5Y@RxZt zVCH^M<#>Iz0_WzyI=d z56*524B_8~iLTbDu(N@kIvZ1S3m^vfI;9VgXK!RN!XxLNT}XFv%fj5wvLE^*!-J;yHqfX)Ayn9j$yubo2Bq z@;cAb-SoIOsS%0)dkr&CGlr|d^>_O%L8^N>FfZJ7aFa~onlF=t#9Vjx>aOXRN$yFk zfqk+$)TqQKIm{2!KQ|C<`Fm>$usZ7Snf83J-EguZ0TM)Q0`~ANx92AZghLEB|T*{SlWst8mi9d};ApI1p5q>Gq2Th&H3p zW!jE{;U*XmkMPl*lGrb-$D_q!8kD45Mn_=F=c~G+$IdS)zU5+ZDuLrh0p+ow#v^Kk z%(5~}Muu|#CH&Id-U&8@u5%borhJ!e607?u1+NfWc>sCO7){!wF{-)AwbQXm&1KeN zfU1jDuO8aFuKN2W9xTBZz9027g&bcwJ39l(Hy{Aji5~#lTIGpr=3!-`dNqnwEcUlM zhANHKiLn?H^SwT6 z*M-M*;%H2wlL`nP?VyY-U+_=p!Bjd#=%t^B=!<-MEHOotk&yv}uA6byQ7wcoL|W$) zx$4GRz(N&3i$Do@$9u>w7@dE)h|sSFn}?grzVPs>1Nk0MD2VFVx+n14KJj>|F$wXK zhZryel!#_iY~MZhmws)TL3O@d?cQ47={c&qvR<^G2zT6FVgxXGVC%~IC41@yPay2K z=-4c*O;r;)0ra=)&7wyVSjNI9 zNtZd!UtX<-TW>Z>{{8#+<*(0W6&3bYR?Eg%ovl&U7ty;>NaHnm3Q<()9f8U+UEtp< zNa~ex`<({-rZ`H`_dWyXwSRbcSr__EE(&RgcBae;D7bogW?*MP?U) z=0Ev{AB&w$fyuH!d9rQeG1*m>vE<3wfBN(j?BxdgwnW1h$n3HM4!iMqX~-cDKZNFg z_I;fDT`+y_>qmoX3vft)CQ_tGfJw0EWaY2$g}|s)wSfd#&fz%-ww%*2!0Z%@qYmS3 zqO&=HqOjC4xCF@;kdBt6KlY--f|Pc4by;_lg|RlWc100$e)8DRipjiof(Df68o;AETSJ*Hw^ozLl_mg;@m8Lxbb+0bu>fFU zC`ubC+6wJD7jN$d^t;>bZa}eLVf>Nz`ciG-Ef&zR5-ABEXK6D`rEkkA?p#CV;BuM# zsg-L>2LSmbVbih#oArQgv~&O^_eBMwjqsG6bQiHW^HH--bnkeobOMNKD=RC9`g_8u zck~Ov#zxXJWg^IuwBk5WSSYb7RR~CteyOV~mKj^WkK8>j@px2iTC2Aj8n)FKp}}I` z6H9Z{F+ZORAb&I(Xh@0vwcq^EHTe@Dy(PRqObh?s-kxn|^V3{Myds%x_Cn-x-foxv zS!=6a|7*LNut*ohKM9=cSm`;cw?28`XrXm2wOPINU;ArmFgu{1KZ0-Kf-L3CetVbd zz;AVn@=Lxm*q@4VS{4-+uX)2W`-JN?qMGh}d+(#Op@Q%d@O3Ns-X@>n4nn}-uDWV}F9+<@-2?j04BiJ7emfz!q?|vJ z!XW8P;{#_+Lzge~LG+p`ZTwVLKhSsSTcaWU?}&yjBH%V(uCnzn0pZ8vSLq1}BbA1= zNU`c*gSeiVw9oapcz6>@36OM(|AoD`4$Ct5+C?dml5QkKkWNWS>F!SH2I=nZkZzEa z5)hCs=@O*7Te@?P@cYi$`}+32u6_PL??2`{JkQLUHEY(o?|XrpT|9I2Mv1mOx;(X! zv9Y-Wtc04xoJcjx^yplKZ)O@C;MbCgMiBGqThzsn=ju9$`sRc z>U?g6Z$Jpq;qVDUNx*Cj&^(1t+*KurB}gU6BZv8mCEz8^8aH2CyW#z|S6l{h6G(&u zFgVk0#SK}3F-z8#aDCJ1iGlRo*ya5F!g!a6QQ1FiJPKH33P5~2w^iRmx_;-sV2*S5 zw{D4rr*l{`no^I->dP35+PeYpkOUb40RdoKcURXMn(gGTj?6oeY4&0>=+wc^d#XEvwf-ZtoV!TLR0%1;t zxAle#NL@e?LwUphT!_lcE9dK6Q}zfe0II9ItS#i4f+RN#FAH;3z#(<>9TlQjuvoq} zS$R-*-`G)WKma7PC(n>777OIS?IN=YqZkE|90BCmU2o0+>DUM`Z88I*9xAZEE3-~& z$~6pd=R zrTpjzMc%x;JyAAr*_;5=B9_Eyzj>!i$EFrLmgoAyLIO{E1oehGQ}_MFu3$vf6~uNu zT4;21YY9I%9K5bpUb^Mv!QUlNysgzO+$X9Ltd_=uYnaHX@H9)>-)YO=|Lf<^`ap#T zVIMe_6YrTr(OTK(CfP9U38-GFGFRjx2cLF06;97s+_Sd|pu71jUM+k&C2-Ys&pUoq z+uGXNoN?Z1E2Wp{TyqP^9LFI@5Hb&I!;cS_tyqse2Qr;KGhCRp^^SXq1r#~F6_e40 zgGAf)J3cohh+j~uiId&RCN^Id0C0&zxtSp87uG*HM&txu#3m55>3}F$_svpJ{A2NG zalz29Pz+WcXmSJD>!S#&RFskLFi#pR{n4s6io4QNc0NV|0s^1_ReMP*^}*iRvhqYG zA7D(%P~JkuAjCt(!(Db)jfT#-VS|+9H*Aa9J!YPEbf16fCX(=y8yHA@x(@WLf@@ht zfHo)pEo7pEZ(4DCM;8;YyOMcnVfd+$2tPOkc?9c9AV|CdtXS!hn7GUt>rr)yKBG)r z#aQ+y`4y@+Oss2vt}T5tB6;;RSRM}=4{zA@*SHl6DCKl?>Jsn|e_P2vImLYR*6&ky9>Fn5$EmeLgM)W~TNuPb^HgM?gSu z>1&ylB-t76HIu^w0#8I==_{+pt_?KWD_LY(flyRb)a)+TAj{@&3vL{Vuut=}i%OJm z6nl3uN5LTxzUh5;ENUcL!f~y*4PS=%PjSH#8j?}C)_UPXC9C@hzybBO?}97l_$t|! z|5wU$b7`LIBgfor>{Q@YfnHB>Upj^_8I*S7wV|PT(~P>lzCH+Qg1kF21t?@4O|Q|w zQ=L+PtoMc}x#GHPW-x0_nNITuaz9|*4qx-Wj;HP67oofzLfWqX;nO-!#zs}vm;Oh? z=EC!2UHm3f_Eo^8^gVD zik2;rk5Mdo{5@Uka=eOpr;#3&$C`0XRY-@0=> zP)X|HW>|EUyh);yr(IKD(^_nVd zY#++UTI75I$wjWn!j?#aMuJ{~Y2QAN>iNNX{y|gF91AV3Jq9~F{aY?-l`WY~zEe0_ zbl=H3fD@k4!fThmUFwar?~rk0)`$Eqamt+CUhkzGOpFDA>X%QJ@HeK<@SaU)%t(3` zRK@%t&4BiWG zgaN^mUM#J!2asGTb((%gDns&J5*fWrn$5muh6icF%_v_FM zKTUT(3Paz0TXumD{rXJHyiK=(aVe4x;l7J+>jyzd4dCG2oPZ$FjVs0RbyI=!KUak0 zGj%3&r=W^Ch&cwLBd}ZJh2kaR^XaG9mUcfoJz98nqDi z+lXXxq0t!;+wfaWBfDnR^0jV$b)5dc72^50BJoi&r?G@R?Xyt3$KfIm-LSu&YA(dn z?u>$it`srnLbd3Rr&@;+ZG>7m*%4booU_Aqg(C9>>q3Ugfm4YP=LugaUg~3 zM2_&ZtUFPRsC$F=Ng6D&GBV}r)$d$$goXE5uH(*aMrg4X#2|#W%BIi}R1s!3u}Z0Y z_-?k}A{YbH#kxZ8EEj@&T2%SZoUU0gc|#r5vt_uSZ_ak0?7Hg=HEZ)nDBFc$L#)Xl z^iS@v5y#b|)-a7x>Ih<>pT-a}JdI{s`~=hd0XMo4&rjfcn@}N|^A7 zN~<{;BN>MMZ>%>|8nva6fg7l35XrITE6fvIs z$JhdFg43x3q<;vPgtDL7zH%lPf{b;0nldF1FCg^e68iq`OGDy;bh%e81Cv2F(q9=7 zcyJG}%4f)r_-U-c{5+Zr5E8`)*ci>Gnpw~>g0o(wOrzo6dO zIJN|G#304>`g$l{m`g~6v6&#~-_pvZ%2kC}7m!0g87^<~9)7QEvDmmd`5efIV7l}~ zN6w7>2H172kfd!VsBHQ-nY3^woDaXJRp4Y0l<0VVST>|cdnhevak8z<}@$VU+F#_p{@`+I@$# z;FiEr*pnJQJ7f<~CB~314(=8L#aI0#=4q^0P$3+1AigrDZMeAW;dH^JvsxsA7h5jG z%m$%d8*=LnxY+|KLr)C6q)H?S6);LJ{H`>#efj2&5>rvJMt$1q{+dz3SEO2|IpmLV3!@yy)8r$y`C7=% zC~lh_+RWlq@-9#RzxcdM8%re$G0{GH>U9Sj8X zKoTnbR#%E{D`72D=TGoZn_o6+s%m23ms>Ifx_?}NX>i?oG&|l-_G_BbxL8l=Ad<~| z1^u)|gUCqP+-c7MpFx8K1p$FtsVF8p43H7cjNR~oVo^a#xcO(BA9%X2Al4iyFP$B+ z#Tr`+v&~0y15u4Zimko9T_ZitFWvj(wJ*g;5Y&^|K-+J3zemppCBQ{@qC(+Qa3Q7S z#nNhaW7W)bHn`o#6NjJOcY&iNL?G}Iy6;BT(pUvL8JGqU0y5!>i;*F>rv2gw=a1Ih z7z;Wv#7`!ThnphBX5QoIrM(@0CMBI#SWqxorm6Z{u!-ovF-ITC=E9$Z}1f%^_ZD>J5*B&amqE!VT*J(m+pvFADE2Dt6C5raK}#`LBN z;ZvYtLgOUca(|(DE#A4v!?)jQq_4@IO@v9^*rIrMp9?Z3VWS&sYhSz6anhS)SEN76 z%()&$wls}CPjrHXAjA$RYG20FWGGo5kI-dg}NuY0r z=1>J(A3Xd?&oGLNU9}{mFb^vhIWDDthreHd^f_I7N6^~p+8W3V(845q`J(9H@T0&a zQdYb$rl9R%@3$2X?klC|z@!p2-W&kT=~4khMX|Ev1b`8Zyq8;P+z}`yHy|XIr)IJr z@0?F<T5mqZ209ka}r!2~^ zsrmP~)qIUVMAU>o8ixD2l9bNdnbAFhf&@Dz#hugcxOlj&Vh?oYzd#V=3T%7uLZF`P zvD;{8hr~-a*@Q_v6*LuwudJ@dV5tV6YCOC{BBQJf3Y_WH`3yl)O{6^JK$sV>fju+V zcLbPhfaHJy73xRLqO^9sgV~1JjX5aEQA8aZe4u@&D<|Xbep@KJWObaF&~?wQpyMZL-(D!phA$SotVoMX zNk++7RaHXvLJElP1fZJ#&W3!EP(Y!xf+YYcrFX}ovDU-EFZ67bF90?yTz?|n?xcGS zS97eaXK^=fo{(i5ofkY-+gu`Bkgc#&67=X755C=d`FznbK zu;ip=r9NsZwv11pdDA)?8UANrG1!dDn=gJfnhtFA>TAAVfnt_Y{BKbBZh54ApE1WS z$J*-BmeLQ9tUf+IKI9t~Te~qF? z3P#%u;dzJVhr$l)Xdy7OkFrV7pb7wGK9$$8o&ZhMS7N2%xf_3 zdtIHgo!u@-W6H_JoUE-deDP!X{OiIZ&kUfSEE?#I)YQ~KwfcoHz^Cur?zC}_-_OkP zxeJ{^vormLeb?(bwLd!S{&Ic$TH%wN3tWzXo?!de(fT#TvAIY4C@9BYPWzt?K>|8b za;jXr&T0b_0nj?NrBGIwA6)1v871UOmnN zzJKs+A8izfb~&Sj8?!L79z666(O+Btupibn#$nJY#ianL=<)4&%*59IU_^y%g`Z(2 zEWfcpP7W0dOPPNHS^p>r-tJzWg)hfoB!L2-RZ3RYX1pjiy95YHc>-@Y?9crEXXn>y zoW<69L6)z+JN(ugbt@#ITeA@-pd^ZkD-a{sCO2*BaI>IF)S5;g?D$R^@!#}!h4~f)XU0+ihmB`y`dkvpsnYi*-}u#L;^fw#n%*{cgDyg%lRSu9`_~RP-iaizXr;Z0i~t1V~c=1 zwE189C#q@2d>~+$P`0@^OT7@Pbtuyoax@*Y!Wm4;12WnK%&MDa^hjOOq+x zndfCkW0q#7yQkDn_CYAbnTI)$w^c89_iqvAapA=WRZB$H;EV z+AXT*-t6Cdt9PKlh5-ONP}#l$%1*jXZ#g;D|5@(NdyoYmYkp@h!{_?7eUlkzZ#jPc zjCxk9QDY7d4}VQWXzPDli2dh?+_AnF0xbeIXyux2liBWdeRO&<%DNi@#2Z{n#>K-g z`LLKSm|mCxiqZ3Eou=6g*<0QD{PbYm3)Wq(2F}FANA@dkpo(>;Hh4o*Y5OYyC#g&9 zvy+pGlf$5a^^nO4D>cpMk3L z=V-5TQ{P;qU|0m22kPnaL>2kv-kq;TwBafW2AH-4o^%C*Fu00lJ6a2vpiuNo&hpx^)gTfb#0{3qtbD#eoUHFOlZ2ZWKWt*skgK@bSm6r|o=m{z$2zmTcPf!p8e?{K5)P3#?5tydGps33SO z#iCIWbM^+jF~u&7?>1PKGVTgz4JHAa6C844=g1rU@+?d8cfuiRx*N`zAQhdc0#w!# zx?3k=1NNpDkEZd}n_Z{H=${83@YA;44wm(}u#l*&oI)s8`UY5i;;n(muUJ><+jiPJ zm`$X!E^X21@$V*6rCNybTn)^oo$nr%-w)fU`zy=K=5zMuEk7n^l z4`SceSAEy%SIAX}*20M@zuG@BsK1QJz@g#gUF_}_nF`j{(n88WEVDn2TjmmLEWx^A z-Rh0Qh$Fs9xR8X`mF+aq3_UqH0kKgLO+#539UJu9rB`W_?|D<}br->i(&bJ$Uv|D{ z(ID>SbF?neot%vhLUN3;&tIL&C(&uXyC<>(3=|QbGLFZGobI+*0bUfSen>Nv*EwZS z{qmOMMy5JCI%8qCS68^#*3(7b&Geu7fzW{r6Vw&M4LocoO=`_JR|^(r4xm(bgvI^ zrvB-%M0&PbYz5f3nVE1PslO?5B{aPkjEglVdu{f3LA8=v*`o(4m7_r2R69rh3@E$4 z&1&3K3v;n)U)~+86EXIC`VpYJhnGAz&-tf$<+oW?V7u;EkAk9g2@|}YeCBt9+zZX$ z#KCav43o5$%m`z*o#C^VZ~uzO4n_J!;W7zmYyj2>?)5zMR(Y7_c=rnK&(pxd znm@U8($OE!HY5%{pP9JTd0WX%oS9-}F{IDXy3|b|Azax=k!)=jxr><%zH6V8Pg{Sl z`7ObakB`sHGcs!nFAbHA%u;5$$Q=JeU&Ql}G|I&kS7z4mQ+wf^JM0H|r|}@4%X=|x zFvdVJlEtUn?3{3rYDM^VU3pF4@EcTIX#C`vBy4;Y&`N7q<$btX1Bd(j%}_H=XP$l& zm&|SA{BOfU^nInzM&fW8CZT)Hrqo2b6J%>r0%)!yW7>H@`4t?|r!1;FIeqyu^JwMJ ztJa5O7aK2Uh;al|R4z%l!v3k4m(e0v4Pw}zg#9Xs)X^r?D1-0rn|~VD2+{#)6z=}M z)Bk$21(Mr&k!~Pk$m+UQQaM|n{7XH=Rp@88-JhEGHsSVBZz?A)k9&wEEk1w@w?Sqg z_JYWYi-_qupx zPmO?VcdiidGl>ht4I;BYQ)ZRNQ(9aUzpi-EZ-s*+g6% z9)Y6lYej`k!brzvrHd{U8Uz0dS zV2S3wx_Z+Lw0o7)mL_dn^O8whmieM7kL1RrrR}Y+lUXeTsC%gu%uJ|28_jG+Bl%y} z!V`RUqsl-*bO9ApbW&qjDuG;c698x#o6U)5w^6y5J}FqD57mTYOVEJjHx7I<=kT+Q zimfiL7l)i_${QV^P6Se(4MY#UZ=;oN!HFBv3+RRT-4cH@3!2~IM=SFL{^6VWYcxt3 z`9lFH+VEc^@sVE%$ZVYq{3(FRWZOirRUm!dVVa>5f6oj`)8|3^ z3~g2K?VMob*Bo*^ki`;(L#52l=&|J6Y=Z|KlJb!eVr0W%X zpq5idK~6s5DP?5Tk;c1+0l`;hov2#fAiLN@IY2S(-$3zD8b8!{^;t$gG?lfrAiN*Y6#6>zZ-pK}Kg zM?3qyziNNWkXCxV53+D0dYtbAF?a=>;_6X;!7*^jV^Bj)zG%%YF?O_`n8K=|gz0}% zHVjyOulP0$`(N1}5ndV?%A1{AZ}W$BK5dwU->=%OPf=d8yL?blSD(?eX(qQi0o7lR zp{*|FAdUQ#P}^IWzonQBuC&o!^je|i2Ub42IDQ|+;E+~!1cax#-kGc9@CwpVQMn$} zZ{<1S0S&qp`|_xa5$xz|{i7~eIq%BYl;=I~_UUq~*@yBtVq5Sy$Qm&XxI^Fw%}TPE zjl!ttRjGbbr7u##ME#!kk!5e7vtod0rW3j+Sug0TR*Ycp(tHaMQ2C?TaN3FFltr?&5 zHUS9PgY@87ZL904@t3aRd}=J_T$W&UZx8XSyGp)D|J48@$O^byV}w|O0K`^=sbTm_ zuZl%pX6$ao@^16YD4cf5l^2eGjJAnfEMR;XQKhuAMzr$V+W5_|W_YLg0CoF@ax=v&4%CZ<=uLe-|2DjM9lP@Hgffo3Vx7Z@JPZ}{6`GH`3C4WeCMM2z zl?4lJB^wrvd^f2_lT-q= zn(vpPGXetxK~tWwm29BL3+VSu2`?w4WMrZin?V z41&_PFih^?)tZtCX80e?SmY;5 z&wF{R!WUE!P9fZSVr4p6_A)&-AtvTGkP+JXGzwIo-I}E1@&$K6^!9d$Vl13YRg3vl zr5*I({-v04FH>+zsvGzGIz*Jf*Y|7%|K7^FSv`V2#Pv-2$lMbB9dHDTN& z0IfE+!No!VLtAm7}+okC?&`3~G zNu(X6#vIFcE=E((upPna6NUf9K(3>M)lprx?fYcOq|hhfl6;H!Z;8y)w}~B3bt)I3 zaOky6=W5Fwu0Gq@xh>-qDxslI0Oq>c1;8FArKgwH;f_VEhb!}QB80iV|LDf}ca$e2E5X1TitF>bc4>%gdk0BvRS)n0R=!Z7LO$ z>~0x2ztvlu-a%8spj^d4KCchcYPI#_`M}z0r2o`w$% ziaf9Kx4o0YYn#%EgH-877ix+_@Y5tDB>^S8l)dF_Z;Ijld&O>_p&)ILo=*QP_2VYl$K{jJAk{LjB5D*c+up7H( zaJ!<5|CS7|s{?0;*xNYunU7An)K4Bom=!z8)qR`&&Fb(h7oU)r^Q6+zn4bwv7Rh$s1Njsk`CU=%nzIcjA){&<5 zLoolUZEPNyiLMBYj$e^0sfw7o|us`nT%Flt8QZVo^9xW6f z(+hqAyOg}3SnQvYQV-?%*qoBv4%{zLRJIG&y8Nzy)#}o-OU!8p^B5N3awvdAJBhBI0d+0E~5R)-h9AbM-NbJu(q0__5L0HrFdF#u!@0C*~nYrVl2 z%N1yR(UiYc;RgM?venKPjxjF-TfwBMUOI>Gg zx4~rrD={8`CM9eZg+Dtu%>OX^qEWVd8imTOk^>MMZY4n=NXNlW(m%g-B}S|E{qZm8 z4lMLj^fdSvDu?ezOK8`go+bE7K2k(+;re*NNk?uty*M z?i=5;3!nnG04`ZwSF;4CNm_0lwW_*5OCl^TMU{(`lc2pC`;y0dHa3-mnDaMeFa^%g zUr$C}MOKok5iWddZlZ>v8MtQYHGFoHe`siE!lg#;8IP2D>SuGl4KyuS1$kP|Njz2& z;sT%m=xz`e7WU0+;U)kA71pm9_f3b$k@n^R_EeYAqE{)tN{oqGZ0Pe#GWRzrFWWPU zJG-G1SuNcjj6&M5dNpM%;!XkX3xIf%zk8R;E7nA{h!43P7(jydFRG5lYTx~oFGWli z+vZiyQi{_jlTXj(#p}Mi`De8hbG7r>Q#aUTvC?X7GJ8dEO#YwD8NkqogoYMRHA^;e zEb2epU4t$*_oq{(14OoNv9RSdNudW8TKwU$_yp=$8 z24>>AQ%S#E`smAW%tK2`-dWG4n(L)4*1y*ZYod=VNmbR=r$B#g@9;1yF;RuWfJq02 zArL2>!f)J4!V6CN-zfFjueftqx`-RV}j_mz6t1?Sz1{E{c&`3^rogJ zAkBufWF2%)`re`NyP>L7fhvFAT+?mgd$aD<;xvsW-d6R;*b5mR{8_fq$Y_8X_552i z1&G*<;0Cz8ZE8899M!7^5w54l{X+H^2;?rE?XA+5>5fF`9x5UJD~j%MefuxXGJts7 z1aMwh-YO*%0Bs41Nvz+w_k=e~mGXHVcQ*aX^kj#S9a5V$KOmbUW6J`~V$JZ!le_hT z=AhZevr4nk<2SdWzaYmK7hAxD0-+{`rlSrT^eZgyUwkt&Gog~JR4%0d37?Ov+-w5s zME*^}k%uv}=KdBlH9fucc+o$RQ3r24cI$b-SUSh1p{8y)4F)yi?>c#Kmk5$~m#`>V z&EGn=8D_nXzAmB`yZ?CHlDV@;3oX%X{`<%7mv<^k*69_^dqe9vZS-%;!dBPgh-U=t8D z-tA2Yc1v0F961KJ%2*ypd)K8LNjFBbsj?;Gd;Lhm4k=s{K2mV`*hH)I+NK>bL`&!I_}JOZ8BI{5;jhAxwF_3Tz$W_k3RD{kL9gc z@ILeUH%EGqv_XN|3k|EGE+2robTK8xhl2-=xO-3!J10d{R8vb%OvFY*tF&3-MJfh0 zmJJ2?|Mw;BdL)%hrbjjcn->60DU`2dVi!~tPVQ((NiEvE=qs|bNq|TTD93?5gdmm2 z$-$x3>b1~zQi_8XYxIdPX<>JwBqKc?7+)pBYcw=H7rn{wkY46zA0}jo_q^LltB{@? z2pXC??2{i438964iu;6w5`CXe8&c8%uoJWX>TWVtv1E z`*KSLc)rKT|8heE-{n_La{u(^Yte)`CSq37`opry%U>ht^GP^N1PX&enALBL#Ao;^ zdcv}wzBEzaX+Vtr^!HtsVoU@=H9e2fdC9M+j0MAHV)WTU%%dNP#sBN8U6!a5I`Z

Ew=}apba7r<^;vmEYAydTieR{k14aMtQJ7p>63{G za1O2D_E+B-`v)|N1M%%2a3uw7%chH2izn|)S`9d8V<5XN1ujJg{Dz4sDc2WsHhduU zYKjBo&p>h7PE;uG6VOUdXVmKeNT9K?F;GKY02Jwz_a^;>@#3I(G4s?Bh@6bf#nlxo zBIv3!Kp1ZckVUJ9hs4Ch-ayO)eDeb*C%}Zt9%LJ0V_^lN6oFLD_mksG07Se>4s-Gy zDFS`4Oz}adQ@fYKhMb8Ex{H+tqV-=HsrFB0GCnBZsh6p6efXenBDxqeC?q3;>~sSf zifteZ$pDxMXlif@PA*s!B1_Oa04Ou=?(9%GV+vtg09OjQD2ZGMf2jWZW;R0V^8lpU zPj`{w;a|8=IrZE@Rtwf^`D(6AlRXb~^FsqAYCuT@bwB@kU|+~*b3hPEec}-$K-6*d z0X5XoJB7!c?IHw>BvmxAs|WPc@ma(U_}70p?x{FCUv_i|_^wruOecT_SvpcugFq?* z2xUS;L9HW)^_Kplg(NIoF;h{A*Qo)O@sg4~_rqoigQ9|-<2q(ykE4&^u2gzGSp=ky z0p>0uG7`&sZS?j>Q z!z^Oc-SJ`|$0aE%oAmDuOWI7TMZDWaKz{!h3Uz|S!SD4I@YQ>d7N@@&qN1XBYj3I` zrcb+;xy;8Y_bh3r=Q7x=Qm@|gdI9yd$<&cnY8sl(V94IRlSyUiYj0lx zb7J?BJPid1?Tv~O^VqHiSQ}7MQpRvmR<|8yea+1Uoz(V$x@cTn6^I2vCkPl=*nUFH zSU=#(RJrMCo#hH@-OkM^C@8=sV;@meNT`=EDxKOIX7xh_3tLA9z^h(rOiavABRKBuKuYKf7dChX3p5-Y z6VRNrNd7B;U-c3q0ym>fNly=ivHo$ifF8jZ*lPRxmi0gsm9)wOv=g#(a%ur`cp7CF zXJ@Ygp9UBvFwLKUzY0z$4i*-ryK|7n0}+B|qf=Rv{J($w|MZE?zu~*2no$1lZONZH zklW~+BXD#7A6k7&8Cjcvmfajo9REv`ZYyO;n>j|LmMzt*B8VDl^*Af6X}yXAU#sZ` z2p$KnpHaIm_WP63`3nzsV)E8$Bygy)m|d5m;YDFWXVz~zuFY#Wc#_`5`DyAI{b+zx zu+1N%e9u{jAhfp~R>o$HN1;+#wdc-05A~(GT$_QsWG<{+Ysr}>woaOzG~v4&N#FOK z#3REgbj{$?rt*Tt*l+6tYBYT<4hEmutix;z{1gtI2FMJ`%h^nA94zA4%W?eRtgWl+sLA5nsMFp3T^HFS&P;(1TUcISrd3=hXI(bOXA2dwq2mmO z+?cYWz*>8B$~*iMo2=S4h7y5AppDFk@22BDLQuJw2`(ZGn{P)Tnr9iWgRW#-XoZM( z=&lTYtD7GvUqEJLWYLs71uf8P>yq?s5 z@1kbIpNxo@I)$+riO^g^veb@(eDY_xjw%jZl#Xbijq_ZS&&|GhQoYxefPt{CA3un0 zt+1BL#^YGgDA^Jgvqx4-^}TPHvo5TqPZD9~>;HKnb--T3jCafH=YYG%+-vaRs1t&r z;lX#@B{3NXL?R;L z%J7y*;E(e+aSzbCo2`5Qo2|!0!btL8TTj5u!CubDPSD2cvyHWpwF3zU34@@GrH!59 zXFUTW5(Xh7Co=;hQ9C`?|HC#FGcq$Vbs%BkU?gEsbkuin{S3Y(Zlz}eeo=b*gPN?q zxsibb34^McA=uDtEZ~3sXLG-2X8KYrc?4oO zF%kBEv)0W2(^`v|SvnZmfpxUhb1)JzGO#fOYxKMlOe9Qfod3_dFq1GbF>|u~*FU}o zWBk{OF)_afE6vM`VDDgOq-TZTk{daxIs`IvfxuVUr2!yYH*T^qN-v{M)3^d z%E;F=sCBXl$N~n!hXvwa^LXoUf!_uBoxIO_k400HED~R6ig8WPLAT4n%@S{Yf#if9 z(mh!4Uprix^&^~b(|Hs~B>5h=L2RY=lf%x`|Dy~&zi>(`C&RlRkJF_-auCEILj_R> z)Z$?v8qzfF@8tOhI?=8G^b_S&5`|YM3ONd5Ac@U~mqc=TfRBYCq?iV<9h@LfKdGzV$St0 z_+cxA)6j^VJi$=?!TNehhKlN?vkwjd3b9XQS~Nx*Xtj&za(c3Iy5u@8_0c506R@ zqKS_szaKA!?C71Gyl?OxN$vqFeD8`W<~+EPcZ|2k3nslfEI|SvV^DV3Xk7 zKAuwxNbA;qM7KQ8HD#mMagteV-6sio-Aibi1M8Qn`Iw*DxfPYOz;(9dXw<%mjO|TJz)sB9Ha;^m4*l0?k|6|Tx$C?t z0h|AluM27U(@QRXT>%INo*M{S!t~JxT-rwhh~P8g0>05SoV*hovNq`D-*+ghFFu>z z6Tr7HNe(eX$Jj0Ns*TbMw-p&*I*uci_^G`*oRaX4WI4j%BuY zTay08qc20;*44{vqdtz;50JW5T#w)jes|C(&>Y#1J`B?JchCqB99oZ%y1NbcFYQ_} zPp&W?ruYZ7(=&8+3i;T#j5HoQym5n0BGzK|wId7jZ%)`>)Dy?%bFyzy z-%;St7>^Dc@_a(qDA68Y3@-DL5e+1?b$h&tdB;3I7=CH4r608d6jq-zmKKD*T1yq-t>m(Sf#q8Jhyf6JdUmS z0ZK_$+Fhd%KTsv+V@gSNDG`GgTy;xu$18i4>(JoVj(oUUONUi|6rGH48$E5V!OJP- zxj-tvByGMMbF*$`p@A5>nW3X$<6xS)zPnk*4c!ra7UIOm+3RFJ(J~=*v8Xz`Bv7qm zRF-1*P#u}Cch1eMyGg^#!3-j`=26kL^etDFVzoF7f(9)m)W|W>}3SQwdu+kS-6`!%g&-x2rOjGYLQXf8g*V~ zI4Z*sZXE|F$fbNEPNU6Xk`XPW`GmCM67`3sxx1-~7Au*75!V_PJL@BNPxFV^9lm09 zQ@rcV%BGnwEalPqytI9-6=V)sTDfv)0l(Q_HNUaV71YDlwrt3j^cd_CIhLaI7Y6KlXPs(A)8{*i(*Z)Fg>GWS+ij3 z+3KSfcNg4E=zbVwy)Z-DChnrOstNK1dJdUFNq$$uQp93iW(2*|tLy6k{a>v2w&`X+ z(-`zV`ODiHs0~MYIU{>GlHXt|;MCau9A7%kdutw$6Ddr)%*9q&jU^4C#?!d+DqrMm zYYxlHQD%IC+Oqn`J=;;}hH>%4n>1>>y4?7_x4sK%FvLbTB$uwk)4LfNQNMRS#z5W7 z5*nbj6K?!?Mdvf;2{rk&hLme%-Z;I)Y9^0o@MY>jwO0g^Af|G842Tru^-8|*-`VYQ@vLV?Fw zs-aEgU`phBlwKqiDGwN3nu|arzL#nSTe}pT1I}{fb#4$a7F!v&rFuivm-tcyW!yC1 z*k6lL{4pi(h=BQx$h%>_&(^0?q|K7PtHFNONgL_xg5S4-N=?7v>{>o~c(0UsRFIf> zzrXqR{Jll?SC`h*>eS%H<9XI(Rqb9QF{+`mHNO|MJX?FSjx`XDK7GX~s1mGYCS7N6 z*(^fuCMeK2cI9CCy~fYerDP^iuhBIloYr2}_FR5Q4Do9Xd)vpDssHORB+T*luk2j# zZ703^X6u?eoM6{mnvS+qP7}iXjm_+bSN_tUt#?#Y2eM?vd-6VBPFQMxnknFBh#}_m z9eYS-tR96oQc}r~PDQtW9hW=KeMx&-xm!AVr07!wi*gLNk`aiT@USa1nDZ%3BH4{_ zOo%ynxJme4g_XA7jbY%+_yPWFy`eICD$nfI9oshiz}0+%+I1tU7FK%;&g^JqoMZbX zBKqr@1bC-W6D_MbX6=I)t~bP^a&zd|7KCWCb{KRe3LBmI?~+6V5bb3@9viF$sYeHE zh^)w7&(~PAqR@9wCt7=3GQ&<;2NCZ z?snkd?wa5b+zIaP?(XjH?(RWy`PaR7YNqDS!*q2&?CQ1l+Iv^O_4oUh3yh3169n!7 zp|JoMZ7zAm8CWt>_-09TY}SCOmSfyEG@p1XW2W`nx#s5E&&TY(E*Y^;ntnov_S_Ei zcbXk{UqcMUysTge68`naw{lv4HVi3)ou^6x=r>M?Co{1Cx87iFY^bV^l2DA-?4)K_5?aBl(#53~ zCBdi+1iDMq&)d!lyd6Y*yUv$!=J3@J=O_JI3Xr7XIkENHV4yc7{gePg90aX_)!)_J zifW|c;!`*Sjh_?pW;Wjr;T|&_qeDu>Ca;&^Qc}*QbxgD)V->3tc5l`0(%sL%Sl(WvL#V&kZ z*x<@KFZk}aYq6pK8ZMS~%G71DD-~?9y4;SHGXU!!XyV!P!Dvy$z$0k}9}0 zo2!$iBP{g2i!xlCU!K`zJS_~9KWc!x^2@RY$)~321J6wh)-Y$E4Yu*RU(ljB_5WI& zAK8VDo~r{bnTQ6<2r-lkM6Y6&OjRyKXkLZY@ek{tZEi7|gp3%gw6E#Ls=HzHXax?2 z58-6W7VGSIJQ4JK$TEQQwVNkbgI4(YVcbHbPe;x2@|dV0E2-#C)aIEjDszEzRI7t6 z=us`yYda_%6CL?Jxd!+$NTYWzrmM*Z zCL10_O@2pAS8-ND|MQNP=)EI%Z)3eZ)z6R* zg`ONLt}qkb%cNv?(oq=}V-aze%{&!xDkjmTB88HA_*6hNp#vdaoxsG*yr#?(A)Jn= zO$BDlYEKdkq)~p0+5Mr=W>opiWJO>6*Yo5#V&>F{aFn=Y99{8pD8S)f4D@839Xu;K zz%=)W?cD*nX`04bT;%w9tdDC=KR;DY)4(k!c_J1=P&HY(BNJX{sCUSIPvQAhfeLI! zQaf`JFORyj5>8r9WChae6WDF@c<4QR*=U~DK|xO;RdppQeQ!?_Ah)#?u&;OCQ;m-} z(Ji^&C%8}~BtZ0za+?b2Qq`LAh;qS7jbYvtQIOeEP!j6ehDx=(D?mDR?Ef$_>^M-L zH$;B$a#Q`0BRZ$PQ4 z%-wW?!5#Dzq8KIU(7G24^bw!KQ!>NIm58>Td(XW zuPxSo%|(Y(!}-S(TPdLu1jWdF{y4Sqc;PZU(gir)=k$3k1H`-ahdSE z#!O(ZhA8|nFFT^TBsixg=by?zv&L+>W!a2v&8XPx==)b4mhnsryAwB=#PgIV1rBjC zZ(=sQd_7tDWMtXgBv^R5>xQLN22xtfbX0oHu6p=<2v6DYz2}vE(@piO`E!sE+JixutRzrA+kQU!KIammtX^ z0%Kk1f#1`6Bsc$AUHgENZhY3g0gQ|istWa_gcK+xTR!~e`;Lqzf!&?bgPh(&5ejk3 ziOEF%ir{=ja0a9QB`oV~4()5Bn&6Gb=#~6&P~7MFg~xCAw@>r6oPSK&SkxMGvdO4% zQt#JB+WZG}uhMVx4Y+pAd}U!Wwl3mE>MqqO$-a(X1QQ5;txFNPC0r-{HsRyS!T3U; z4dg^SJ&+9B$i7|j;0`-K-bECe&*=Awms7NFK9?;S%jYyBlJ933=ty;yACfqK6moXn z=L{Zv8nrf6f*Mr)-5s8<(943cF@GX<52^xovBOmGyicJ zIC&t8CQfR>br#r3&=gVOuFwa)?!b9hk!CXoKN)oUGLlSXcCLgEkb2;1C;48axoilp zA2(R{>EIt#`PIfc;j5fm@oJ%DUNGB>iPCCg?#WCZqT=o!!>3-twUjgJPl4Sqfkyk? zQemcj_&#b9ey~-O+oRLTx6PYLm<%r%2pH`Yk}Nj@d>M7#arDs1xe|K9HP*Pd?|3esYd@Lw`z zkS!N4FM9P^3-joe+r>lGdOY1LT`^%ri2N|@L_u%r9JLyw+Q3wqVcRcg77_XF>+0JA z!+VC3vtB9l&Q`YXa_ z12wSNjQU0MSRwATjNJOLyx1W3u*HTm&kkfhBYeO{7MjsRqL-N6Z{gx6TS$r<^+H7Q z6w{3XH7j*gn5X5TZdCc*ps8Z$5Q$9XejhirCU#1He^tulTj~YA*Xu^jQrZyrj6#$F zJ;3)KOOMSD+v`3Vf0S0tA&=7@UG9LT%{lWiT_q58MDwu$5zljEcIaC9)Xp5o*v z)$LNF$7%e_V9NT6XRGtyGF=$fHaql94P8#!lAf@DQ_rgDET}ND%+!t;Kl*nq-QX&Y zdj+C>u`QE1UZvO!cG0#4+>P3?=wasr=e&1mMP~mq{gu~h42BV>-P4??Oj{`KJL~%j za^EH3X)kMP z?y`@uuE7_0qFy?_H>3k=P^Q%5{j+bcmOXt(3G|#R`;+V@l)h64H*cVa7;gJ%Q*|>j zUFVbTyx_SwZ{fuFNLMgwAR2O8gSGb#0Vd`24+$=CyE60irkJW#`zB^dQtY~f*Q(Uz znvFrwkGuQYl7p-Gz&knA{cJL}iSGDmrnRAP+XYyJFluKa zUpQOoU?}jI;|>0iL-lChs$S0wnh>v;BflpUljVXE&981@p0`IB&6hbx7FuCYYtZY% zZIdxlRRtN6iCLCeCa>;e0%uCBodu)AGboEl8Eu2VVmsp`u?k><1dFQ+(YayumTNlj zFsJE396fVSMXas$@%LosK> z&aKz<$y(vM~qGi%msx+aM(D6tBhPDjY{N)W) zOtCPBRU0Tf#0dm5;7T>DrCTirUAT_cyhK7aY!pzwQw&*i&d zN3AwzjDRx~8c%97)rV|d*~15u6G0{-tU>DRkGtkCeSBJU65JZ$$>uBSY=0wj&p@Y{ z0`afO4f61N?GL{vHR8e_LmXN4-stP|NTtFH4P6{w?fR?mOfdI&#$VJohOvHRdTIN> zDqe`-6v{XFr^HH~^lVXCqFupJJjcbxqp6e)E1y9s_et&@4sI$MZe;>ihg@{@upNbD zk6NczPfO4nVU=!c`fD4yC1o;FNjKd>_zPs#KrW&gq)U>Mi4)ClF zqh97?s5Ou-!xo{c#I%mkN(`uiJ^iUpN_dXt5bf_s)tl|B6dSw*`IFiAM=SDf`@3O=Ct^)3@z&h*wX z=KAxYJSD_|GIs1KoqDuR9(pr68@ly3FS8>%ltcpRO^*P*)}%)KQtA|*u<_Xd^I53E z;$6E@*muF;k=oB5>^Z$XJgI_72| zk`LZ)v?axI-0U}fsYTbTqI)#A8ToqweXWSUfFpo%gs-_}ln{Wmz@ZE?y23{^y{?*M z?tnoE2Q%c?lW+Y&^1^;rwbGHy-OQ@^(Gaj^W9VO=78uh)>v$_{YwfhR47J*TWuG)` zRsNgW+dh5H2(jslLEX}frm$#w7^i8KIJu)>RJx#8iw4&jL%s{DhpIxe7BVvId7@ZS!1~)__u=I!q$fj7d?_R^VmxWzt2E1}OdTwA z642+SfdE7dp;=h3@j>F|WlNs|>7w%2QOUL?6)feA;^j{)fv>#ByATM+Z`M!hlfie{ zUT;BvM6i&Rw(So@t$&V`!x09xP1D06#l}|JMM>)$5}UuKcGNR3eh<_9vSgTZ>qf|L zON;0h$=tkjH?MpBD{M$7;CG+JrvVDxt0n1pgWsz+I(AB9ikM`=(>F{{O@q{N`Z~kqyYbu&(aZ{X$YN?zc z6YY!=!HnG8gKpI4>nD$5mil3zESDqezTe?L{oD?BtV6P0(0HSK38Q5{Jro=v>~fM{ zsxqFC*5_{jqXS00Ob#?S1L%(^sX59fuvNF;_+$9JWJ)X-X&Xh{`{cFS)7+StvWc-W zcg*BwD6S@LrWw*fM=UPiu6VW$>F|+K?r1<;rfSqV(OlD}z5bylWxPBPEBW^w_0#-Pm#O*)ogzEdVDNjvy#`FVw* zO=0w_7`EcJ#9kY5-&{tb#KNxcVyd>;Ox2#W$=0fF{WnY*`RoQQSQtTe%2A? z_ng}G7{mN9r=LcQ&zrp&V!56}PhY>>N(lYs`${)*Zwa zinD21^Vn~Wts@)jB7xVetc_N4)D_+8SkbC^Qj+roOlmZ_FJY*s^%?GB(7DY*ymMyC zo_Q-Hgy~BsUse2DgTkte#k^g@w=Eq7PRg1a8w7TbpQ3MGOvPRN9)(v6shJN?@}=vj ziQv^P&~&i9REwV{dhSIkqL1K;4O_$5rB>fxyXm1-F8q}!AE`WXhNpqkCvhK@{hmmsOgAm16?E5w%CPJ>9uU9P*;1x_7Mop7{vUG1m2+8%np$LC63kfBjFbquDM@3S!j5I6ohtW{ODV}r2vnoG1d}sc~Q@D z=m?A{J0vs?}&I-TUX`c(wQSK_+id6>kjDX-(mx4qu?g~BNqu@HEW9vQr8{mh;~G9qmE zx&0|OI1cNp$~flQ^yLyQIaNAO(OR*4xL|nOJiXF0I1|KVzM4pA`YDv8o1J)FV}aBr z{x-nUP4RKM@6O`fot@PPJ>l zf)2HM69(BhXj<@&9P7Wxzs}$OI?h&_(T_3JR~1XDmPLfW$vviRb!^VpPFv%KZCk!o z2K=Hc9VG+Uo>>Y*|JY#|m=2C5|$ zN!4ir7!f|}(87r7oBwq{_(!p-vi>uK7hsua92tli)tI1?y@5Yqjyv(?QuK+hf9xlx zsM1>BcR?>wv*OA>f#dwLDg3q3i`7H=%LO|0`W#GF)I(t^X`_$FsBJG_x7#*z?uWD| zbkFm<{t^bgY*byAbnSq{y-th>1^>!emGZ2x;rJ6UIE~69&@vHe)|gSHC6T}m?;wC& zQ-wD%a{HvPilaMliFrrR$U2AZVm3mL)6v0wt(l(`{XLt`2F65G3r^w*-rhyv)jzs| z#g(bq*nhY=P6&oHlUls@-;W*dQ4x1gngZ_{WS@pmwZO*PsTULk%^AV&aEHXsynL$J ze~p(^l4tIwyhRd&G9w@UG&L=`o@^IV=)tyD6xPa=b_y8EC-=PMqBj~#q|`KLQ+02v z@{`S|%Y8P?2qms9CS5+HwnmEJ_$@%&!T_sJm}cl=GHjx=3pl7~e@>e768I~cgtSgJ zgk5Djxk?ew*%C2Vg zZMe;@mZPPJx{ZUoM{?v*(*06r?lC`YDtBUbS7VDQJ@>DDSVYo2Kpg2m#g<^U)6tFWz2V_PGg#Ox%=dk-B!Hd}1&AlsX?67Ifh|xKA9{-GAqvC8v zp?=cu;S^nwd;2CG75#+dtWOaM^GhVZ^nyq@(siASAVRMK5Onm%HHc>d;`VO@}?CCZt&o|vZ)q-TAcXnS3 zY#P92F4M%N4}e`go#8ER-k1SpgZEXNU}K68q@fSnD9*G`@7{0KRvX%lsar{O>edXP z6T9oxBo~zF!_ESORUgR6u6LQh+IJ9x_0)g;mqWUUTPKpj|d#_WSoxYvpyG5_d~6m}~J*i^he$wj9RP^$or!StUp&G#AWAr(dG01p+Oz zqxSwBYB!cf2^*$Vy#_7!N-KBk^&{f+;Q`qYjks!iy6P{>{a!@pZK?SMOz|m}c+PfS zhc4?HyS92Zhh|8BN0+Dtzg0z|8$yB@G+q6%KL$;!<*z!j-B{AaXZ7;AlzRL>h-t-d9|ZN>4J<#q@7X zPacTLw_}Ho{@)?f=8C^0_UY8o$gpcs z7I1#)n!%f|>wO9g>kUL3{lPydly`b>>K=_a=ML)oS+4%*{-7~2f&mr{js&c)wUJWF z@u;4*>@#QLKxZ8@V$aSt=Up)tdcN43ZBYag6#uR}vt~ttW4+yb@KQY+=(M#13XN8P zN>$`&84b46DFcfN%!1XMpr?S`FL_-J48v6&PJqU(`T&`|#O9x!!JerN#m9?J!!o1G zN%@*ogs^y@f~2)Bsw&pxIv7pR5!xck?!2EY7M-~|T~kM%YxPQtsMpc2{(h=zyKrl0hdKn9X!Z(t8 zOt3PRTz&cjrWc>4c9)5hRR6_ZSB~~Nppe~io(kVGcPs(pM2`JvKNvsnSk#Za9}xYl z=bg-n^o=O&obhrifn|`$vm~}qEX$klM^J){x~#=lQU`|H`%0fIV8NCt=Xp}BwM|vyZvmpaJz_Ux8<7DOxq1&OOUvV+h^M|4qzL$Z6PM~Ms)XVg zysFSzKJ&V@z|iTO=-!LE&$ zjiVMF>(bV?uCECiaKW8b*Gwo4%h6auK5VRIHudU)EDz~_$|5LBms843R2)2xQe=aj zEgU(x)Ru(}un(#>>V1ihH!AG*)Oiw|8CE=PWThR5^Ja50V}8E1^6-_tQyHYGddZRw zEGKyJP}(G6vanxyl|MhE0&;tVkx8ZY@1@>3!}ik;Ck0a-Z7BGA?w(L3IK&(mXjsgT zrO4Fo&MV_*cLJ){cq;bVL^i`77Xj3U_|L(Pj7Qh>{dnw5g1@r*dYSYj9l{2(T8j5L zBsMR8tM2glmfvHqARC6U{frIM#mVX9OKxufG1I8LBd;f!;^k^pvI;#e-Cpm>6kJ(+ z^n!D{d=ELNRjEQ=4Y>X?P#K+W>G}R*V5GdYbCBUS)!Vdp<)6y&tWE2A88suAf(u}m zM9hp{=2>3_Du4Wn!o;lgSk!(3$(8jQ}v4QYHIc1J#zN`KbCL26^v9R}&1ns+U z({-eI7wZp1_%;o%{(g4exif0#4)MT^UZ#t|yhd0791qejKIs!T6-%B{M^uC9B2rr51}_$~dQ z%KE2@hF?cL6N0aN8L29OeAThVs$=EWYp^(5&#da+;7p^QC)lb#8PX3qiq#(SD5z|Z zuDz?<9+IzRY~Ql0vbZ7%N0|Jj{&Zei8y>4|pv8kpd7!7hWJqrE*&SX8>lu3O+p^TW z)mCgzc)a>$G7$^!KdZ6w0-p?1=}Kk$SCg?x6vLl<0}_sEKR=mX#KvHF7bTD*E0KIl zd<--_yc(EH5L%u~(f;w~Qs~KjnQhAqart$bdrtF`u0SG_(*z0kw)EYjAB6hH)UuDG zJWIS%$G(a;$;o5V1HE}Iy=)7KNGqPtTyc~A<;~#aq`Xvx5>OgGKX^D2tNl7|ysNbU5iT=hxYn*#9(U1= zsQl)je2npt8Qo2M0bKR1JE{;zDRM*D2ZbNlY^JeMxi6^P$-bo$7$M?1fp+ZCV0{dz7{iq)2AqY^xW^9qTWK%S{U>EtXX+pMnc%(m;--_H>l`Ojn zg_w_)IrzWEF7S)ACb^yxnm-qCO65u9g;Fs-bPR^ff>vXdLdNIrB<%i0#g#NoSAt}B zi9WxHY^B+h4lbgoMo2#r{{hVzSSU(YslhV>vEZ0+~-NrLCLfTsyANl|ftj_C; z$8x>4&U)HgN;1-Ag!Qt`;9IrCp5L@@OIjCHs*!2&eq#HaRxP<&lBf^L*RP&{LC&9_>R*NXJXpTK!@PH6P$je4 zJ4$GD3E%%}bnNIKwBOgyGyeyi;Xf4Nf1@iR9{_@rxvh=p2h9MW5#?cJVP#HTC^V^%YPBJ4geYzh{nfI*4Fs{J61tOOoK_>*~$uRXk+t1Nzka6nL7eLZaZU> zk8}or8pOfzqZ)vX2?zqRbF*@=GqN&qFanuCEKIB{0G Date: Fri, 3 Apr 2020 14:04:02 -0400 Subject: [PATCH 011/199] noise in robust should be gaussian, change variable names --- gtsam/linear/LossFunctions.cpp | 74 +++++++++++++++++----------------- gtsam/linear/LossFunctions.h | 40 +++++++++--------- gtsam/linear/NoiseModel.cpp | 7 ++++ gtsam/linear/NoiseModel.h | 13 +++--- 4 files changed, 71 insertions(+), 63 deletions(-) diff --git a/gtsam/linear/LossFunctions.cpp b/gtsam/linear/LossFunctions.cpp index 8bb670a92..45ad14f0f 100644 --- a/gtsam/linear/LossFunctions.cpp +++ b/gtsam/linear/LossFunctions.cpp @@ -137,12 +137,12 @@ Fair::Fair(double c, const ReweightScheme reweight) : Base(reweight), c_(c) { } } -double Fair::weight(double error) const { - return 1.0 / (1.0 + std::abs(error) / c_); +double Fair::weight(double distance) const { + return 1.0 / (1.0 + std::abs(distance) / c_); } -double Fair::loss(double error) const { - const double absError = std::abs(error); +double Fair::loss(double distance) const { + const double absError = std::abs(distance); const double normalizedError = absError / c_; const double c_2 = c_ * c_; return c_2 * (normalizedError - std::log1p(normalizedError)); @@ -170,15 +170,15 @@ Huber::Huber(double k, const ReweightScheme reweight) : Base(reweight), k_(k) { } } -double Huber::weight(double error) const { - const double absError = std::abs(error); +double Huber::weight(double distance) const { + const double absError = std::abs(distance); return (absError <= k_) ? (1.0) : (k_ / absError); } -double Huber::loss(double error) const { - const double absError = std::abs(error); +double Huber::loss(double distance) const { + const double absError = std::abs(distance); if (absError <= k_) { // |x| <= k - return error*error / 2; + return distance*distance / 2; } else { // |x| > k return k_ * (absError - (k_/2)); } @@ -208,12 +208,12 @@ Cauchy::Cauchy(double k, const ReweightScheme reweight) : Base(reweight), k_(k), } } -double Cauchy::weight(double error) const { - return ksquared_ / (ksquared_ + error*error); +double Cauchy::weight(double distance) const { + return ksquared_ / (ksquared_ + distance*distance); } -double Cauchy::loss(double error) const { - const double val = std::log1p(error * error / ksquared_); +double Cauchy::loss(double distance) const { + const double val = std::log1p(distance * distance / ksquared_); return ksquared_ * val * 0.5; } @@ -241,18 +241,18 @@ Tukey::Tukey(double c, const ReweightScheme reweight) : Base(reweight), c_(c), c } } -double Tukey::weight(double error) const { - if (std::abs(error) <= c_) { - const double one_minus_xc2 = 1.0 - error*error/csquared_; +double Tukey::weight(double distance) const { + if (std::abs(distance) <= c_) { + const double one_minus_xc2 = 1.0 - distance*distance/csquared_; return one_minus_xc2 * one_minus_xc2; } return 0.0; } -double Tukey::loss(double error) const { - double absError = std::abs(error); +double Tukey::loss(double distance) const { + double absError = std::abs(distance); if (absError <= c_) { - const double one_minus_xc2 = 1.0 - error*error/csquared_; + const double one_minus_xc2 = 1.0 - distance*distance/csquared_; const double t = one_minus_xc2*one_minus_xc2*one_minus_xc2; return csquared_ * (1 - t) / 6.0; } else { @@ -280,13 +280,13 @@ Tukey::shared_ptr Tukey::Create(double c, const ReweightScheme reweight) { Welsch::Welsch(double c, const ReweightScheme reweight) : Base(reweight), c_(c), csquared_(c * c) {} -double Welsch::weight(double error) const { - const double xc2 = (error*error)/csquared_; +double Welsch::weight(double distance) const { + const double xc2 = (distance*distance)/csquared_; return std::exp(-xc2); } -double Welsch::loss(double error) const { - const double xc2 = (error*error)/csquared_; +double Welsch::loss(double distance) const { + const double xc2 = (distance*distance)/csquared_; return csquared_ * 0.5 * -std::expm1(-xc2); } @@ -311,16 +311,16 @@ GemanMcClure::GemanMcClure(double c, const ReweightScheme reweight) : Base(reweight), c_(c) { } -double GemanMcClure::weight(double error) const { +double GemanMcClure::weight(double distance) const { const double c2 = c_*c_; const double c4 = c2*c2; - const double c2error = c2 + error*error; + const double c2error = c2 + distance*distance; return c4/(c2error*c2error); } -double GemanMcClure::loss(double error) const { +double GemanMcClure::loss(double distance) const { const double c2 = c_*c_; - const double error2 = error*error; + const double error2 = distance*distance; return 0.5 * (c2 * error2) / (c2 + error2); } @@ -345,8 +345,8 @@ DCS::DCS(double c, const ReweightScheme reweight) : Base(reweight), c_(c) { } -double DCS::weight(double error) const { - const double e2 = error*error; +double DCS::weight(double distance) const { + const double e2 = distance*distance; if (e2 > c_) { const double w = 2.0*c_/(c_ + e2); @@ -356,10 +356,10 @@ double DCS::weight(double error) const { return 1.0; } -double DCS::loss(double error) const { +double DCS::loss(double distance) const { // This is the simplified version of Eq 9 from (Agarwal13icra) // after you simplify and cancel terms. - const double e2 = error*error; + const double e2 = distance*distance; const double e4 = e2*e2; const double c2 = c_*c_; @@ -391,17 +391,17 @@ L2WithDeadZone::L2WithDeadZone(double k, const ReweightScheme reweight) } } -double L2WithDeadZone::weight(double error) const { +double L2WithDeadZone::weight(double distance) const { // note that this code is slightly uglier than residual, because there are three distinct // cases to handle (left of deadzone, deadzone, right of deadzone) instead of the two // cases (deadzone, non-deadzone) in residual. - if (std::abs(error) <= k_) return 0.0; - else if (error > k_) return (-k_+error)/error; - else return (k_+error)/error; + if (std::abs(distance) <= k_) return 0.0; + else if (distance > k_) return (-k_+distance)/distance; + else return (k_+distance)/distance; } -double L2WithDeadZone::loss(double error) const { - const double abs_error = std::abs(error); +double L2WithDeadZone::loss(double distance) const { + const double abs_error = std::abs(distance); return (abs_error < k_) ? 0.0 : 0.5*(k_-abs_error)*(k_-abs_error); } diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 1b6f444e8..8d569a5df 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -80,10 +80,10 @@ class GTSAM_EXPORT Base { * functions. It would be better for this function to accept the vector and * internally call the norm if necessary. */ - virtual double loss(double error) const { return 0; }; + virtual double loss(double distance) const { return 0; }; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double residual(double error) const { return loss(error); }; + virtual double residual(double distance) const { return loss(distance); }; #endif /* * This method is responsible for returning the weight function for a given @@ -93,12 +93,12 @@ class GTSAM_EXPORT Base { * for details. This method is required when optimizing cost functions with * robust penalties using iteratively re-weighted least squares. */ - virtual double weight(double error) const = 0; + virtual double weight(double distance) const = 0; virtual void print(const std::string &s) const = 0; virtual bool equals(const Base &expected, double tol = 1e-8) const = 0; - double sqrtWeight(double error) const { return std::sqrt(weight(error)); } + double sqrtWeight(double distance) const { return std::sqrt(weight(distance)); } /** produce a weight vector according to an error vector and the implemented * robust function */ @@ -157,8 +157,8 @@ class GTSAM_EXPORT Fair : public Base { typedef boost::shared_ptr shared_ptr; Fair(double c = 1.3998, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double c, const ReweightScheme reweight = Block); @@ -182,8 +182,8 @@ class GTSAM_EXPORT Huber : public Base { typedef boost::shared_ptr shared_ptr; Huber(double k = 1.345, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -212,8 +212,8 @@ class GTSAM_EXPORT Cauchy : public Base { typedef boost::shared_ptr shared_ptr; Cauchy(double k = 0.1, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -237,8 +237,8 @@ class GTSAM_EXPORT Tukey : public Base { typedef boost::shared_ptr shared_ptr; Tukey(double c = 4.6851, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -262,8 +262,8 @@ class GTSAM_EXPORT Welsch : public Base { typedef boost::shared_ptr shared_ptr; Welsch(double c = 2.9846, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -298,8 +298,8 @@ class GTSAM_EXPORT GemanMcClure : public Base { GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block); ~GemanMcClure() {} - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -328,8 +328,8 @@ class GTSAM_EXPORT DCS : public Base { DCS(double c = 1.0, const ReweightScheme reweight = Block); ~DCS() {} - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); @@ -361,8 +361,8 @@ class GTSAM_EXPORT L2WithDeadZone : public Base { typedef boost::shared_ptr shared_ptr; L2WithDeadZone(double k = 1.0, const ReweightScheme reweight = Block); - double weight(double error) const override; - double loss(double error) const override; + double weight(double distance) const override; + double loss(double distance) const override; void print(const std::string &s) const override; bool equals(const Base &expected, double tol = 1e-8) const override; static shared_ptr Create(double k, const ReweightScheme reweight = Block); diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index e0ca3726b..5855ecad4 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -654,6 +654,13 @@ void Robust::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const{ robust_->reweight(A1,A2,A3,b); } +Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, + const noiseModel::Base::shared_ptr noise) { + SharedGaussian gaussian; + gaussian = boost::dynamic_pointer_cast(noise); + return shared_ptr(new Robust(robust, gaussian)); +} + Robust::shared_ptr Robust::Create( const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ return shared_ptr(new Robust(robust,noise)); diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 627c0de2b..dff94c874 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -90,7 +90,7 @@ namespace gtsam { /// Unwhiten an error vector. virtual Vector unwhiten(const Vector& v) const = 0; - /// calculate the error value given error vector + /// calculate the error value given measurement error vector virtual double error(const Vector& v) const = 0; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 @@ -677,7 +677,7 @@ namespace gtsam { protected: typedef mEstimator::Base RobustModel; - typedef noiseModel::Base NoiseModel; + typedef noiseModel::Gaussian NoiseModel; const RobustModel::shared_ptr robust_; ///< robust error function used const NoiseModel::shared_ptr noise_; ///< noise model used @@ -712,9 +712,7 @@ namespace gtsam { { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } // Fold the use of the m-estimator loss(...) function into error(...) inline virtual double error(const Vector& v) const - { return robust_->loss(this->unweightedWhiten(v).norm()); } - // inline virtual double distance_non_whitened(const Vector& v) const - // { return robust_->loss(v.norm()); } + { return robust_->loss(noise_->mahalanobisDistance(v)); } // TODO: these are really robust iterated re-weighting support functions virtual void WhitenSystem(Vector& b) const; virtual void WhitenSystem(std::vector& A, Vector& b) const; @@ -723,13 +721,16 @@ namespace gtsam { virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const; virtual Vector unweightedWhiten(const Vector& v) const { - return noise_->unweightedWhiten(v); + return noise_->whiten(v); } virtual double weight(const Vector& v) const { // Todo(mikebosse): make the robust weight function input a vector. return robust_->weight(v.norm()); } + static shared_ptr Create( + const RobustModel::shared_ptr &robust, const noiseModel::Base::shared_ptr noise); + static shared_ptr Create( const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); From efc264d8ee3c4704471488c982b768c1dccd57c4 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 14:20:44 -0400 Subject: [PATCH 012/199] revised comments --- gtsam/linear/NoiseModel.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index dff94c874..7349f6304 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -229,6 +229,9 @@ namespace gtsam { } #endif + /** + * error value 0.5 * v'*R'*R*v + */ inline virtual double error(const Vector& v) const { return 0.5 * squaredMahalanobisDistance(v); } @@ -478,7 +481,7 @@ namespace gtsam { } /** - * The distance function for a constrained noisemodel, + * The error function for a constrained noisemodel, * for non-constrained versions, uses sigmas, otherwise * uses the penalty function with mu */ From 90b286f553fc7a5fa3f6951a60181365a0ffd1b6 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 14:46:17 -0400 Subject: [PATCH 013/199] change test cases to use the updated names, remove 2nd Create in robust --- gtsam/linear/NoiseModel.cpp | 8 +-- gtsam/linear/NoiseModel.h | 4 +- gtsam/linear/tests/testNoiseModel.cpp | 72 +++++++++++++-------------- 3 files changed, 42 insertions(+), 42 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 5855ecad4..206cab3b1 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -661,10 +661,10 @@ Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, return shared_ptr(new Robust(robust, gaussian)); } -Robust::shared_ptr Robust::Create( - const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ - return shared_ptr(new Robust(robust,noise)); -} +// Robust::shared_ptr Robust::Create( +// const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ +// return shared_ptr(new Robust(robust,noise)); +// } /* ************************************************************************* */ diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 7349f6304..c8e0e78a5 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -734,8 +734,8 @@ namespace gtsam { static shared_ptr Create( const RobustModel::shared_ptr &robust, const noiseModel::Base::shared_ptr noise); - static shared_ptr Create( - const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); + // static shared_ptr Create( + // const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); private: /** Serialization function */ diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index d6b133b98..dd1d46b42 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -451,7 +451,7 @@ TEST(NoiseModel, WhitenInPlace) /* * These tests are responsible for testing the weight functions for the m-estimators in GTSAM. - * The weight function is related to the analytic derivative of the residual function. See + * The weight function is related to the analytic derivative of the loss function. See * https://members.loria.fr/MOBerger/Enseignement/Master2/Documents/ZhangIVC-97-01.pdf * for details. This weight function is required when optimizing cost functions with robust * penalties using iteratively re-weighted least squares. @@ -467,10 +467,10 @@ TEST(NoiseModel, robustFunctionFair) DOUBLES_EQUAL(0.3333333333333333, fair->weight(error3), 1e-8); DOUBLES_EQUAL(0.8333333333333333, fair->weight(error4), 1e-8); - DOUBLES_EQUAL(0.441961080151135, fair->residual(error1), 1e-8); - DOUBLES_EQUAL(22.534692783297260, fair->residual(error2), 1e-8); - DOUBLES_EQUAL(22.534692783297260, fair->residual(error3), 1e-8); - DOUBLES_EQUAL(0.441961080151135, fair->residual(error4), 1e-8); + DOUBLES_EQUAL(0.441961080151135, fair->loss(error1), 1e-8); + DOUBLES_EQUAL(22.534692783297260, fair->loss(error2), 1e-8); + DOUBLES_EQUAL(22.534692783297260, fair->loss(error3), 1e-8); + DOUBLES_EQUAL(0.441961080151135, fair->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionHuber) @@ -483,10 +483,10 @@ TEST(NoiseModel, robustFunctionHuber) DOUBLES_EQUAL(0.5, huber->weight(error3), 1e-8); DOUBLES_EQUAL(1.0, huber->weight(error4), 1e-8); - DOUBLES_EQUAL(0.5000, huber->residual(error1), 1e-8); - DOUBLES_EQUAL(37.5000, huber->residual(error2), 1e-8); - DOUBLES_EQUAL(37.5000, huber->residual(error3), 1e-8); - DOUBLES_EQUAL(0.5000, huber->residual(error4), 1e-8); + DOUBLES_EQUAL(0.5000, huber->loss(error1), 1e-8); + DOUBLES_EQUAL(37.5000, huber->loss(error2), 1e-8); + DOUBLES_EQUAL(37.5000, huber->loss(error3), 1e-8); + DOUBLES_EQUAL(0.5000, huber->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionCauchy) @@ -499,10 +499,10 @@ TEST(NoiseModel, robustFunctionCauchy) DOUBLES_EQUAL(0.2000, cauchy->weight(error3), 1e-8); DOUBLES_EQUAL(0.961538461538461, cauchy->weight(error4), 1e-8); - DOUBLES_EQUAL(0.490258914416017, cauchy->residual(error1), 1e-8); - DOUBLES_EQUAL(20.117973905426254, cauchy->residual(error2), 1e-8); - DOUBLES_EQUAL(20.117973905426254, cauchy->residual(error3), 1e-8); - DOUBLES_EQUAL(0.490258914416017, cauchy->residual(error4), 1e-8); + DOUBLES_EQUAL(0.490258914416017, cauchy->loss(error1), 1e-8); + DOUBLES_EQUAL(20.117973905426254, cauchy->loss(error2), 1e-8); + DOUBLES_EQUAL(20.117973905426254, cauchy->loss(error3), 1e-8); + DOUBLES_EQUAL(0.490258914416017, cauchy->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionGemanMcClure) @@ -514,10 +514,10 @@ TEST(NoiseModel, robustFunctionGemanMcClure) DOUBLES_EQUAL(9.80296e-5, gmc->weight(error3), 1e-8); DOUBLES_EQUAL(0.25 , gmc->weight(error4), 1e-8); - DOUBLES_EQUAL(0.2500, gmc->residual(error1), 1e-8); - DOUBLES_EQUAL(0.495049504950495, gmc->residual(error2), 1e-8); - DOUBLES_EQUAL(0.495049504950495, gmc->residual(error3), 1e-8); - DOUBLES_EQUAL(0.2500, gmc->residual(error4), 1e-8); + DOUBLES_EQUAL(0.2500, gmc->loss(error1), 1e-8); + DOUBLES_EQUAL(0.495049504950495, gmc->loss(error2), 1e-8); + DOUBLES_EQUAL(0.495049504950495, gmc->loss(error3), 1e-8); + DOUBLES_EQUAL(0.2500, gmc->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionWelsch) @@ -530,10 +530,10 @@ TEST(NoiseModel, robustFunctionWelsch) DOUBLES_EQUAL(0.018315638888734, welsch->weight(error3), 1e-8); DOUBLES_EQUAL(0.960789439152323, welsch->weight(error4), 1e-8); - DOUBLES_EQUAL(0.490132010595960, welsch->residual(error1), 1e-8); - DOUBLES_EQUAL(12.271054513890823, welsch->residual(error2), 1e-8); - DOUBLES_EQUAL(12.271054513890823, welsch->residual(error3), 1e-8); - DOUBLES_EQUAL(0.490132010595960, welsch->residual(error4), 1e-8); + DOUBLES_EQUAL(0.490132010595960, welsch->loss(error1), 1e-8); + DOUBLES_EQUAL(12.271054513890823, welsch->loss(error2), 1e-8); + DOUBLES_EQUAL(12.271054513890823, welsch->loss(error3), 1e-8); + DOUBLES_EQUAL(0.490132010595960, welsch->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionTukey) @@ -546,10 +546,10 @@ TEST(NoiseModel, robustFunctionTukey) DOUBLES_EQUAL(0.0, tukey->weight(error3), 1e-8); DOUBLES_EQUAL(0.9216, tukey->weight(error4), 1e-8); - DOUBLES_EQUAL(0.480266666666667, tukey->residual(error1), 1e-8); - DOUBLES_EQUAL(4.166666666666667, tukey->residual(error2), 1e-8); - DOUBLES_EQUAL(4.166666666666667, tukey->residual(error3), 1e-8); - DOUBLES_EQUAL(0.480266666666667, tukey->residual(error4), 1e-8); + DOUBLES_EQUAL(0.480266666666667, tukey->loss(error1), 1e-8); + DOUBLES_EQUAL(4.166666666666667, tukey->loss(error2), 1e-8); + DOUBLES_EQUAL(4.166666666666667, tukey->loss(error3), 1e-8); + DOUBLES_EQUAL(0.480266666666667, tukey->loss(error4), 1e-8); } TEST(NoiseModel, robustFunctionDCS) @@ -560,8 +560,8 @@ TEST(NoiseModel, robustFunctionDCS) DOUBLES_EQUAL(1.0 , dcs->weight(error1), 1e-8); DOUBLES_EQUAL(0.00039211, dcs->weight(error2), 1e-8); - DOUBLES_EQUAL(0.5 , dcs->residual(error1), 1e-8); - DOUBLES_EQUAL(0.9900990099, dcs->residual(error2), 1e-8); + DOUBLES_EQUAL(0.5 , dcs->loss(error1), 1e-8); + DOUBLES_EQUAL(0.9900990099, dcs->loss(error2), 1e-8); } TEST(NoiseModel, robustFunctionL2WithDeadZone) @@ -576,12 +576,12 @@ TEST(NoiseModel, robustFunctionL2WithDeadZone) DOUBLES_EQUAL(0.00990099009, lsdz->weight(e4), 1e-8); DOUBLES_EQUAL(0.9, lsdz->weight(e5), 1e-8); - DOUBLES_EQUAL(40.5, lsdz->residual(e0), 1e-8); - DOUBLES_EQUAL(0.00005, lsdz->residual(e1), 1e-8); - DOUBLES_EQUAL(0.0, lsdz->residual(e2), 1e-8); - DOUBLES_EQUAL(0.0, lsdz->residual(e3), 1e-8); - DOUBLES_EQUAL(0.00005, lsdz->residual(e4), 1e-8); - DOUBLES_EQUAL(40.5, lsdz->residual(e5), 1e-8); + DOUBLES_EQUAL(40.5, lsdz->loss(e0), 1e-8); + DOUBLES_EQUAL(0.00005, lsdz->loss(e1), 1e-8); + DOUBLES_EQUAL(0.0, lsdz->loss(e2), 1e-8); + DOUBLES_EQUAL(0.0, lsdz->loss(e3), 1e-8); + DOUBLES_EQUAL(0.00005, lsdz->loss(e4), 1e-8); + DOUBLES_EQUAL(40.5, lsdz->loss(e5), 1e-8); } /* ************************************************************************* */ @@ -665,11 +665,11 @@ TEST(NoiseModel, robustNoiseL2WithDeadZone) /* * TODO(mike): There is currently a bug in GTSAM, where none of the mEstimator classes - * implement a residual function, and GTSAM calls the weight function to evaluate the - * total penalty, rather than calling the residual function. The weight function should be + * implement a loss function, and GTSAM calls the weight function to evaluate the + * total penalty, rather than calling the loss function. The weight function should be * used during iteratively reweighted least squares optimization, but should not be used to * evaluate the total penalty. The long-term solution is for all mEstimators to implement - * both a weight and a residual function, and for GTSAM to call the residual function when + * both a weight and a loss function, and for GTSAM to call the loss function when * evaluating the total penalty. This bug causes the test below to fail, so I'm leaving it * commented out until the underlying bug in GTSAM is fixed. * From 3f8bb104053a3d1451c9d03878f310aa53b1c84e Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 18:44:56 -0400 Subject: [PATCH 014/199] modified document, remove commented function, add deprecated distance --- doc/robust.pdf | Bin 197566 -> 197679 bytes gtsam/linear/NoiseModel.cpp | 5 ----- gtsam/linear/NoiseModel.h | 12 ++++++++---- 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/doc/robust.pdf b/doc/robust.pdf index 3404719b492e481bb77b96853eea0fa3a2fc39ba..ef8dc6fe624ef0af97973b383042940993273752 100644 GIT binary patch delta 2581 zcmbuB`9Bj51IKN1-$%J}tTG|Bi_J=7aurcx`1W0Fvr#?H2^FTfrYKj|q&bqucbHr5 z9GNQ;5$cPm_)4zOG{^IOJwH6J*Yo`Pe13SpUZ3}0@NP|%EoaK6LJ=r51`M?aUjf5m z7#J9CW(FpJq0V6V-_`~UN5Ehh6EM^X{5M?xmS`jbUP*)it{@Qz@c#^Y&Ki8h+=q;y z5-}!7D$I&r1cSklWFHKfXhI|+&?GX23OAu(C}af6 z42_|nGd=+f&&Xd^{G;-KH8(!Se(xE0c;^^1(;w8Y3OZ-2A*Xod8kCuQQ6eoQ!FwGF zQkkPa#8>pnCO^}=r6!QXCtrhZGiaL?xFgu#-eZ@c0L<> zL<1RzgjD}1NxtkO^mDV5Mxt+BeZc2L=ZFKk_^f#fXr!Un%bh~griQRJ zT-5u53K&xHgL+B@k|WDmW30FvoU&siXb|D)eqEJu_*t3z!j*l0)~32c%^9BWfWc8M z=Z+Kbcs4!f6(Lku)g;pmI64gTiU}sV{V^BW&xC8%ait^^w*OH}O)lB#rb0Zhq2A{O zEgu6Dxc;*!SH6Lv-=}Z~oP{yB07ADuDxKz~5Y^BbE5n}V)ejIBpr_SNh5K8)3(u#G zpbot^T}DJs;X6^1av#jf!k)kM^V`bZnmd9f(C=JoBJ3-NXTdLgx}Jh&)~s1J83jD4 zPD(L_8x$v{pX!N9LKzh$k{PR3Z5^U7FDMFD>W7r?;;zBON<=u_iOOoC_Yrrip zP0#!04yr#+ry9@U+iS-iui>OuV+WR(cI~nW9W&o#i#kqB-F{0bvdm}TpSGM9V#J3W z>2vj2%6r@vCmrYO|4h&J6SGUli{@Jtq_U+UQCCS#eo{k{9GjXUXLTz@q9-ctm*qi% zi)5vqjf;TdnJ=)7Us6K)Jv|Ve7aHt7?sIP8O+3NSD#c@R^!JHag3UAJ=_@k+CzA?7 zLZZ~eVlpyQPLBrbYEcjD@zzXaMGkHO=rOnBDwc2~t@y9eB~_3F->}f?QB!7CLH&A!A8yi!El(k^(ZA zxd4xnAXEP~7mE4$GK{0jk~%$WQl&EUj`8!Z7cqaefPLcffwy9(- zE7ADvNkz6OY;iKC^oBQcDnZAwpat|>U_#xU1|LB1;-^g&oR{D+Iwk|R@MWE5EBo{F zgNcZN=@S?*m`PgnqrdJa!^?Bot2vrK-q=QP&|e?Ib)u!`(hh(9Ud?YdD~Wq#u$-Mdf&xb2XaUon_=^+x{=}@1v0dycKT<+?HmBz?Q_nIq7NJz zr^0aWl#^UAF|Qm)D(6#oydNq%Wur7+)LEj?l$BpC#2x7BzN8D z^524B<87@c>9Hq>PHe5x`W0{d5&4;C6b|bGJ8*sSWk*q~*LZ{2#@BAIIEm<8w>-?W z>3AmhR&ov_QB6kk?y5zVa0FqwSzM-{YyUT z2VJqsZOx$yfvO;=p=;c^#zKwt1mMapc+1o>Xz750bPMqQ_9~Nh&keoin$H4#+y)L8 z4&Qlmyn>s2$vx()>np-X4euhoOp=yb;_x7y4j-|($kN)Wmr9xH;`BVock9ZRa^O#W zwz9ufxG{Rla9#YWgayYeC$QTE%ga5#J%r6H2x`GD7t++7u8n?04BiiX3tZFOhd<7& z(+g^8e6a6OFaBb2xrO|r;;Q~8Ua^SZxI&U_OUZ^K%3WrM>Y<%W6#qlYKm5q6`#GL; zoik%v^~oCMtY2-6e3jlWGCTJjwD@Qt?+}f?RId}m5Oz=-WJW3?;i}#$!Q#Eq3*3}_ zsQ7cA_!l3SaY3kJ%+KTgpg?7QJ`KcV+46B9hsAi*|Q7@yv1tg;Okng5s zIT4}i2RWk2bO1HAM+sE^NUYS!U_hFBL=m?y@t)R6jD^T0LgWB1AacN~8xp1ngb4x( zW8DLQApbda0MIJ{GX1(5D;)^3qyPVjgeCk}dyq*Y0DW72Nr%}G zc$3R{bAozU`Y(VBMXv}fm=kYvs%qCsR_~3dB1|+lvq=SLo4+WlTrQ)zDBT}?U}OkC z*x`$!iW9^0wX%c-5L9Vy;Uoxjx|u9=OE6DHILm1WxxNVk*YBap22lHPo zE^ZDw$B<}nGct3sf)?d!vV9QD6=F2wu|wI&tT~N}DIT(~YFyc^S^Ko>=G(?pzci8e zyWvuCBXlER6o0;iJQDFxB<#30qS)Rt*Y0HCsE&dThaf$C%b~3B>9?B~Bnvzk)0yv2 zOG`!M=|V}4!(q?1-R&Vc_B&71=X#*uqvm6myHrqzHhK-7kFx2?F+VWpnc>jS&;fYK zbT_Spf4y1nu4<ZS*ON)FH;-Mn{2^y6TSsn@2mit`Y!A|&I;MW0$;u%^#)(BnXJ>4xRDy0Ad9bE8s^ z=N=-i`*@eOMAY!3`b}&8*yl;=WGK2LbeVR2(S1!Xm_e>A`t?R2f39k@Hq%S0Cx9>* zdO7cRyq9ur7acmZv++z@p(B|Rp1eR+o^i07bg-?d$YO+}(UW%&^j~sGC%yKvbOUx4 zjYBK@8%_~0aZIvGj|PGxGongWeo>|Hf;rx0AK))`^ZD`D8nIaFJ@ZXVDjCpdrX}N_ zO&;{cc%o{LV7Fb$ejVrNH%Hh%oC|6nPrvXnjHRTawy$$uOY7!ui7}v~r1-kpv^a5( z9DiQ&3c1f<3`AZ*d=Rv+_=A}quf(#LfT$hT)XEkzRv*DxUr@ZpBLmK zZab_f_KV-1dL?Ad=x(xhtxa0_8aeX}%@+s+^PdUePUkvQpsn&X`Nx-r$CEuKn(U|j zj}6Nam-c|)%*C7dhS94AFNeg6q6&SHh~R*|U$QSFE8Is~Ug=f6a<=vFQE$QWEN2H* zsW_RpDt01O1M0#6Rn>x4lfMAI#>ZYJUwRAP+%N)F6U@Io4*OJX;9ls~p=-w5QWZ}0 zcD1Z7i5@pC-MGO~@(?>M75f+Sa4k9-NMY7}19;?DNjTaka<92xjtC!G{^u9{ z;d=3R^sb_z-mauOK|KzjOZHC=It<-tuVL$&gbypSZ0FX0%vY<-?TFp(`e8b|A<4)F zqRR(foKhRi565;@8hy0x*cQ2|xUl`^Kr%%A(nb9Qx+&(Jx$c2X0R&(+0h(zmt5$|%zXb(*f8bKS5jpVrcg%I~+gHR$q2=0kOh2Ix$! zFEX}>xHJ!oTTjcW!HMO1k4TMvt|3`t)|DsIC&W}F$ZV06I2nD1`@LsY3$cY#3($E< zU`=wA>nc(#H*pvnq`G;euJ}B}>fF5Q-c>*Sb;k#^9t~~vtiW}Fv?t#`MV~NL&xfRV zB{?9l!U_I_8@LEf^0HZr#mTmnoKh?iSof({3Ge7W4I}YTT$Morjhqb z7iGHoIBL*`cmWLh`e^w6j(c*QFC^-bl(d519V@OC6qMM@ws(}&_|e&c zYpZte4=7G5%$OPVca3-M8mm|S&W)ldzIp0u%(0nn>)GkFIcHJmc0_fRdZ+eVk})cC z`87^CCO7<5j2es0djB#EgkWq1rmWDyvOQLim0{`kb!ar!_%@yXR2wV#KuJPYz2aU!uI z*;Ch4-^wG46AuU- qW7#UC*2{_Hy!;E0&0UhVEu6c~T7`)UgbGVg|Dl&tg(||JBYy)Q=x|y9 diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 206cab3b1..a7b48b034 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -661,11 +661,6 @@ Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, return shared_ptr(new Robust(robust, gaussian)); } -// Robust::shared_ptr Robust::Create( -// const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ -// return shared_ptr(new Robust(robust,noise)); -// } - /* ************************************************************************* */ } diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index c8e0e78a5..73484799f 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -94,7 +94,9 @@ namespace gtsam { virtual double error(const Vector& v) const = 0; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - virtual double distance(const Vector& v) const = 0; + virtual double distance(const Vector& v) { + return error(v) * 2; + } #endif virtual void WhitenSystem(std::vector& A, Vector& b) const = 0; @@ -713,6 +715,11 @@ namespace gtsam { { Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; } inline virtual Vector unwhiten(const Vector& /*v*/) const { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 + inline virtual double distance(const Vector& v) { + return robust_->loss(this->unweightedWhiten(v).norm()); + } +#endif // Fold the use of the m-estimator loss(...) function into error(...) inline virtual double error(const Vector& v) const { return robust_->loss(noise_->mahalanobisDistance(v)); } @@ -734,9 +741,6 @@ namespace gtsam { static shared_ptr Create( const RobustModel::shared_ptr &robust, const noiseModel::Base::shared_ptr noise); - // static shared_ptr Create( - // const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); - private: /** Serialization function */ friend class boost::serialization::access; From 99761a1a71e8b7ef84819f2fbd816140c2c91ab0 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 18:53:00 -0400 Subject: [PATCH 015/199] check if noisemodel is gaussian, if not throw exception --- gtsam/linear/NoiseModel.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index a7b48b034..b2d05378f 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -657,7 +657,10 @@ void Robust::WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const{ Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, const noiseModel::Base::shared_ptr noise) { SharedGaussian gaussian; - gaussian = boost::dynamic_pointer_cast(noise); + if (!(gaussian = boost::dynamic_pointer_cast(noise))) + { + throw std::invalid_argument("The noise model inside robust must be Gaussian"); + }; return shared_ptr(new Robust(robust, gaussian)); } From 646a4b7f0ff4a9c327ab5ada04f07f66e6fee77f Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 5 Apr 2020 19:00:09 -0400 Subject: [PATCH 016/199] change unweightedwhiten back --- gtsam/linear/NoiseModel.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 73484799f..a9f06693a 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -731,7 +731,7 @@ namespace gtsam { virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const; virtual Vector unweightedWhiten(const Vector& v) const { - return noise_->whiten(v); + return noise_->unweightedWhiten(v); } virtual double weight(const Vector& v) const { // Todo(mikebosse): make the robust weight function input a vector. From efcc5c908eb25290ee29f04b78e672baf40f0000 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Mon, 6 Apr 2020 10:10:46 -0400 Subject: [PATCH 017/199] rename residual to loss --- gtsam.h | 18 +++++++++--------- gtsam/linear/LossFunctions.h | 14 +++++++------- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/gtsam.h b/gtsam.h index 8ee778f4c..1094d9dd9 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1458,7 +1458,7 @@ virtual class Null: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Fair: gtsam::noiseModel::mEstimator::Base { @@ -1469,7 +1469,7 @@ virtual class Fair: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Huber: gtsam::noiseModel::mEstimator::Base { @@ -1480,7 +1480,7 @@ virtual class Huber: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Cauchy: gtsam::noiseModel::mEstimator::Base { @@ -1491,7 +1491,7 @@ virtual class Cauchy: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Tukey: gtsam::noiseModel::mEstimator::Base { @@ -1502,7 +1502,7 @@ virtual class Tukey: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class Welsch: gtsam::noiseModel::mEstimator::Base { @@ -1513,7 +1513,7 @@ virtual class Welsch: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base { @@ -1524,7 +1524,7 @@ virtual class GemanMcClure: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class DCS: gtsam::noiseModel::mEstimator::Base { @@ -1535,7 +1535,7 @@ virtual class DCS: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base { @@ -1546,7 +1546,7 @@ virtual class L2WithDeadZone: gtsam::noiseModel::mEstimator::Base { void serializable() const; double weight(double error) const; - double residual(double error) const; + double loss(double error) const; }; }///\namespace mEstimator diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index d1c3adb35..6a5dc5a26 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -36,12 +36,12 @@ namespace noiseModel { * The mEstimator name space contains all robust error functions. * It mirrors the exposition at * https://members.loria.fr/MOBerger/Enseignement/Master2/Documents/ZhangIVC-97-01.pdf - * which talks about minimizing \sum \rho(r_i), where \rho is a residual function of choice. + * which talks about minimizing \sum \rho(r_i), where \rho is a loss function of choice. * * To illustrate, let's consider the least-squares (L2), L1, and Huber estimators as examples: * * Name Symbol Least-Squares L1-norm Huber - * Residual \rho(x) 0.5*x^2 |x| 0.5*x^2 if |x| shared_ptr; @@ -135,7 +135,7 @@ class GTSAM_EXPORT Null : public Base { Null(const ReweightScheme reweight = Block) : Base(reweight) {} ~Null() {} double weight(double /*error*/) const { return 1.0; } - double residual(double error) const { return error; } + double loss(double distance) const { return 0.5 * distance * distance; } void print(const std::string &s) const; bool equals(const Base & /*expected*/, double /*tol*/) const { return true; } static shared_ptr Create(); From c54346cc590a38431e34af954afe6cb311b5c2e3 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Mon, 13 Apr 2020 15:17:36 -0400 Subject: [PATCH 018/199] modified document --- doc/robust.pdf | Bin 197679 -> 205572 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/robust.pdf b/doc/robust.pdf index ef8dc6fe624ef0af97973b383042940993273752..45c023384c723a506f5bb48b2bfcab5aa5b338c3 100644 GIT binary patch delta 89002 zcmZ6y1B~EJ^exz$wrxz?wx_3U+jdXezqY4s+qOAv+qP}J@4s(%vu`V@-(ZydO{~plV#;J@%x28R#A?RGZNkjW%Fe`UXlBf1Y+}sJ#cj+iz-P$H#=>dJ z$%Spg%Eivi!D`CM!e(m7YQ|#1!p+9Q!Ns1i3rZk$(Q9LjJnBv`!SEvvACXwem^w@a z4m9qANVxD-9+~i3y9RD2W*t^xZ7G0PowSRyM#g~xR7znASHcpD1veJV*97?8{! zgoBh7aPVIZ4q%a>)Uf{-9(yAzSU$f0uo#+~IuWxo{cngW9uB6&j3S24hBo%*2^K%- z0cB$D|E^TV)Xv=5f|!|=gIGWS*2&q?)X)~zJ=560z`)4B;MT;z&|t^P9NEMVj4317 zA7jLXyEpe{4<;6+$9NFD1lw4&r2uo`Q-SVYH<~SgPQ}F=16r_w zRK$eiq$_ zPHC1k<;oVB6vyJ2v5bnY+*bsnc{B|;8s6JySh*3Y!6s>{tp&{g`un436g{CHeq5mF zNnHjzj-GP9JJ(0{D<^p0W3y#tqvzW#E7_QU^{PIToRJI78Fd#(rN2BNdz5u6ZI|EW zVlqNmlE%jBpg~*aovLJ4SY(ocKYukEZJT-J>7;6G zL0?x?#HD>j#OTI8y0?u>I@jiQ+r|Xxg2qpM-Q%v;C*OB5l;2(Ofs?fi*)D{FOI_>> zD`@-9$zrGTYHOh5b%LgIOSNJP=%4XX=dWBfDk~%zAMw^uR~m++ zkdygChn-=Es@E93Gg@K~jSPn(GepPC;ZdGIh$matY!)EVfeCFTXSZqOd01Uq{F+%@ z_Y_ZmHe{me;$D!XPclIiQ5@e!)3Q?2cm<>XQ-eFETXSwvRa%@?W*L~y@pEW9%z+$D zD+Et*cC_C#6FdOD_3#$k0UQ1ak1o~K4 zPGm!QYz4Th=Ln$=>K(0QOi<#U*Lda;$_V#TKlyp;DnrE#{gH}Er5|7eeV~||f!CjU z>$;60s#J0F0;`}0JBhMMPYB_}5h4e6hXo3MnFq&YVGrV%^$n)OVceK|+rjh)mEaZ= z9|VbgaLdlWr#XWWyCljGmB=R*ejxUEGk0@|&>!&2G@e5}V4IJJQf--J@SslC>Fq6f zxHyv&j%p>ZA8l;ESL*neZQx4+pSG|jq3EoUFpnBk8tO9E%T#gXe7m1t5=$W;>v~2C z(PR{mQzTUT8vjMI5L<+&!DEV?Dnnu`saYta5rh}RD0n?w=!2oqfgVpiX@28*P?Nbs zj{?M9c6?N+j|~_(jFQxS+h}ifp&x^(Wb_ixTBAgk?dSEr zpwc`gv(sxQ>G*fEC|FbD+p(viV!|haI2Gl9V=9@iuxjP?I6p1w8X3ccglu1rr$ zpGYCUVIrvW$-4ySGy?C1aZ{)SnYJg>xjZA?#&x>9a0=xyKR?}aE5Tr|EHu75zfc1!@fUE{3k-?TC9EmZ+Z2vM#w8_ zrNN~2^6T`N-L|!NnJg=cjGFXv%EDQ~K322!>;qt=xAF-55A^`}pIKCS9WyZG4ZtiP z?o#Q4EzrkU#ER#BuYCCci{MY0_|)__PvE}KG>H~uP06rk$9j^eaQY+k&XtS$$1i6H zl%zJlaBU+e#7TZS;GEJ)Dsl%ZD3BoL(hqp$LUzCDs*&W~W7Jl{zcodBwE=o8&!SI; z@@v0V-0ucL&9Fj@bO+@(f$Q_%-=E5=gul_GnBF;y3($IqD2 z&p(j;l}^K>N`-E0G^LUN9e-XT%Qr zKXjNBVA`?aX7f0i`cY4JiZ_R6L0J~ImCiH-!2Uwfe8yuGP8xqM69MhI8>KK;8<1d- zinu4Q6Q0uo4ehV^U~(#)hn4NGI*s9x7Vp6GzEeBVG4{NU(L`flcMu_YbSg||xwxJU z`~C|TEk(?v5$w+7li_@2xxuHLl>}sL2;8f0Nq_E)CCYpPG(7ov4rUu;Wg60ZoKZdXy zP2;gno6DJu&k)`NNw%!Rww?ZkOH{a${u1u=+xvkxH1#g{5CG$S>zpnvW_o%xacL-{ z9#?FWcO9`44?0Ttl>b-a(kZvJ-)oCd#jRGd_|{d$PF{+WaG*Z=I8^ zbSnER}$wss9^5X8xIvm2hJX;@gU-jHX{GoBhGu2-PE@xVi{g!R@^}Gc9n0ou2 zkuR*_+mcmy2Xy0Pb7^tGqg2a9UK!!Xcc}PI%#?%}ZK4F5Ji>-~1TV@2b1Rw#cXk?z z1cN;IglcU}a84HH|Dlb*f28t1Rw-ub=;Tby#>)PG(1=C6Rl9YGJD;9>BDcD*)n`z6 zu$KwuwjtNd3HUpq^{6VG)j0`Aiq)EJ9xWy1Lew=FObucNj*LZBT{reYY|26=J$J(Z z1+7%7OjHUOg8W+4FH6HDhc&p0;1)>@(qFaxS^$bN@)8U=`;L1aI!L4nSY_m|v;zn_ z1v!u1LIpw?>b!t>A%#*1q%0IIFmCf;HJGcc8ORfE#zr`?R^mn|9)|vCkkP)Wc=`T; z>ZH2<0W%Eb=USH^30r<_Ed6qZ=djg?qJFeClM@rNZUV5et~jSpF=fzrOcNa{lcPTWiSH2*{bM zAMd#-c9mg8nz_=J2OiCzbaBIXa1@KvKmljvOp&l;<-K5mXg>U~_xZ>+bq9Ww>_x%z`b05qPRO z$7u&2b)T7FG%GkYViB=MKE-kwQfxgqxbnU=T?2vgi(u5`U+kDY-1CfP=v&{|`Fy)M zdD+3ZT_U$fZW++Fzk_5)+_Qc2AnNAz`Fdi%5qM=!?lett@usrgoPOJUAK28_13B+{ z#&di}yx-xScw{;%&w1@z9Y4002PBW{531T7D-f+&qna+vKObIpPIn1weP1glwVy{e zRo|G}e9p{$AKnbUTU!3{`3AZr5^OnQU$0ER+k8I^R_NX}HSh3GE!DN)V;T!Q+;8!E zwY)!I?fATOPp-SBh0eg-_)9&1P5}I#zV&VaQ%iFmF=LyM=9~)qcGAv7070j_kJ!=^ zJ!8sdBc_u0p&j-~u%qNTdi3)2DFzYJ4yKqKB;S)cu$NYV33)2MMk zZI9%zmWa!CiM*TxMM>YmSp1``N7J(Ax2SPr@X)DIwEb z0`1yqN_9`axbr$qX}?VfC^=fRmH*Y<%D4^Z649t=F8D$wQijo<{#FOPfVYnpRywHR zFT5?xOK@f73fQZh#458#89Fn!S}-$t^T$hXt?BgjNJi;j@@5Ggr{80GNOrtE)0o>N zYHgEHHhG?|;M{IR$~W)J#{e7F#NH|bK1Fh(K|+tnMkztkE>tVPxpfIa*j9@c97lLX z!2eA+;w**zL1CH=vvje8GI7!CFWpAKXU1LniDK3@Ut59~H6_|289rkYh8ugIVfkgJL)^?o zL^l)+tITKBv)~iJGPo7>*$mz=_0a12kNi@>5Zx*G<#BF^_xUu{!tW5om?Vi&{{~KQn{0J^%vMY9)1=I^XwwhT&hn-+uau~1RtUgbzv_h~Gv@1Qyc4Dc*$&j!xzGz~O z)YV)+6z2RNI%btBg_c`C`iN)I+>g7l?WGQN#(rz2c);rcU}_FDH9M|AnZm>dL95p`sL4wUz?#mDvdG(UGxF_)$7VrgWf&$e4rZFgG0WU5`*T7_-o)@b z>9=IwjK35V5EbnmZZZLX`vWdL82qz>sh$+U4@Yob@0M!Llr0rAaSz+{QVIWn=%+$~EVPO&664s?^fS}}ql5{1Ar~-C z=j@3c=6A?3Ba`@CrU>SHFd`{ArJoVW62yj>PvO$Yw&a97srnJkfHs_PLHnk)50AiItZ=j4(nJH+MF?X`bA4lICT5nZ( z`e?DyERl3E!!$X_@!S@b6F;n#4GkKL%rewD`G|C3k?f;Ve^?cXKb#DM8(aN!?(k>x z=|a4Fds16fiUir?JrvZvPPb)0`Nge9a&7NRt>qtWNMB%1e*S3xSpxq`yZlrnZ%)>v z3ososp+Jc0qP`0G4S^$s+v2&ZX-F&3Vm^dgLS7=<_Lu&}#-NsX5DLddphLsw1{0NW zpyuq(EeP{`LSfb^#7xV_VBZ^A=i`5@YBg~+`sqP>k+iX-lyXv-2UPBjZlh0mMIk>>)oK!Jqf#`#hx7F++A)o! zy(5;_a4#yIk9kBo>r(7brMf6l+}9g5&?6kr5k``Jx;)XA?fc{}sY!}nI_~0IKO1qJ zD~7A48(m7gYSwjywp*N*nvTaV29_u25L+bU`nYy`#~T-LwXvy^PzDu9Seb%l0|iZK zJUJ{9yJ_9VF2DM<>)ghTx-gxcR7(BAlK4?#;Lc}l#)~~=Ni+JJ>Tm{TR)=HFO#{*8 z8z?b07uP6Hn5wB_Uax~?C`BTfBX#MQ@Uuu<+Bp>UV@v17bojDx#+ck6@<};T5zkRX z>AKy+H4MpdsktJ&iAuS}AudEwfvg!_LU9SH2pjyL7})kONI0~?f-ZBhc`=4f)(6T~ z1&Pq-(m(S{Iot1MH;r@+yfbyj-=OFpE@Ly?MIuzk{$7@_%H&T{jM>7g((2-k=*85x zjRo(APv!Kqifz-pA&1SsG=H3xdYe(;EUUX z!cChGU;H3_r_P3Q&k#(s&vZ4|wv- zDRxlZDxkBy(iq|rl)@-4=-u(MLu1kvKJd+GQ|o07qiA#4oG2f~dZ5ZIxF@qt8Fv)Z zr)?ODtPrHI%B)IBr4M2wuBJxAWp*YXm$mGqA)lNKTT7=01=bYb{J`k>Y@nS$dO!u- zd}lWpn4H3_da?y<0WtMu2R!}_y=7MK$FFItmbDth@`AI%@{0Sj{PxQ9v-0+8vBlQ* zGP?>%_BPvcP4*hh#l34u7xhnFpI59ez5WFvYBGSWy5{I7fK%VX`AX-D6_be-!{*99 zrhR5EaC2WU+v-317z15%mQj39yWb$nPpEsbr3cFLRoY+y*iGH+SKd8m?xp0O`6MH) z#T?dP2ckPb_X}2Jt236XFJ_!!qyJIsqD{Q5d*gb8NEzL%6lb2dTAL6{7(c5iimo=7 zZJ1j)J`)6YF;!51SsO2mu5R33SR7KP`D~9r{c7(=LRu=1FUp@Xe-vf46JU4}Q&&Il zxF7WNW^LC2w&{u&E4%S^7xwRGRoQzw+RCsBMlTO71PGS(m(U`Q?(>mB(-0p z3AZ12TdZSkw6tI|wANla^VOv}yp<&tw0m|HiU|}$7nL1|!U{B%8PjpNCv*POV?3L& z7x%|!hhvKNC#oqIy>+H*uJ>8Qj&I^QTy-hzXpHv(@Ej$a7^ZR!g4}tc%IH~QOJagr zCfpva4Ri`y*!iy@lSsPRPYX>s5=IBaR{s(64#iZY2JBZx^55jVzi`{AP2MX?Z6PBC zw}9tT3VgPGQQ6a5m>1TPk(5|6eUbE!VAR9Wle1#TB8T>Wz26O*1}BWetc6G(4@NB6 z8(={|SV^Xocg4{Ys&4n|c{QPN`k+ik!liqbeNB%{O@_9@D-p6trl-AltcUt57LY|* z%x09#-CVri!40vZ?}i2~;^`;px#bNOa6fyD?{r!C8E$klK0_50lvbeNiq>+9-u8s$ z+l4a<@Y-(A=ZhP3=vQpFmd2qZvlEW5*r)=l!Y5`NIH^8#Se58r@iD9D9iPmWJu8BI zT5f%RW({Xm<%OLe_$s&1XcpXTxi>ku5!N|1Eof}5#w|GyZGhT!T1u5S`!VWka>^l4 zYzG5Gt+xuP;`PK+S%0mZy@xS0s1YZ@jz3y?Cs&cS4~t$er}Z#Nd6dVl2ev-wtF!H{@lyg zcD|IyMT|yYlhSu+sJid})Q=?WTP&eD*M8=#p!qK)-;5^0oqBzwSs#f?$_2zK`KXFt zJ_+Nnrkdp?;7CzJ^iBy^+)S>f_5e=1sJmdJ@EhaQS=4R9LN{MSoYgc(g60to3j2SO z{{JoSvk-Iq=UAl7rh{StT>qH_|6is5Z{rUYv@a|UImtk0DrTWV!-5XwQ#r#ZP*M); zf(|?s7!1qUE7Vg=WQam?^1>pFGOW+1>uH%KOs;(;#i`bBvqmi$AB;LVRLpM=;x*Zbn8nG8+xn))0tW^wAdz% z74eRr_>~+;EC>i09U>|U6d34-Q0|I;1au*n5XuE;1E|Ff7$M1y0;jjykDy3SR5SCK z_P_Vb`XIbP;2@}IXuDswh_Ox~KMj$Y@N+@MRzK#F>N5C7;WF?oSu%txw`I)5?>Z_w}NIfCGrblok5Cv3fY46NI_ZzWaRWatjG4gtcs4lUYfZmkIDFs*+PXOxwpEZT&20ji4cyk3Nt25t~!#uIxtK?1TtMO%4O+jToL z@T<>61o771&3SASj%C71#H+!ZI931a-LtXLtO;XR;OF2P(ywUu(sQRAM3NV~-tBe& z$*m*K)sJ@dzC4Zz*;4nZ8uGUTE(a9<=nPR+`9t|wE$BOD0x<#%8g%eQG$f2uau?tq)MGt<4)DXP&we#NY&z}o|K1XnN{cgY0!|06+ zZ2%sa3$moZi;e$HblqZ9dP#J>{z_`72g15T|0x8rQ!~B&O=pK=7U;+8@m=uc_0Rh* zM9i_AM+Zp$;G|-VxdD5*yMY69e;EXV{6S)KV~K@+2NCUj>x-`$tmK4$jB6m+MS_HV z#$DSMe2uN{%cItQw~^rceZS59-cZ7VHTVuaJrW`zK6rwA_?~#)ruYWfz7G$-#~!{X zB~~{_PdTT)Li@j=pm+x|JHHoNi>i6gToKriTgE}Y^;Jnvh&n1joBZ2&zZrq@5U}m) zK>UrV(`&K*jYLB|1w319Sfg(!`QPEr~w)3#b1E;XgvkF7t6ULjzghl`#0pxZ9ht>Hd?Q( z#}|k;1nT#)%nyGM0c$dBFc%p=+m{*kNm zl^iJa0U|)QaDlT*LPS6N5xg@kM?#Ehh{$e8FIawX<#ksXBjIDD%jwzIw-4|}+PHj6MkVws zzVevBcu=IU%!sn|l>hUk;T?8A?3h;xMSHz!le-VzE;?l0ta~*3NK-8Dj(O#EZ0dS& zcjkMm$MaRM_6_NaPL(~mjL~S&-4qRPavBBPpGw^qpOU@5keQpR8x*NOQg`Z2GAXx+ zr}$bO0@#OnjN?Oa@PI*)m~lzh9T&H~hYK{#rD41w@#)r^Pq+Oau->vMuV_=0KA2+< zubVs;L^J7gGsfBRKGOTcMH4x>+wBBu>(F3 zi#|0}RF4wW+C-5NjGqQe+Q?s0WOBKjfl?oN9cIzNAGlkjRMf&>BTd7iSiGw#RPb@) z7FPepw7lK$Wx3Irwzwb#pQ(LDsg(>au6AF`L#e7AIQBv}2g+7h0>^z|83r9m+XA)@ zi^8=+_}`koB!NqK#&AA0I1|V+n=clgDcN6`meH_sQiF~&Tb_QG)8YY!y!ouh-GrlK zxRh;zV1T!!i5wEuyCH^j9Q#{a|aOlYiss8Lpr`1+*7&lfFwYx&%s`*E5x9nVAQ-jfxYoUpj_N6R; zOAAZuYEGlD5220H*O#&c&enw~BUhy=t&|;pS;DavlOB5sHWNlDD}Ah{$LPBbMw`0U zXL24@2e2>xTM|D#i}N4?JC6FT{ZSutrLhjVPFxU}$yV3K^0Y7-n?CKfc(X@y4Q1Je z6zc|kel>k}r|QKG9|>ESu#@S#r5}g*7}wo0>#2UxakOHMl-))e(`gzl?eobeD)(l_ z?($s;soq}BD4J8%Rb14QGuwgo-a?_qw}DEu3dA|qr<$zzaEBn<+f+twOsRVkY9qeu zw3r1=_w;^DVym8B|KPxA8QNXx_!@tj zB4QcIjtYn&S=ENtm5s~fcQ@ppIMPg!+fsC7pUb`J>_dW2$b4mT4& zm$JxJo8F|QO*Hi0_u+jv_R9ZE&*Ap;02E5_U*)Be7FKd5C@oVrb-|)qx;JNA=vl1S zEqeqH8fp(S_~re`6jS$VEI7GCycJI-uX~hdw1*U;|JZf-iuznJLohCHx6G%sWcV1p zGsr~#+%AnG&McJOxeeG{)=GWvJDPARefVr}nk>HgcbZ6KVrq}w(}C%4_TU~`3^=xB zH-l`8LrGP8Gd5bh?8Ip@A4VC!`ScKb`7w3H-~K9J9GTfVxDwg4-gcz;>Ycu)&#>W5 zmoR+uKPy?fU5$QC&SP^LG_GjXR$W%nTp$>H4pDbq;V~(&5cWx=1$*rN2ZbAhg&IgV z%|K`FrP2%ccIlY9bP~usATGy_8&n;-qiwSoV$KgoA#6`MJg3A5iXW87ky5HO-vH6TLF#S56>CjH}k&r;h;ra zWMOkVBje+9-T82_1CwFDQN$6t8`|!N?{VdfJhKp>_x;mX$v+2-hJ^fG5->seYEZ)7 zj^Q|WjyKHK4rk-)_%erHHej_rtRt`En;qdraYYOWi*#Td8}4UJVASnscd14k$-?|s zMtidbuhDiT>kb5(5@=f;HW`N7D0gujBBo-y}(f$ zWXPQZWwsiMV6Ku5Lmio-2fEOa-ZY*ZGLES`jHr-T+!dS+&P#=2L<})ARpWTBMe$mC zDGo7aEzwIoRb)WmdfiAFqDTrlY3`%=Vq&H%7RT%nST?G|U_*=K`63kbi(elS*r|h; z+~&M?e}u5$UXnL(`3}O5*nG9WYY*wN{(MQ)=KAlw0>uAhaXy|50@l!Hd8XyRt^+3) z;o0E^)3AJs$Zgu>2eSWq^D3)^FAQAGdN2_l1o-xtuv8L=Yup{3$CQI)f}0Iixps`o zAP=%&7=cB`NI$gxbQks9A}e5r*w4PTu8xQ)SXVtX-`};JwawaVUMLzW#Lc?z_{U9h zVG;~VbpcY-nmvgo0idXdC(#_NrbGR>x2{%{DMsj6gpl#1M8$raV7sO8lFh0Pqm(} zkb(k}eZ`HO0gC|FyKbpfCiTC9<0IKFZGA>cogE>+vX{-!(MqJyFlFr%3hho|Uo19M zz3K2BwlFme@!TLx>c8*OcYp7jLi$kCq&6!W9_qRHa{@)v2*_qRm`r(5^h(r4l*Sz{ zu%{l$rJ_b_0STScKUc`ZtTB#@R@`O+qmk9qfBBf*EJCB1p~T2Umb#nnzPd2qv*`*~ zld%R*_Wcw;+uN%%Sja+q^C54uEBiP@xg|lUf^pd9O3AzRTRp?GzWU*5enV%j3@> zZb)fVUgE9g;`j}3a2sv<0O{j-@%hT!t}YbBxW-A*na7s{DyiJ4{2PpMtX+TWX|oGF zE9B5`qOW>`X6cq?lS;JbnL=D*`l zenIP_8^E~MiDi8dGInAv8-safvfMV+tzbgpd@?H$03kRKfY3Aws^QVYPN54)r*L__O*em#!5LM_cKR7 z7y?0DP*od_h?GVzyErORyQQ}{r=aZYU`R#a3t-SIN@q=AJ2d%Km|0$q)hZ8D;Pri> zCj(XG9swIXdN!)M(m|S}<($LcXrWK4%*G$PswEGe&Fq9?nfkRsZ2BqxC*!GQQD%nX z??mir*I1tvk_(+r0B55K_2p5awQzXjmbZoW{qTB7wK6m*k@83i2nkR;newJ`oo>Z` z4%|8<#Y_EXLBi|mQCvlF5#`)e?pDE@mi!*t)-OLL2Nc~dE(?1yYfyn z%zgjq+t|Xj(^W4`0iQe)@Tbmeogv|R9mt@`N69Bxf#59a1}9{?wq-+WKQ>))5OkW) zrma7$T~GN7-={F^dEt~EK-AbgI~!Dz@_s=4>dY6Oq3AZp@uy{1t8ARFYmWjdL~rmy z(I%FIjHLT(Qs!9UdA@xGK8rM6R{LL@x%gP_pn59hEBYlC3Qw%-xhi|)B%EwU8}OEg zn8p$p+ezcm(>Q*)V2=h)l1=Y;b#-0j^XP>^|9flm0v>;*^5RWEka3uxM3?=SB4Myq zYpl4*z)`^Js8hF7nv*hGTdGzVN3+{8N0QgCOuD42%PAe#P68OEK7%$ufd96vy`jS2 zrsE?iF*qC==lDE`+N5-f-EUOF9Qabku77Skm_YPd6%&cd+eiB#G;eT4$gTd%0J{I^ z81)!0q;Z=3!OK|Lp@7=Ysu^3|l{}C|w5!s(dwjI54?pfD!WXXpqF{>rjKBjTk^A_V zBTyzcPWEIMx42t`UAP0O&}!qO0Grp*(e@M)-!j2mtAFV+$ntwe&e5tO4e-2d_;~7Y znkTq-h4+vOnR6g{kA*i8`KPN@)Oo=ql|gyXl})b8jNMTCCT1>F4KYP6NP^HHbIs8m zoMg(bT1V{%DXx+My6J6w@b7-mI@+LJfmyB2M(J$dIfIFRw--ih-yP>WjH`N4<`Fa@ zUz{k%eLP?aiZdJsl=tGP8-QegW)RO~Z=5Rf+8FcZux30lrZ`Dc6}=jD=0@)3ctGNo zJ{;b5=wB{(sy9>TKp{{g`D|0^qSP2%mxfp*9TKgmql&MrmdvkBe*9#LWgHHhs=yLu zGoU31J>gQGJ|9Ps+t+?s%ih?Ot}fC7P0}8X`FAFWV@QJHwxT~=1E7&mogi2DNSoI$ zF~9v@4kXlUA$KZ?*18`~+-+T3sYELM`n#L}Z`)QCH=0r8SO1qNEru2Qy0sww!7f`f zErg-sM2q>PWCiA;+!eOkM5f`dFwr@xX3_){ubBgTGQ(UoU3@IhOBGxA1Zi@HDtl9% z?r1)mB+=?$Be-a&E5Mfi_%)k#*k^F&AOAm1_Xk_M5V!N27sR8{JE{WM{)>r>je<9v z8m$mLICY~QY?z{fFyX9r1a*~9C++8hYo1Zpw&tj=5gEtSREM7WpXknemw{kJflHC4fAdhg(+zUE?KMDSL^S z^svwYkxpQHk1et6$mNrDIUDMk^Lx+DAZmiG+g^?aF49C)C40*y@#gA5vd%`{fsV*? zrHn(NE-8qZ_z(?!KgV`{cS~A48A=n8QWC02xL!?y_|{GcSq|Zsch&X-shh!dhN+2r z%0Plf_TT@?VF7o6jSQu6HhCTEOV3|J#3XHGwM=!gz2d)cVDzX-`e+{H4;sj%jx`BY zCyYcEm}V`jPHP7d)hc2#N4tsXvUg2cZgBZwTj3U6Vp(EwsTG_zOMO4gs80=xJ64u{ zEY(`Sh2T3{9VoefY4H-7Cd1f9z_ zzm|D_MxHdBX12mTjvd3fIF*g(l0ZdU`@yHUy#Usv9R@Y$z8Bf5umldwYVYggvi^yJ zx%PIx!aX|hp|i?MinPSGaPWv(j-ta2v&fYcQw)r_v9`DM)z>~nSCOIE*x9ouwOenk zAPvAIqV3vOT^v?}h&urrz%&{wA7mt?dvOZ>$=x#c zHy)gIe)zqs%U|a5bbdy zN8YBODF2@uch)Nc4JhWGY9pVhcL)mfEr5QhZ0C71;A?i79p0)BA1hJBUgnuK_yFsg zG$GJ9^ww+aTDFww7iYopYbq$bMjxFxy1R6}jDZxw5cD}|k=2f&hdIv>SG2!O5x2qM z8riqI9N-RH#9GTMROGsWPOC;&@Kfm7uP5%s(=>FD+WMm!4frM7W>P44R2p>74I z7D)a6$r_jApPQC87FgHF2$2OxrnnWZvRfzQADtt+tSqkib8DVbI)<~S+6S>=+lsas z$*86{mwPFl-SnpANn6uje=82gti&;pzO#@Odn=ZW;p2XCJhfgkua!vA!vlhWXB3qE zuKM@K@zFH(G1zG?_lmhHH-AA!FCKq)2&`(x00ydZgZ8fR$`*Um=!HGOF~P&W zSTBpL9op-qz77|2-&v~qj&XH%Tp4t!NW4`N!Hfba60RZ7`RlNI{UzhRa z)G(QkI9McjYSYfNNF&DgJMK-uVW*+>Q*0Mhq(1JFm9Kn~2L&KiIel|6>G)~uLg63anSq3*w@f>Fl95VjE_`Qah@i=OE!y1e9##vk3Jm9RBeu*dYUe4@vi zjF#kYisR5WSvXNT=qNUdJxedi%`$L%iAV5iDrH!(O61Ihz{>H{6VBgbuc-kdOKwSB z5o^@vmgS8VV0>S*@z8u7& zP3#Stq`UW}AH76MT>5&}_9b3qPMBO;JFr=K)OyhN|HczNY@zAiea&p~t5kRx%0qFs zoK3d59(-uZZD?ecrr=Cx9$36w#BOXGv3*e`%K7=BfP8c2ew;@ti4-(l8?33iTaPae z5ua=1qI!G!LZ7tV(aDV2x5U9}oDMd=D^C?o?`C77d!ZYtjVzt5n-02EIcxslp59}O z%(8^uv7%MEZ8ZF17DmUcPGV7$uET~)4(9aj^c<_7+PK?0F)&fL7#)e*SiVfD9Ew!` zbrRGr1GViNj7fBL_)-N}Afwo`@!Hxvu9lRzPt8esxNX8=##S|o@{FE&atoz zRHB1>>Lvh&LwD*=_rge9YE|y;FVGmi&J}a^p#yNYIE{)haBoKkgWcbihF&u>KjdGm z1>@Z9W&WCSS&oWf`<;Cx_@hg{7qrEY_p;E<1BnOn@55vqjG4y|u;7OYEVP6Hf0cAx zVLBl*kAp*{X(2u)##=k*wrH^yZFV?b^R0sE|Ca5Yc|C7O8bLxC5>4B!;XYU6ZelE3 z^TIZ>8#d(6Zw%|Vgxw6iY;awRQT{w-V))N)nlWhH#ew>F?f_5G!yTJB8NmVl(R}p`I_qyQyGF_jQ@~8G8g}!cm!`CBZo4nX~`B+;^q+94O zv-)3zy4RQp#Zj?Ud+?t54SGeZjo)ct_2Ero z2I14^GTBwPye_i3oFPxl4lO|j@sJ;Dig`k5Xl>d}PvKjsLx{7BsH?Cf%OnTE`k8eQ zGwGE+-EdN6Tyk9|d)uWpn>yVU09d|NZ#O5lG$Sfali~AxH}6vxxa2g~Ut}awasU+A zR*GO-JxXx2u1@oE2&|yWwtOB?&=IME5DFl^ON(?k}batU$&B05Rsq8i&w^mdjRTA#b7{z+0;=U3lOfTgvunD#UN(v%F)C{jIGnd zN{9JJpSw!y?+D)BSoA5hhhA@0XK2Rx*bm5xWZxR3H74wuSLYf}!dOxC(U2M|V=-=t zM%eLe3f)cY-{&%>!1Y5DS*i^vmvbK7`FkcLroygRqv|uUO8?^gwDL@}qidnnW zza;su*-f9n@eHkLY^y8IrBclG*!UVWlEmNjtw7|{`=jwuUGCVY?NFaaGoHIRk$=RF z4eh$HqRZg>%*s0|1p|~ba zhs~doIGXUrjgLLpTlWleg@8V?F825+=1FDIzdXEZ?ajS23RP{x-e3AM%VV?SRtF~i z?z+(AWhZ{4*M*vRaPAIqNANAA$=}CU+X>boz&OyTW<2e z0%Z@yqNJYboBueS~45rdfsP*`_`Ma21sW7#Qe-(kCgl0({2LY*DOWdq`HjF)y zL8MX}LT+|E@-MvTSU0?Up5M6|}qk&;G#T-gb8$Gu0?2ytN+J^v&=XBkW z#HycFdWaaO1~Y$`QmGA+ou>b!$LxXD47vu=$kK2|5P&DT9%JJW)jfO>g~HJJrr3dj z@}qM6*D(11THee|Osp&^w>zMi05coY|LJ+R{7}hQ#pICrL(NcRA?3e!h3>|9g-R?` z8$>p!8<}i0xEa}jL9Ny39;vJYJ6P2#Zhka1(e>T4^juY$lxe=c`hH=a!^t?%puTpY zw1g}j%l8kbZ)&oS94uB*S$XdW%;C?ited zAq)xj=;v>HiH!9AVGd(ZZv^Q82M1UGxr-R<2-erDCS>l1i);wx=(#crdjdTZqTw$L z9rF#_2RzIn`ujyVIJUR7{Q=3^!ADN5;$p??MTn{exA5N~PNf~ez3DLV3;Ca4iv%WKi!p-pwR5+&iVFeGcY!#gru4%?NO%gst@yI+g?u@8 z0NKFb07Bo#-`$97?}?^_XlcXH&`&NvU7LTb0Dc6*AP63+h(Wvo2q4bQU$)TBK_Y}7 z{?$UYq%(JYJ24CXARg4RAUApaJ!gU1eZ2}0nc#@7AG)N+*Gx#mbjLRI;C~#!xJh?b zdhQc`3<#+q9bfgmsyh*6lGsh@eG79Km|JITn`-ogIG*tY>gok1nta!LARB&@HvAv~ z0X}qo1$6%U0EvYIIj}Pwe)R$;K%zQ9B7e5O6+sZtQ-DS{xL1H2fwBSjeCc}%0M``; zfw*8F89v{R_!e8)*Z{Gv#Q-yassF)i{EhZ03}63>Cip-E=?aDI#6J^**ZcT>|2+2K zZ@7ePE*=9+d|NP=JyT z_xHfzcg#^w!H0g@R}ao;kE`>C$n--=-?uoDGZ?Suhv}`*=5kmlvqB&reBk{zkbV~U zm8r`f%l^_d|813o+#C8Q*0I?qmyMT`2nuUE$B{{g@B*>k_lKCq>ZfFe;9+|Y)D+4E zyyp-9KtP`vNl!=TyTB`zg*G(Q8se*WQczXsWnhHl%i_Qu-V?k0drD+#71rp}>&^Y; z2Z#_h{E7eP%m>szq?(JyBCVZk>?xjiv$%NTEx#kddUDUqv!AgiCdVc^+(-T3MHf8{GmQ@)AyK@=?*~{ zOK_0Wi=^61;C}-Yjef?4tqaB;lb}2UeWAbjzx}=!AuE=dRzz~XQgcEHKcT+=kOl}{ z5z}7Svm(>Z8oa0PG>_9zOL0E^olUU_9ZiAcyC`@yOAXU&gSlVix{P|@PEvZc=ij(9 zdm=cSV@OGpZlKgVZ)yZw2)&Ol8t>Md8xmm;|T(%A}B$Q`QR$`-q=Z= zaBc2A^$|MHO5vS!7-8hkm0p5$tdzP-r9|shMAvBo#!@HfjSUjD;d@)po%s|&46zcF z1NHYDq?O040~U(7?}Ph{JD!`=27~g_hudWYi37h>_>PL(ht++%)I4fT_?ECH{uN_V zx~eyKUn@`FFs}iN6zFY-qN=F7?fA5sJonWxvI=%YUB*NG+{z<~0x@+8^|~3+?z;gF z4v{^eB#eyJv|Me!uwoi~D~JkuZ#Kpgt{I*SyL8k4Ock-rai>#_ITg9~@v;jZzr|+U zJ7uX#xg(^0G@MWiFQRUPH zdY0~wqKe_UmvGB8_}>Q}EkRZ#hzb$HvDW{iA!nY`_pV6X7`f31RrkMXeMD)>IcE)N zXL8mf1L?m0UVce*9(INFu;e75FW*#Q+7HOE!j1Z=^I9`#j`PGZ?OH**-tqy;@OH%EM?y1l8|$SUWl8f#l@dpzR%2yEG3yb7U`*UW(#>8$^%w> zt$TdV4$-ofWOwf`EK(oKtn_ZjchL=C>Rer@x(mOOco-Z+& zpE}W-5~K*PvG)XJZ#;1Tst);4EL>vcNWUk4xuT5hS6t0LH8G-;sb zLu}4ttnij?YN{@BGLM@dO?W=R*0N8~arJ*XLh4ka4km7AoSV&qLQ9`TpOYLy6JpQ*=kEfQ9}w zfBqT#nmk6lBIFs3lmjmf6~?`|FYm4Nl%7_h2r!w$)aWk55h2$8{y~eS>U*I)rdD9! z>N(%Zz1Si32rQ-5)nmTW&Wxo?QRQ2;x5?>O!*Dm^dJ46@JYF`I`kn|^ejkp~0^!0Z zRatZbz_vO2*=TDN#{4j6kwB;KP&n7IgLK@RzB|VQ zaksc7gWZ?k6%C`S`cU0ni9Qnh_^->e)2Gp;S&}?ss`qq|)zq>?h}QPw?bzox^<+5U ztgAmg=PRE?=etTdU9MfYx0hl`v#^~A(=4s7!D1@h5*-St(!|xJ4VHmgZjVTce_nRW zAPIwZ80C$bBC&ISg91G;)$GfvhI&S&miv4Lna0ChuZQi)#O0jCNZ_1*u1he)9=q(?wPcxgwyO=$s@ zrYY;2l%CB2i|Q4Oi4+M6)4JS}^`RV`!pNfi<4TWq$K*W|=nLEZb-!||Afq_W+6cJ2 ztYlMTd0^ML`BVogDstAcFkH`DCOX7d{xYogfVh8Yu&+3H@19qq{V^HEf5fAn+4+e? zOQzm-pmM`gnk#fx+5t)jU`Vzxndic=O>(tA(fe5&C6+~Fo2O#PYD8qblgtclMm z@h+tm4H`^n9VYBX&!V2vWbP?!~&Q&-46r$SqZUIK@Z#9foOmK0Vc*!rn~ldC zN4zYv_RsaZGh}y#wj=3}C%um|pEb%yEDsJxG~H3`%&EqUn)_i}YbGfx(KoatbsG*a zeI+Mz(sJ1*zQ|KHCXe&AnIS+CW=r}YQ2YIfIrnwmq^}zQr**G{e@dGTO@jNaL=Yy< z$&A!g@3My@Q{bBFqvkP0Yc?&)p>8bE!TvT@=hF{Pk`pXsH?cY-!m;ym&Bz7%8n*0n zNi$th_*IHK&`okYpdvaA9j1wA{_Q6M&WTByU^#m|G_MTq@DuLgAf4(&J=NO@eh+;W zZ%_Y;lePChz2_Pbe;E1p($+g6dSVrx-+1Rbb!L=(+cu4B+UxJ8c`a^Tv+tnJupr&X zYI^#mY3CeU#D?sM?Udx5s`45h&y4A#cfkcnVc0LV1rXfzjy;POt(K{q5lC4rNJ@KT z4;+ zmnqyL06Xq9f6+U&C7!98j4x}sh-v4ibj>Y0p+j41b7o(XL&56lO{)q`g;V6BlZ$Qg385&ni*Y!3MU%pbExWn_XdT4z0)u+i z9;cv`f4$79q-@_EyY>FW;q~6CD$MbcD<%jTY-sZ z^`q<)?vR35kJ$&iue;0+m1)gjEFsIucbAfIf3qi-?h5xD??N&0_sBIaLQ{<*59}+~ zhj(E|^ID75CQuHiNbb$R(;O`QC#9JnFXtebwAVZ)otsQz7YyJ41xk!&&* zE+^fLp|=LadrEm}eN)M(u#YD54W9x(-+#Z+0zoWX<5pW>)=!`k`(slTmFYIqGNYvE zf7K;3&H8BP(9o$92lU*a(E+J!S^}nTrfTa?X9@AK2uRKsV$A}|$EP(Cs~s1|zIcdH zofeyU^2nue>EPc^WIbofwPbA*-`m|f~D(1S2UDeZk%Ex zBp%YLWBGltgMYoUvE$cAo`iPs5Bn;5g(lTY=RUh-5KQD~gwaw&z|AFV;?pR$hGVpUnyOaneuUVLz%@Ta_C1e}r4W zEq!7$qrTmC!3G0QmzTKGCADtq>~QTw2955+y=zBg)0zDpAyTwNa@O_2kQDV~<0d~xFWXmy&T2Xz84C2Tyn{)qgY7!OOo8{4F%Ee;Hn6{QkTc?hMOus zB$N}(K(}o3)gQTem@dzlf21$Kd0d9r@OAuN; z3$jHv3{Y|*g;O4{E7aHD3yEcc!XHyz;mQ@9J316uN;+$@o(zj>y^C_rj0@-S7z?c= z3;x#NL({sgvh!6%PbcX42O)~psLVvDoJhOdU`FORnVc07PJC8(S+|(d*-m(oa=*pT z&j|+1TJDESe{nmpC_V02{No&RcE!&zTVxfV?q+@C8bG$H_w8yXQ!aSC7TRc5f?OoN_@jOe+LV%(V4H@kn0+)DH$YGEMoV$(w(()=XJ*)W<_F5MC8&(=o zG2Ap%e}#EJKTjb7L2Ve6F|>w0+~I6}L~;$YzA!lwsOJCXQ_>TX=YusM@0;XP%gXOG zDL9W2s$oLo)m-lf-*}Hr?zU^tFfY4&*&vWlL|`RpWFhB?xz`l5^rA)1;eIVN-|Q8; zk0-cgeP21DA-oYPPqX|H#gvoS_4y z;~kKaWZd+S{P=_H`(z*|I(i6lXA*?-{4HXf0>>RE@#Ktkn2bfR;ZSkR{8IDfDLJ<* ze_X@AIY{SG?YzS@|9fi#_;r$EOm&d8gFaMn!^J~u;$=V0symL@DSNu>8`NJ4VHLc^w}))1x-toaG{I z1}a9iCXeVmLz(;pEX%94row1eEGaiqf0aD!i;n=R@^|T2d2#~l)QRe96pTP4Mf&N%m&1vQi~L4L+^YK_$#O@bn!ZBt%ZX zr&PVB2o;Kw|Fj;dac=-3r&!en6_4$u+&Amr;87W+JTVx_OcG4YcSe=TVP zZB6gTCOhSu#=@>_s$3@f=zGfz7BVq!L=+{P)kHiOQ7@Nc<6%|Z2>hj9iyKl|Klen! zMGh?s?OXY$LC5dei@WD*uL%7-A^brD1q&Z)t;7g773E+0sWx*+ zaMdlcPp{2sTgW^{3KVn!>7?e9e-*v7EWm+65jBlV6IBQueGQ9Hs)?U`92)NQ?s4v0 zghw%#22D@1%Z6-)R1`?e54dWd1cNNb^MyqL3P_I zfxCq1l(pLh3c%)ek5%ItMf43LdfHOn0oH6w^XpZu#iPQ*kX10!a3ybef2U0jwADp~ za`MPt*rM(fE@SFSEHST7X<0Ii-^@Xx8vT>E#Uli8*LwPWnUk?J;;=uI^c%SGk8sir zt$I786f=RI(sPn8DSv2Jz-d~Er|CcI%B12_JA*v8gO2O$F!UU6JYv_%W)d%88NJ4u zDBd67;eTV-wtd**t;E6qf4a*;^Htu(OdzwxQOSEv&HjcRre7EreDVC`iM3`$K}*4b zBx=i*kT=wr{0b}<5+hpjYQ?xK-Trse!?tTNyU$3djcRy5m z_K1vCu|1kxu%h8iCC^h!e+P*c}xY}nf6=wpg0w;gxXlBI8a^rsWah2 zmM_m@YE4x&L%9xFe=ZwTek9JaHcEMo5@7fJXk}XJ?vkhIwyz>aS+Rfeu63=@(XT>v%b0_6g(Ujz2m|uC@xkk$J*U*u^ zLOg$Q9J3f1WQI4tDqfBV|A&yXKYWc&GaSwRN3 z@)O^r`b5i|Ys4E^pErQ$o^ZM`|ks3~=mV%|0YOe2Y2!n(U4>z!J^etgf zZPtW+N(c3i8g6Mu0aCaay_Ey&K=8ibb>C;FbaKJ97M*Q2iaWv6S#~mSJ1h1+;dg4Y zF$(B)fyna40y42YlXqdAis~Nxc_qF`&->+6%l-SFe`go4@3#S6v_9dVyj5@k8tw2S zA8Zjc2DN95iBXC@LgB@{iG`}9$rY1N(HKc>&rg9n1qG2$nnnZlJAXEhR@D?6Jl`VA zFzQ@#Qnaq?Hxb0ijZWWN2@3DQ!)TBJRw+>qyQ~HsZ`IA@Tv}jE2dRtLN4F~94z~%9 z9QbTVfA?ld^@bvsCW@=%wB1OZfMMinbx^ixlzE zG5!6|4eGTIQc0xC7FN|tqbWx_^5*wM^@J*%e`&BgE>RUlS)6V2*Sr&x(w9N|TtcOJ zm)N4OajUF$KJYm(WodrEKP0*;J(kkEjeq)$JN~VqRmOXKHSB?M__GDvp+2QeEYj2L z*YQeyDmzb^t#!zXR6Y+p$qeH24ksg{D-AT&-@H+k&PJC%l{A#C#I1+m#>u08ci{o! zf2=-!J(_o?<;s9GNH=zI@g6e_vf3$S%8@-CEE8B%?x(oR)X}md)Y_4KT3T~w2 zRg5}dd#lLox)728ye|nexmpT(m$xE*qO-~ctLC9{f6qZ6u3|AnDn$s z%9g2}8-ra9E@Iy;R7PU6Ty!oU{KBmr?Zpdnvs@1JecI540!%*_YV7`+K3{U*&s!+i}f5UJ%dD0c~xNLYcp6C?cN3^v_EbgjYXU@FB;>%E` z*s~;}v&^Dr%TD&l)lZ>f7qojkD<_d@{L_lK0pp=A!@C_v^_#*13bOHTYrgo_aOUhUO)hBds`G4|UE-!DE&YXGl5e+uYrWnu4e zxQbeF?1vSFEckuv-s_Kgo@!N-P!b<=EO1KVoi(XS^{i`n5m`uENIjTtppZMn-Pn=y z4HF*ub~}l7-L9P;`%tP14?6Nh?uYbkd2X>Y8kbhQNDi04WK)eadiQ9%NbE~kI`P=) zS;!2rX2H-sRqmKd+(!nbf4kv0-stm>k2+gt?YQjX_GiBKQ1dRZ^H~$;>N=612t~fg zd|Xt^b|qD5auG}`Wmc&zgcr+JMjTN!@yUO5OS{FK=j^G|mKcv$N>XMQj~A2SRHxAP zifyYD!ciY#s9?L+8EsGcm?iK!?}U+4%ko7cad%H)>;l-9N6~2I&j9Lir1FGT{!d#d~ zP_D86Pa# z-X+GLY~H+QH@10>T=R6t8sM7AU9`Gzz!=#w^dvOF2eP(TBBHX^^V1Z~--o@F%^(1J zRONs_8o=Qre}qX@M7$-p*wRXs6Rp3^+(S2Zg%OAPf9e9OUnrV^*Xgz35g1v>cSPv<*a6l# zUGmGZPsxg&noilcKCSPE+I0H7J1zL6%+fK!W*r$WCQ)B_Ai|GXSQeTL+KLv&TT}%| zPwLy#>4eeMV3Is4l795JJ8Qc2*>chC)LuuG1IK(W#W*2Z*g+YKg|EvV(f|0N9I>pe zfBRilX1MEDcRlhDR@TP$Wo+s>%9P&RQ397O?@j^Vx6Fe7Q2ApdDsp-7xf1(35`*-Jd9nbBVVsN~3gD0lBvzsjAH}0LS z8uA2GnMa5U9MVRbm*qtKFp9y`C7N$iK(eM$tSD{%LR|xdWlips=x8`+!im4ocZ&*N z;cQ2Wl?)CN;%R^^R5Tm|Xgv6LDM5H^0{d}+x5Fwb?%Fr2c17QoBs^Ruxi^iZf3PIu z_+gS0jWbiAJw9&4$X%B3ym9y>x%1G+6@3(-!8+Nyk@gcpeY1Why;qw--yMFKl`uWq zMfD3M;1M5HKRJ!o9?Zwdzv>J=f|p`lcGYg<0|=7zDD{%c;Ez>i^#$Sp>#rA_QwtSj zKCqq`AO7+YuQRZOt2u~pf*Bk7e=r*G7>0_XLL5?(E+;l)X6blybXR|Be=8}G2kt@l zmoCY$j@VRbXIe3qnhN7C1#oZJ1Mic3K{RJ!IuqBQ@~-Peb|gp=~_cif7R}=!bBAiWtz94KJct|@w(Pk zZ#wl&RFqK9!g&^8aKg7r)Hz!|s5n0pkxNiFpov4gZYDp)YUkJHi&O^C3?v5_y(p z{D~B1Y#8iOs^KPkfys^Ir1F?g_H7QU7l}%2?Z+2Ys8rP)Ru0O3lYJuLY00GgMz2;E zS|-21xxGm+5Cg5+vx-W{_)sOJnHK@`f8I-Rs`Y7MeTxvI>N`=hUu87OQ{DMVPbTis zLjlB)IR{QXq%6BQ_0vFnTt*z9y`s1$G&GsjR?#nuP7aHN~s5ZT(FD|Ca0;K!PtVW-ppUDWj|Bpul0i2n`#cmr}))%oP$iaOCgOsFNkeT zn+;Kqv`@ zp0kxFgm(;FayCSQyk!V7`9Eeeqw<$4Bmq3Lg694kmt=eaD-ks{Fd#2XWo~D5Xfhx; zH8?qwA-@%WHZnFKK0XR_baG{3Z3=jtjkE<+)ZG>~jv&%fO2^O*Gr-WDQqn0kz|hP9 zGqiMfhjdD*pdcU(0@B@rgtXEP0w4Om_ulv3|9`FTTeH@0&a?Nk_u2cLXCEdy4Q(!I zE4T$z0S-fQfw+Mp09iFPB_RM1$j1!?@?tYF>DVEE9ie}lv6=Lst_V9gOynN~Syw0o zd2f@0An$o01_4!j`AKOO&#ut6Yzm7OILU;(wUgJJ(C`@I=z{TIH!d{;Y9zzg8L_CNsO@87>yCin8P zg2NoW{zLzBzdQ=+a z!tVFuavuc*{*Ui|z$_i^9}vX7F#mEv5ckuD{Bw=JG4y_({<{u&m?hlm_u%n@1pp9N zSBMw({ng(iFu(_NKcQAo&p*6spzNi8&C@L(`0BwN?p5AG^nEq+OZ_9Y`V3X@L#fg_&l5J z!Th95K~Oog`FU%5by>E5DhZXa-p^GnoptaD8B5-(Q+)9E7~{zF=b7{>Vy&0h zNgh=M%U}9?7YMtkJE8-X-GkN-7{ic+@}j*|a{L%odJBb*f8~|B|Hvfru}~zICDB$Z zpwlA5?v*V}`Ls`F{EGp@z&<!%Ngr+#E#O>8T=QB$HT}rToW_Hy>`^>E7p0q$!v>+WdtOJZ zTda1>%8*@Hfq+JT85O3UZ8X)>@8KsEL^P4p-^oRohOQ|$r=vn4!g$T*n3JF*IxIQh+clQ3CpQ*Z^rI6!qGPRb` z-0bv%((u<=!Pezet;y$^gd6~i965xe`;pazMuKnDS0#@T;i(%NJDZQ0UKR(O#k1Luzj}>8lW;7prYuY2{ZL`E zIhKL$th3Q3g{j8l^PreG^V3(z$1lAjvV^(p$ArYb^QXr>&Lns2xtR107^5_O#BW1x0ciKNIv z8>6s-6Gz4ac&U9lGzOPP(xKr-0((IoQ(L%lQKK-Xx>?Q`~lGk{W=a}>;Dn<I(mV4<~wxgP0c-bLie{S>kDzrMQ)YrV~An1E`wJjrQ<_2SCyw0<3 zE+Q7O&o*WX2Hql0Yv+UK*KG{(FLKC5>iw|AjmzZE)=noXExur&<751ot61@WAYZJF z^ExiLVH$l!=VM*r7s%>Cq3f&G6C&^nlURoK6%cj4aQ8>|w`%4>_<&lq3{W1$1BLXB z=d(C7GA16$`svTnmf(kdo=3`8Xk$Z4qdGUDekr2NgvM8itXOJ~ycZm_StA}?Hbf~G zje$&c?bj@}puqyXLDU>oB9aY%$9Pq}e9U)iTnF+k21h(Ens18SJF>j%rBn`EW2_l= znr{3tP8K*23JIcvzQ8gS&AcjOvbKdnBZ6#7xq)*nD@jCxWMUcPA;m*b9490b(86eWSfpFWJlkx*Zi)3}!F;);^pa)#h>gcJTO6 zm=q^WJCePt!y+9kC8Q@|)O430pU`WeTJAB-lN#9VMBVhI;$RZKoVd{?1Rjz1EPcCE zv&8zm+SL@&0y4d+!kr<1oV2Q>G9-J+5}bS)Tq*YJ#E>wLM4mvsSWKFW@!^LAmcGT9 z4gz&!lCsNI870|=YeD|iFFj&}R%&#!Cff6li?yWQOL5EO`IbE_i4iCa4h-V$FVYE7 zFYCUg3?i>T#537Q(tG|zdW~6Wa*$UGbbLLF6Fa{sRo0F%Ad^RbPCxTgHpwg~o75(M z(M>k^i++-U?X&KvH>%vbt4unUu6|UA-WRf&N?LK1CSkg?7B%)Ch z&l0tk+uihLJQh3Fmmi&aHa^PRk4`~P$fh~L^vVx&xU6fvn{@DeHZI6# z7X4#3a_XZgu)rvPC_#IKX)$fSQas)Mktf(d-%u{Qa0`Pj;-j7;6N6vk8X@ca#4^_@Pgr>u0_WGYYCs~4(h;%+h;QjnkfO*b)SA0O`0i_!tv zDf_V>p&%7&uCZJ1NFA$$lnwC{UM9`cVmDTTRfMBM;;Hw4r-&8~kDRhG3@6IJ48ooO z6nf7kxFp%?=zB{a)eGyTe0fAQ!Tvhd!ya#vc);djU_O;REe4*gy57NL=!a^gHgMAc z5Wy?Stxaec#BJ)?Y)1ivjvSn~6vRBq-D;-Oplcm*j0FLG6grSQECxHpxrt4iDyUuZ zYG^Y;<16cb$kXY82-aUHd76B*4n}1-SQ!!DvUUpiKje+tnF*7O&@g)yMIiber6>E- z`Pd^?QKdW`IHgcudbY1E@Z^WgjZO5Y&9JFYi%Exek`o%7=uPRxJQN8Hb2PE<FVL=nw6GJ#z}q*(vy7?3g=^B`9H8&VDTi zl`o-riDmt(I{$&9`(puOWAu>l(Z?OSLO}C<-B}KezF>P&zXC4La0$;EPzF>T4tObC= zF#~abV)mP36>$!siwr|SKR5wOw4G*yiMNv$RRSI8WZg73`ZK6_xvdtVDxaTbuQ^m+ zodlmSgol14!oGfhyj&UF-&i)UnY}ruxgtiy)slxqwS2FwG<40 zK4{%!dW0gdS0e;gNV&fw}nc7yvTs^sG zTZLb9Eb0VS-j)4)J?|skgThaK?j6g2mS>p?De(_e1=ur*G@@~aTS=Coz`15J(3N0) zv|d8=hAyya`a8^}(Tj_EO1aVL)QcuH%_;lG&Ea=FWcJ)~X;;~2QrW4AzM2QOUpSod z6ljH~v(k(*w^Q$z7BE35lqU$*0 zi|s0IKYv>kEiCKC)amy;;B#+(9joRRy*J&J^~%|5$tOaDzg)XgEBSa1fT5)%^^k|K zVy=I}s1PwFi*5Dvl;P8*=R_XGH?`64t;yWMqV>rfepn8;1YT9%>*`&@_`_e_-vhsc ztS^nGxD-asG?rCLBKuTT08&AWx}A>{KPl5K=BlB!pT}>q9-iq8xH2c$G`> zUK&3sqW{~g3C*;t^-(GJ)-TbF&UBM+NwtH7;8)|ROtrj{kR|&GuIUw2KM~uMSDBZf zA>w*|m4PB=xlOl#uane&s~D-MyOwo58?uO?2%$Q>ReZfD zi^z#J)0gsR=-T>NAZVwa*4ox@P&&7qf@Jo=2(YjlFKlWugz0sExIAnK8q8m&GYBS+ ze*xbedRXM~%WMxoUn#Y`Hb!hRhM%v@pC7(6?y4>Seh8NX=rg&Or~Q=q3!w!1*TA(c_Q5tax1u_h^=*N81ZmSJ-d9Iwoz)#!{VZ@ zXc@KwjlQmP4jtZqXkOoHeaL@1GGF(w2QM-p0{K8+uDViBm|)av&Oz`xeB-QqsqKBI z*tmn#YbJz}vAMall0W8q1+LU*KTy9DQ(2h5S@{7A7`qaG0ur^B95Q{?{1j{IoHf$Z z#;t~uuCh<+6FMB6C9<-pl|>>YX0L12`l+`HwJ@mD~8 zE-jA*MqsMQ4bkjQ=hN|9h7s?BjwnttMb#lyOiT}qU*iRtDyGxVN8|1)EDlrImfPaD zG&A6-{ooIOC*O7ba|DAnzTXiHM6i!YE0*zhf?N}v;&?uFFcYsgRnJ|y=<_`>RWpA=t~v9LZeH$Jm!T1WMq z(Eor*WOt2ZJd13$Xmrv5P56|M%Ou{1+3a!yL}4N5>&+Zi$-r-7P4T3U0?byqDK?RV`_RTWn#7gq`QX09|@y>fk(GSi#hLO1S;!GeR?;D!qlCei~x8fLkfg(_0(WuzvcE-yXIeq1lG)YME76_$9$0K&YWB{ea$J zZYQf@@H%3FN5=HBgB2}4CROS&jFBN~9G`UmS;x1P3Q=J(nr>yBwx&gnHP6q=QP z*rUM(`u8C}_FY;oI5H5wBynKHWkfB0F};^^NrV}yF;z!c-bu1^fVbJv*Q-f!FtHBfoEfMQv8M_Rn$CHD|FDFi;XWG)W0WU?9cyb88HAWh_DwE^uC+@f!2GLt@KAiT|V zj!=)OJ4SOil*)fbem7~6=zl#Gq4?r_pK&bHSQXq~nD%7&YW{i(B?8;J1eK?M6JLN( z{p`#uC2=e=Sm*noaK_8nYZLWp^e^Tq_HVc6YCr@W5#gEoPlH*kUO&(LKKGe5rqpq% z8&vU5rf*)3%+zG1sM#Cyh@(T5zZ#StR!F4zN|(q5JBFs>^oe3-vJ4qb^BvwovYs?c z!JhVM=`WWF!c<&)_w|d8V754ak{TlZz3Riq6OTuuo5^vYFQ=&Ny4xrn&D{utd7?K` z(BVyP5@xeCI;d=>+UR3kG@&pL-y2Sx2&3l>@=r%)ADmR3;~3(^YN10vdUsBq9q=_@ zAnK@{14gg98FBY+cteM@o=K8&0}7l&U*|D&a6BjIBu&3sgi2@}6}ggseLYs{W%45X zaVhl>r5wgpSzYq3YgL>7{ak0=q)+|ubZm*?!3#3d&+2=&AtmzVOLj4N+s1_C>_jr2 zk*KoMqpujs2U-2b8N_=!C`Jq=4RV%9IN3;VXu`SD%vmf-etPA9iRR z9x$#MR1fVfJu)PZk-D&jWu%I*AC_*^MoDQ(W~K&z)Q~5W3(!6`u8O`Y-vKPn=C9?I zREJc_){tEthaRihYHB9ujeDw%q`#7LpEcQzY095DyLvbNx^hK-xq|(Z&T1jU0{!v0 z?N`dsnL|5$Gca-gt5gayh{}*oSp~&0;|xPMO86&k^qoCGU{Cr1jv*QZ-Dxx6vp8zP zi1m^FDnl0uar`#2$DY~SF;r>UK#Clh71+Jhuw0koPZ3znezm{Xg32Oc?%K&?Ktr8L z@KKL-7YzZgKnqoW4C&M=K?yx<$DD$))ON03dq;w__T6EuDjp znNtNLFL|E6%O?MjdG-@qKG~DqFpCJ|e7}rwcD=KE@pb!3>_p+~{N3E+J^zZZeNYPc zu9qy^SmNpHi8I@3h7Hh|!eFd%uDSGE2aGS;lJ*VHR?}vGML4u^5`kh5n8wc zFZrfAuEgvHX>&^L7aDVSoEhYQTkPEt*&Y!kipZ=R!ujUQfaRSoY9%SYwe4ykgP&E{ zqv4i`!`rogOks6J+g+Z&zWT1Ks8Hu4W~VXwie=S@%jIB!!xhHs>ei1X;SgZcmGUsHbAd+gMJst09hvH%@qj5;=(h zN)DNcGEh|~G3@jQ?XmlVVt9mA$L~7&50&vBu%cfTf8$Q}LqjU^en0-T!L7!Q{;}hN z%_ucrugJEBk0Mh^UR#h``4vv)3?TW+>EtXN46xM&=cd0m}md8m~3a!rTCJ0de5*Zn1z%JIX`?gZ@V zThf6oeZ5+y`uypfl?Jk%8eW+BO~xle4eug<%L;kS;Kn^y<)-NZ?Ztt-i|#n?1D`!} zchZQivUnQF;i$l_6>*(YWqkH;3&*cnhzyBJfkvNr8n!ZeSqX>MHGlGX>mNn>)Almw zM4;kiS`xBWe=&%7Kpi5NAB&eKq2+JS;8ro_GpSmROD6~rJjc2i=?}yMI5tyCXG?5< z6QaBo@SZmM{0dCR$xR?6l=?<1i#x&t$<=t#hmmI)AFJ>GdXhifW(;6(6B>8md0@*y z#C`=37b+{;Z`TdkJp2wf2T`mc;M1*>N~R(%vCof7lrvKR6?ak zZ!(!3C$i+3-_ce=Pxp^zxS!;StAFZ5c(WNwuzgNzhJ z_2*PmQwnuXhi^i*&veakz-nb46Tan?GWOqD)hK7O^`sIhCS_|vt9%;8kX-E!=B~IP zA~h6<_MBI^>0~{#%9}o4_Enq~`E$h=f2zted0=x@1$o0FyX>c04Ije{Z5y5goYpQ9 zy*GoR4Y@oZFPv?bel)XxHA%?D5MZ`L?Gla4;iHhtJ_5wcRCO{nrDIpeuVIUkNhU}Y zeM)GxA+c_hNG(xs91#m4x?ml>l!zX1^Mm0|I4O9pzv_P+ z#kAjBL$Li5HR3%n0RN?PHPsCc#l&Vl>7t@Yns{BO!$4VqPE4djkWAc-(7&=LPB~?lo3bEUBc%aBX5QN^QUnf^9SQ=b@QH8& z@y=#b&T4w{+LS5y2xU>kdGOqrUy>L+oLmzS5Y*$hh(|?hCo*}UO?G%@jq=DV&s%qZ z8|C`p;?qdobmZgsb@&v8JgG%UO=7?}Pfruaxgkf1J)3J0H=^%`B8+ zx{ZpHwHMXreBQz`D4o}ddpS;0e2QbOVbW|KuwrP;*6GxhU6jdVr7J<2v-S-`+DcNJ zj5?;b+@kNHL|7`E_Vc5$O04~y2$?dpLL zt);GL_yfP!^?}|Ef9IU?&$7PXA}**%y}na0r?Y?###DUfc9tl(*XapyLl_PvZ>b^` zb(dh9+TWrV{3_?>=B}SUsaqo7nESafot{mm@R6?GCAhvbeCZZS`r+nd4LEWA#S%)i zKpS1$!?v$sUi3DQVAgF+d?C$o<8JAnTQ!H` zHVgF#Ig|tIKyatjGjLScWS;7i$sLMajY%$abYU*heXh$klJ1QqEWtv3SLLpy!ArV2MKe*n8D0R|tv4-G}Dh&?$HQ+fl?n4p%_=9AMkRJJA?74si{bSly4hxI_Lvm>&mKkR(9QE1nV-A4}d=Te_t zIVakZaFykDDFu4i${^ zLE(a)B=I#x4%u5+Db{SxZdC6ZA57L{jui9Kr+%*SjEEbit%0~}3@1c1Gnu`|mEq^? z{}>_We}+Rm>Y92I#O98D&i~R74@G-FictGHIVt1W7Sj{VO~}DFewkWbKX*y#G5dv2 zN^I%|A`-3eE^DC1Og+KpTarfhbj!WBzn;#pCkM~0qb)Wj4Y#9uV2f>D{ruWT#5UK6 zZG-5Q-m@8m(EfN8l|I3CfmY|=yXqDbgPQ+Nf5fsN9m+OkjngT_Ni?AOP%^5iE3a+6miYsmLm@|b1LiF&=M3mveBD@*L zFjnA2PFVRvpayB!b5CX)=fn!_HOVb&tfPzfOF`{k!>tRtCEXADX||K;1y$fN=qy-z zWLL-=yjH0%B52~6bX!a#Xo$Tcg+YoSf62>-XtDc^LT{1SbX%T-W@N`{3ZtjiqHQ69 z8yjTp&paF{=<}qSi87*1aXZq}Uj-aL>*qNzn&I;_(|U!uYA0on-|#xbGGzHc>Lr-5 zOUUFY<0kge?TpHu_ucv8)%zV><8Im;r%wq9Rl*iDEQPK82`L+k@AjxpM<4P!*oVN9aeWzmi>@y-QTaJL#^3hwNQ=2l)KnYw z&Al#=bcnmKH0L~XZd>aOXE}>LPA*7t+>8)c^&g_X+sjdY)+;ujs2R%>3bl;&H0}OB z67rfB3T19&b98cLVQmU!myenOFcLB~F)|=8Ol59obZ9alGBGhZm+=h(6@M}^HZ(FI zK0XR_baG{3Z3=jtjJE|)oY~ec3_*hg*C35saCdiicN%vZcP9`?fMCHbSa5gO;O_2j z!R7YMoNtoz{eRWH)m8NSEMIFsYrhQziIOV4u$hAiP{P3;M9<8?!~+nOS7BxXFfp+* zFfp+pP*A8@foy^Q5hGA&0DqlbtQ_ol{xA@A1{#CFGBINi*iPQT9w6gt3t(miFmv!Q zbMi1T0a%!rxc|q{!I=jjX6$BV29Rd}$T-*oT@WZl9UMKKtt>1-;57g92%t8l0WfoO zbAI^S9UyE6bha`zwg<=?gDin|;Eblmwg6QJQ!60I^S?q+^I3vGj(kFnf81|I#u z4t9>l_MTSu765ZATYn%xQ9_OZ}G6bYit5G_`7mrfP}Cz zz!==%f7){~b+&Q@xiGj`+5Xic<6mLGQx>;36Lqk&1KNXJ5dNx9%*q*P3Ld*B<3A^B zWAET@@BJTOZe?#~{#O%bu8xfA_Et`=Kxwi6n1DqHzhxFc5PyK3iHV7mn-u_b0suWs zEgAm`ujc6p{9DQVml)iEueYOvBfuQo1kl&Y90>kG@OCkF0|G$Ku0UV!KNbIt5SW<( zW>%&kfCYW&GhQZEx-X;Qpst z@RVgfcihnK?C^jSPBkc)&c?4ze%pg#Li?2{=@wLO!dEA{{I;MSCs!7$^Umj z60Wwkf2*ng*8hLh#&%Y=p8qiblhzdkUI2Lq@EX|vZ+}xw;6F<%4>YrKwfo;%X^=5^ z5rpk6Z2ujjm5YRx2hdE(3S?^e4_p3`tN*oSwpR8)B?lL)zpfPkJ@{z;mkzvIrZ(WK z!v##qzg0l+=KOa`aeGq-v%gl1g`ERn?Cfmpi2y!iFk%OIGlO^04CwJUi2;lZ_6{Jh z3jo}nFMq(?!5QJN6XjqBFbe-A`Ui0U7)5>~P5`6mZ^Q*=*uRJw41l&EUv_0E{xf5x5+=-w0fe{BHy0K<7q}d?-+u^Pfabr58;pKia)Zk;`HjFSO`MHQ zZGhl+iaF@Fob_M%KYQ`70$ji8zla?i%+$da%!&Vzu(ACmvHPR6zsSO9_6G!~1pbZy zZUy*X8JJnXxxw@?cCq~3?_WMnuHdEn9R@re^WP9`VEzaEOKJ5x3F}|b?RQq@zXZR7 zu^azo?%?YDM|7}(#UBvd)$eN9z*MyKbhHH8|Cbdh0Uv*62fNyXH|!5RxL1eY#ekh1 z{!0yR#__ir9Ly2?;XaCZhy>=9c=CbevkZ{7TmRq?Vl82W(F7cI|2BD zW&~L}1OI4yTcz2;25rdK=9Dr{(#`Z-TxpA*xTa|2oCT02L#X5>u>m9cbciI zGkAuezu!7w#{Lif`!@s-=m9iESeSJ%Ywxi3#KWuP10v@Nnt_sgz&WJ=N>52ziy_`Gsj+uWn$?Ne2=49^SyP}Sz_*I zyjFjHsIj^cLAql);(vF3exi8#df$h!9bZ{gk7?*ks)$wIY#4$QVXmpxe zClM@iPgcJIrjfNRj{+Jxy&r3wRtAUq=x=|+lA7)Y>xZ^FeKiXNdj$zB+?i>`Ep;Q8 zmv~YMlVFNLBX2r1fzp_$9~RvbxSn8)L;1XeE<_&inK$#8m~^;cx*>-NPT8}3E@FI3 zYtI$h)~C_tY~9iIgI|L=6kbi*lg`ic@GM!yjncxXvs1-8KW49frc&mu0@h9k7c+mJ zua{yoh!uGf%f)T7&tLSD=d(#mcJIuU4Myq(d0O9d=Q5mXl&Uv>Vb4`2**=bQ9j`=8+An>h8idiv*Ra(|y3Tw7e1`R=SGv#x@#hBqG8et7Rm@*}p(Xr!9omrOYhr>C>W6Q~ zcb_;CGABJGvz6`pOWuEr#M`zirmNr4efd>-=Bu$lX<9C5WML= zS`<9Q7T*jN=0Mfw#0wP+C02j&Y?2Uqo=P+-wDp&9;de49KcBWbXnDSx6|z=(5CC6WTTy?JDmaK|BzVP{ zc!Z5;IGhEeo6vT}<)OsK#ymrK#Sa?0lY&@8LFVO1X>9OymUU%5V14|iE(!r-^$oj5 z3RGG(G39&XiAyy5;%7=kp||FA7NFPEw9BT*=0>8MYIrN%lv8n5UH*jCw`&@O&$LEZ zaw#u!FQ2K+^kew5n>T;Q8t&Iwy}NF}8|O@?!EdCjc>K3eU(?klwPhKWWpNJ&X*xgP zNDj$*8%K!hh)8C%A`lUJE>XXWl%)#mW>I9C(nu=fkX9lmw|zW#_|ZTgkF&1ZfqOI! z92tzd>&J)3lO3L;WTCM5YEteMek(JKm-4~Y!B74NOAoHss%w8-N>=zZ2kp0J+V9A{ zUC1R9uiWjUg=>O6xw2oeO=)m{j@@qPom*srN+|`4wqnM5t{?4T)sEa-<9A!gv&p4`Mi&)tX2*o`HCa4}_qm)%j?GK>nDQ$nB7{qelSlwXJcPQ>&1C$v)3rbu5L~-5E7O^{(fW_gdWqt=gpJ)bO zG~mf`8`QD53Lum~E)2nyvu9Vmbf+w$Kbop2&ye)GE95@J zt|vQwEuPW*S9iK?D}|CcOEwRYhA@q)h#ccCUorM6J4Uf+hH&oMZMrRQnfK2QL~638 zc`X=w3D`JN_$Y{Eh!8Gsm3fCaw9Xzi9O`XD&GR=V!Y}@^J`VDTh8VL`Nt$SDF9flz z$e!Es`>%f-0VP?L2CcWopbTPoAw}k+Y{qm5i3{Sdb*!F5WGP#wDDv`io2$9ta}9D z(1$q3mqq+wXMfB1hlY4p?29iUpN!~iz4761fy%eDUkruJaX47;-6p*7)JL!k zD>6qg`*cc}iD-+r`=imzKg-kgn>Yr9@p`Wm55Em8Rc6KB*U;dd&u$rsn0kkdUZ%*P zn6ZCu^`V7}t7Mia__#YP)FP8#kAGc=RAT)>R^m=A+vG7hwoM~2#+KUFqO3E0(PXkT zdWEE6zj!8b=BM7q^Sv>fGBZxaupgj=d(%lHzoB3_9}wqaU~`h=ViuEX|IRD66CSQK zcQ21;mOw7U3r{}=?Y!6-F)}}=IM_`=tSx^^UXqiWTw2cRg)&}v-s1g+y)B0)WVp=R z&k~BYmwd8scaD@s@)To)g>i@6!s7i`Cv9^m_iFF7cjjuS7Dgd77sq#kDLZnQ0%ZX& zcv#;Ut=?KKOuD``$-wUtMd0f1@e-EGpUGr}MDS#|)Xnl}+*|=M3%iyUrz1HEk1>Df zvgNAIvzWMlr85P9ita zaFYrg-7Y(k(+R_3Q*P#a3mKe6xIdC(**9p5mWnbz^ni-Zgvf3Sxgf@E6vC&YWGf)E zrg(EZ4yWU710^1)VG-v)DO^Qv_{(!$=CNiJ7IsT7b66t z7|NyNJ2zjg`}lXB(Th{3OV$_ZWX zC1{J6t<2D^a_)bZ%giYO>m8f9QvOVkB3ds}H|qoTr`*+1Ts-6oKxx zc_z2E+_am+7Jtp0OzwY=;cO@Tdg_vZ+0}P-X|J;eMVr#hUvxX<^6T6o71Kn>JJxd+ z5uQX;lsL*8#}uAH(_g3V_>5?m3CA9B-NZ4}!bK_BjGTT#@1}foI+aq6&#@gEy#d7* z1Iee+FSUki|AAq!C$Wyse6-)ov(PP=c*C$t#H(y5JTvT?MbLk3x&2r4}QeIB~DCt zBVoGVuaA`Y8icg6_HbGxzGkc&5oCU+Uzs*OR)Dss)f zaP_o%w;`oRI#qw73wy_$IGS=|%C2z7UF;~p!YR`%@_be6!U%O5S!Y3gUF3nK{NWu) zK(}m@Yb0LMrMDrFhggN2Tb~1yGUCC`vy8^77BA9m@W8t3Mzb(Vu17`0fKWxm*tY%1 zquMZQPCK2aie0{-9C~f{bP4k;5)LD#xfG@Ly?@~&qji5?=z8x$Hi_@5(bv->F-lE> zfPv!eS!Jz8a#*Rgf<2UBkaS*Y%Ul0}8HNRIf(xN}d#n=YL{!7;WBcX6E_mcN#iuQh zumTLd9I}04RFWW!;VQO)Vd#|S&{J7a}HonUFR}!d29oM zz}J1-c4dFZ*f9K(9RDerjzBs+NpWk*31lh`oGRJH60N6+HlMtL@=X#tb z^8*F9qsG0MMOEoK2y&H}yZwlOgKtz>Mi5y`WDH^hp1tntLRd_7zy!(9MD2v*Lx_8l zX-H}KY3-fDsZ2asiha|3@$!aaqQ_Kzk%eJt{r3T?u*|mrva6{kG|P9xy2@d4mc`oi zJ3)Vbs?IN-#_RxjC2h%~nQ>ksZs=$NedwYI9Bl~fs8AvHfVh>l32J+l@ZEf*|jtRRo&M1)<2E`i1I+4A!2F`J~aMcW=;%EWRqzP-h76_>y-H0BfA z5?-lB_5JmNIa|`E5JIX_l!<(=FfDPX&_I7Tdk8L!z;uZq0=+Gb%3{{uE8|jO5>L;T zEuM=hI?N1Hl3b5-n8YBHG5MF-j~k5UzN~ABsYgG*_ivF(7A2yU?opY`yG+1M6KiRz zKl?u2)Ydm>_tZukAO=j&QCN@klSs9lMJYq7t=CTu?WS0Mswr#+TPYnMyx)zZ`=sWjGCyVZL^;J*DFbOYM!!xO(}H^ z9eaPxffX-LKI0#CG~PEr44k(-QnY`8GD@#MP2F<5dq67Xa`jv$cfL$qxk_+FF!wce z>ZW7w^z~tnv$Z9Sew5E+_<@zI_Yh}CpvUTF@coJRP8TEir?AHy?=jcTc-I0@qh~)jeEp**Lrqv>r9tB4d9o@@;pE!T37G zVBO6(9#QX|`h#;lp{1!4Ut6qE+2sm~r8`V(eSIv6I>=+a#5OV1$GX0_H)}`JwLbsQ z;Tb*K>lw@IO=E7qthM!D0Cv3Zhct4%6MBR11O4Ne7;APpV!!5FpTQ!>`%}gY&xuDP z_iG<%~mc(0#3kD)t729&;mi ze0%*pPtNtgcI?AlVv?EcY2SIjE4LNYDe}6CN*F?q5@^`tIw5wXmz$s*$bE!5 zlQj|m7}XR~bQvY)oUXJFx)cjGx&3VJGthhbNE?SW`>Z^)QK)}lVjfDj)Y7&ZlHox5 zHhQ5z{cVfa#FfRN#fb5C%oo=hiL8kfzHSVy2hWv;;veI09%x(M3|QQ}vI%Oj=y!c# zE0p>+l9M`j`OTnn+({1TP?eUfesbl9bekU+H_j<=Ow*Tll_F*TCF4y~VW}`D>4CRc zm_k@#BI-)B%RW4U&%W zZc%DBS0!Iwm`Kv87TKFAve8(z ztonBnw-0}Md-%_{2Gj9Sg!oX1yeV%xd=6CrVtPG6$WpG;9Iwi~&*RBd>B_7FCcGYG z4Kc*5SH!BrJjK=~XeUb)4Ir6VI7We?Y{l2pG(u;M)xa)15B-Wp*cJhr&9ltTTKxdq z^m{0Fhc;B*z3g!bUepf?l!a6nRz;C|l?uw8(wBcy(<9g8#2tcaJSRf)5@$Gj3a^N8 zs#={ZOqF~;Xqqk8HD_T1TiMJTCB*72KQA%NSF63DF;In>peG8oclUk%fEb~p&>)UA zE(&>Fev7D$7_9;Wto7=ezBy-Ynbbq5n+Kh|yl8K*8-2!+@H0&H=!_1AQqS;-qSA`1 z?GJwskrYBvpGD=6M${ut3E5k|5qRPm)G&N}Gbk|gotsvg$rpR7R*%$s9t-}ARejN` z?_$t(TO!RIYIq?p^q10F;Si1Zmk2JDpeObGv&{D)@1pO<;z$R zmT*q}i1}$PE)K}_jY4qF1=iQLW6vBd*o(nR52p+ zc>>IfXY5)Ex`bKJKF^-3BC_=G;s!k3qxiu7 z1hrW+PxPeWCjVwH7Fl)c~$%eZxYkR|qke0y0FI+mcZ`sGU+Lh@6pa!8Ht@+yCy zdZ!i-0d&yflAtNw4aIup+Y^Q6Wf4_&?y$Sy&T7c$;tbO6*`Bm&i+#0&mX&P-lOoMt zc-STCDq3>DCwJH%cl$J0k)PtXLJcq#NSsT%wY~EB^1~=`oRfHk&7?)&8!<)%`XbO< z10XrP^nTi2q6|MrrpdD5(~bnn(&K;4t!U<}?kGi#lnED0QU&*5_bfl)RF6*%i=VN~ zk4q_WcH)#1ooH`s4$@ai45Ew6$Ij`08xZ-pnMsZgp?|?b!Kd7~yXm(JWofWMv~@6i zT;ZSFPqx_aZT8*KeIkSq!s@~5kk|p9+c|zj-P_*lr!R-9{uRHH;noRu;KzSjH9(89 znxk^Qf{JcI?e7TD9#&GOf--Jt&lV+(Sp@+y=~@jcW>D% zHtz{3S}(<_Y`?jKFdVS`VfcTYr7pH8CGy+4-b@IqOrMvRE8sy5Xf60785?~RSy{ve zQF+8>@vKO+;c1#ob9|uaK4Ib~asnyqvz+tO+L_^r8m+#dd!wv_ZP2mrxhA zMdS(bN;G8FCWpl{h^c%*+B(xu{xg7#Q|By%Svg6dsCEC*KUk7!BSWGOAK}-{Y}GN& zO}?@ANpg)+fc+pUf^bCr+@=B@?gO%pcX0zfOVZ%zGT`2v(#9AB`EJX~4vmJGK@gTb zvuX`t(T|?kHc4fV-Tr^@bHh5v_O8=)Jyfz8a0P?+nH^_T7ABikZ zv@46l&hlG?A)T+kg1g8w-yO3}RWomqG~d_xbxpIgy@tNm@&p5i`iJpuiKn`sVwt$k z*hiR(S-vk0VpO1|c9KNqEBO#QBkP(E~H7a8Zwn9>O2b`&uq z21}H={+=RG;=Lhex!b!A5i+ch0F8()mdWAqj2L!}SZK#DYNL?!#n^b24G9k)VTl8O zQYoAkQ?Gv~YfmtCX!`~Axw8zJc5L)z3m5xtQrIH!V|@q`9D9d)*HVO{yW~&He(39q z?WyT{|H`oU=zIUJ$+E{w5|1bWalV4<8q%p}szP5QN=9qkq&}>L&s@2tU-smMo)|6} zzItDBwoW7gxt-=Q%;%ug9yZmJ2WoDWwi&sY-1L9gKb~iS-Yei`qnv+GYv6`(Vs25* zLS=q~iGH~um$`;}#;7v=C&F2&bnv($FuqS9ZEZE=BUo@2`aU9en(i@rrM4=|pP*p& zj%0sSHn~2^i0Z-w`D`&DdkLuB2EPc%vX2io&hpfst`yRpRB@yC=uuMz-#EhZ#a`Ul z?Yck@U=jU{DkjI9u6tPUqGUwr0M6Jq1_S)T|NV`i(esQLES@kW=w`srw?fzD3T}UN zQoYmUYN%O6H<5Mw6*fa>{#{YU5l&)M1>}ELwpjaOcY?#vJk%G2`<78GpntSvFqUUk zav3uA;~S^|6dE#)bjNh##u$$4=o1`tjGKBborH}Fk#8vJBRbOr0UE;~h*zIM4#7x{nC`0UZuL@+qs|#p zPg=8Y-H1MJP&i+dh>rm^I)|+ZB94EJ18>u4KBY$;;EMV@Os`_hHjp(_*1DN`>3y=Z zjvRS|g#P?t#hg#4a6f&a$T(;hvCkR)1p~$v=>mxY)iOGr=Ro=-ZBfcOgG_YYR zApN*9U1#6|4G~N60_~Xhh!*_paR$rDxhL6TRVZfNR)1osRj<*b%V$IAUba?eTy(FEp zzYSx>B8bf9s?9jA_o;3B^bLf|m1eUjA;$Yn`EYU}Z?LZhRV5Y#c^F_?tS4ga0}+Ey ztlnvhQCOYczfMAa-+Nm0%j#k$foPG_|4K?M4RT*ual)8;#oHr7w*Y_pUD%^I-*bZB z#8Vy=^rLGTB@-)>;-Rvk`Mkz3M+<3k22EQ&M>BEQyTfpE`FZPR_mQp$ z-jzYu=20e=_`U#dOBfXyyK*+ArJtxiDC9U|^@I@5Cl@Gg)e^&RP?y&YI1+}hjN&HK z@p^`)@bSGm2d|Ypf4YB_^q}$2HL=l$f7d-cU}Tp`r&ZaawV@J+qngD!sn}nSEuoK? zyZq{8ece=Du^kxfU~K{~)L=?@))=nCNP_QC7=W-FtD=x3Wc-Px_W}K^a&u8K@(PI; z0f#Ycnr}>Ka+&%hXHgby8hK!bkz)Ny2}K;cF+Os`S1lj_=pv zvu%o3`^b@Nde7axOjd~@Xq%2mue93c$&a+GSnbp>>GxKh3V0i1f%N@n-%=2reQX^8 zULx}NsEkzh+fI5tGGV;zygJ(|omydN|JAR-l2U92Nw<9rZ#j4w zp3G+VgMQM;I#+)@_5;4j`Ej$VxSx@JW$_GK(+oNJ)Ew~{381upSG^e^!}H8_hIU~9 zhaXz>A!?K@E|TUW{$a%;h(yW?0au#OjuOOxy*&4+x#AJY0me`Z(uqakJIpO^eR%Gt zNyRllNZL!b=k5=NA9R9k+SpS+9V1IxNY@fnKf_43321+KlNvZDn{wBFpiM*#4w_zd zJXvxq+IZ5f>8ohCjfOYgWNX@ow|tv8z}w;u)bF30z(}@Z5i|;t$GA;Y5w?-m;`4E! z;=7J9?o5y11GG!+KGz2)XfJ$n=61dAt9>UrF4IftdE(Q&XY{;Pg9)iJ7iao{Y?#4p zE68voU+;grR`+?8Z-4S?$W%F`G;f%*4dIg)kjGxq*^I7B)Uy$~j{ieWT5|~uso0NH z*?M)pFEzK1U(=PgjWM?QF1WG>k~M|8X={*`sQmY(z|NQZ!`1SJ<^~K0?Z;-%JoAu<2LC7yQ)i7C;O-D z$3ofb7kpAdgy7~*PfjSo19H+FaTj)pkm)Ms?EjF`%q zm7VkqexV2ywR&;t{-$dSfp4tBvr`_u5)}vIAS;S*P@`Yuz^v6v{QcnDXvz|%xXPy{ zEL-qTXCja4H5AXWcx3hpW!v;`J4mZQc6k+n{Eo~Gmmv|)19Gu4wVA$GYQ=dXHFowWuYyl$R<3x9{Zr^y=QK07~JYr5T^+b>Lwl$!J{aNxVeq zuA-8Xk196aZwcR9ZJ{lnz_~|n-q2{FsQP_L2YkCPKm(!b5=xZmgi0KTeo;oT=pgJ2 z3NFzf+6l7At}}xCaxgB1)dj(sp;~{Lla59-%OZ`x16qE(7kimUb{8eJfohpxch(QM zmgVEvkKzX6x|nQ$W){nLZt%=+kdY(i8*Yg#B0bI#4)ShTgn zDEKa;B~($#+*0s z+BgG@)}wZw*`=L7iwIK=$#d|9bJi0|=6whHSPY?!tPpqIi|y*yDG-%2I;GZJ;4&UH zB3m&s+qj3{LE`LNi3A?a?Rh#2t}vfZ>Z8EJR2)K|pk7UjX!2;7efob=bMuK=iG{?w z-QuZ z;PSJGwDq-D`-3DX73Q>eNhp|OMr+l1eGI3b%DAf_9KUPBu~%~lH>uAF?<*9WC5LAP zP*0iWT;W$kW!zfIZn1x^;BD{ZqvyWl-r9!ebmDsBN9ou?b$`b2uUq z5C??OtA5rx;vf@|g2WEyQKO1&$JeA-HA#}0a6A``2&yz9pwB679A0KMBgVFWAK}|; z8D>F|_=w4JkMQTsqzOh>#rmxAlqMqWCwL<9xAbYPgcHd0MtpxiH>76`)CIA611^FCW%?MY7{>e>Shg&ukg?;iyDcY-9-aEA=2Wf&KLFk+ui$_cpB zOF!8VQ^r?uc;$Z+s}E>x@0`=Y2Tt(5jh|S_n*0*4*o^gyPq#(HP4a2WFmf1$u1~V{ z1$Kr5)ko9A5I*~n2C6*crCq_up+%U&5VMzl;P!~fnco9&HL)a(!8&J$3iH{G-n=d(I`InRuEai$5VfNX2h(8Yl|1jseH>{WSM~l zESLOlQ{E!Gc0rN+-D|P;g`IN{L@oIr1hHLRlMRl&P_I6I4Kq;RKE)1ds_N)9DbicRHEwV;m%X&{sMSvfN2yW zaW|S}r3QcJ6)Sg%q$_XvP|e8Cy8KZ{FBoU?qSagu1KwmP9DboqB>K`ZS$9(J`oWSl z4Y?m>)`Ik92Rcy@a6jJ&9o*D|50OYJUZnwRv=6FPnOcuxxv;nDcTIJ|$XtMH8-&TiU6RZy7X$_+?BtDOrw zXHFKPW_ZqKx}53(vo!qekPRyPh`&Muso9)33iHuqpx^rG+Wh->HpN5sUt~627d5SN z)RQT`$;u84btanKr;ijVJEwu@4B{SBLq1dJC8oVyT-llnAClk{C)_f>BSL^H<+kvH zhFpIvd1u7Nt0fjm>cB4TiM#5ZOV%s6)1+`SHi=GYza8}TyGsq zGCD;XY0>DF^FD-ub)4PH(E1V5YY@ycL}?9|8Gpk!S#2u0q(UzC3( zw3bC((kzSgo?OU%cWltl>oAFrPZ!GqoiAniuC8JttF6N9$9(U1x4?tA`trr65H0lT zyz}sx-TUS{@hKvu$x>W#xR1E)f${mxmaEn2%QB~D^y#oLBqDt3AW{x=Oi>jV!o!L1Ca;a)XS-nG&&XM2G+3Jt{(9JFM z=atz-0KH7D$huOrV>;5G7tzPn?(2LQ!iA#<)xOM+T^x$l7OIq4;abu}J$iqEsQ5U} zWte6@XftJ+kb~;~$ny0~1?;H+-|UF9%D3#(lSE~#Z_h~UWno2mDrHw>ZVHXt`d;Pr z!YM4IHbT8ZX@?#GT;e3Hi4josQN`i(E9f$LPQh%&bqFIxPIrk+y~B7BO~_F-Q9}6e zMobER2h@gd&dOd83P$l4bLM|kmO3XAdba~3Bhwm=;2`<(UBXms(`bXpS9(^)j^L~U z4V1$#VoB|@8hgir&uJ+NRP{TUt|j?vnJhE19#%vl=$eLV>~#^G-t`|b9%>iP>(86V za{<`7a}z&eTjv=gB%`uK(0_VU(!@ZWGpttAkxscV67)Hy9T81_TUmcv<=E@T#r#+a z|AY)LmLQC|poz#5DQhiaa;;IU40Oiq?VJYE{ifjiw;o-J79G>E+(h07Gb?X8s zts1?~fgf2KdNPT%f6aSc{hZ5JGyC=C+`7$no7byQ)jWVh0lSp$7IjBZl%zvu-~PTB z!Q1meY;pb(!M-WT@=kyE{D7%OE6=^a3U(r<3)%MSl)3W}qe#FPp?3hC=qJs0@e17D z3newwm8e!O?ueJlO^#Rg1dF#ELm}Q1ME+9?Oga}GcovctAq$Ne{k!UB~pF?D}JX>*k)hE%;Z%3B1D zxX@j*oLSeW?CYho6)P{@RJ^{AIgtTl!5=@gO(|=9KNg6vv(YMbcyDl$#M8m##2$c& z0JW5&8xOuciD2Zk=J9O2xc$9(Va8to!}~ z5-3Qd!9Ve{>oR`@61Q66sZ}ckJVDT;@yEm*=tBc$QS$Y2(L8J?S*rIEKQ0U%P6#vh z(CZ1-R}#==Re9{76N((A)xvY1lbT-Z)RT0fzxg1& z<2#YZx2NxUxzUD>WORIs*|m}TJZkhelk1CXmEdm)w**b zw^pAET)cE#N=50ZD8X_45d2AHu#@#TC2=pm1ag{6;FY*26RA?M`BN3-mh7*m(g@J1 zDd@QU$;o+`(LBh_G~Mjwx$$b(Z#YAGuV1W{o|}JV494(P)M-&h?=#>=9b?uhW^+&B z{GzjRmy(-|K+Zs$`8tTx>+K$5V4jL^jaylBaQvt1;V4=`Ha+5yUU&)BA(KHu1RX=9 z3u-gkf})rM0fx1}l&vAyo~~~2$zZyn^u;T zJl%ioW1~)7Wt9LZbz~-ryQs6e+lx}?7i_&AtPKS==rMY@lB~T{oc_Ll(g>$%?hM}M z^|;>~321gCaU?O0%?^JUdLBRiMzJ!@^}D^omG5`Cu#3ni=wA%%n}M>EX= zKl;$r7PQ3@BKDm?3JriXObTI{?<7pbqr8h2oS>!I zOacRs?Tk@>na#T&&=W`rcnwk4oN|9Ch4@{>9R<-vRz~S6)PA!c!VTiA&C#weCA-ch4=eYG{mA3 z^A1c!`h078`xAC5rTb*{`&;w9@$ExbjiMB@kvGO3h>#8BLIY}19qA*po~wV=!Yvv} zfawpA7jpwDd3EDV#GPbp3!_%Ag19k@aNG5Bs;{gj<+cz#a%VN)I8-*8yaOpS07EW3 zHHX(vW>{q-&s)#w=uM1oG~OGoh@(N0l|0=KDH(Dj(uoO4uOw&emCnBSE>@-C?dB%UF+GQG(WGrBQT>mu|R8FM=2TEHjqK7Q$xK3`#1EcjvKE|pw<7Mi(+UBw4B820za+D@jNv=n zrwf}5WlRtOh%8@uaH6iV3)2OyFyj3POT~?xufhu&oAipGkcx|c{6cTXSb4INOs)!R ziH~Ku6p9|m-F*ALVHA2F=`a%p$+NiGo*{G^mKu$pvw!pvmxRjwU=f*-XD4y}8gnLX zVONW<>f;Wh*#cu>H02=OIh5Kw3>WXJT~!8&GJo+_AaI&SVgD-~VPiH>(H5fv;oycW zuo(68niuS($#@Tcq>4?!2Wh}I2}#^`rgz%1E-AabI|_BXZR0}2J^xGg5?(u0xU8ZC z*~) zzxLSf3iCZVX>O%InAKF-K$V*v{4CY(N7BUL-v?*~EDgSYwUR3QvM8s^JvXYCSFmux z(Yw(0qb-|{i;nK z6)W2G9pH9xWq!@~2X*@hi%)B$Zhi_XHQ&Y%n)1H(X}epze~vZ6M5*=4i@S7#D6Vy4pG}*#zYU{*@TSD6V%((Ls|ao(hmb!A<=tqe9cLqg)i zm@!3Mk&nak67A2I$j{MiH0Yxudk&ip@t4S?#$q}H0r_@WuL>1D5v0gTl^G0eZ?F;r zuGg)9TJa8T)1c9j(qPJHsU0JGNNDP9+o&GJyc5(bl&pSeFhNqRw48$YYYUL^>7;?$ znuWWcZgeRvvu+eIr7@;*AN8F-oSJHf;2QnRIqFcYU*=mX;wlayGsFEZJu_@svbdm! zZm5w9b$9fPiLPY!ZSl%G0fLs?>4vKpF7CX4<72nX2Mj@{c1LgVoG8a!s#j9^va4Sy z30Sowh!S^*L=C}Gj8BwCA2R`#5lfK=~Y=<`VOyC-XUf zz}sqnlY`N4e%iU<7fP5f5tKb|G@}X|@j-#4Nl=s`OAibdN`9H3FvKLxe?Bq7MczVa z`(Dh{l(AZnK7CSt@PCf^duD5uB~k*yoWWC9A76X zvL6_kf*pAp(i$%1=a3WB5oA=z2lu?o^aAnn7?L5R-ettR0vRGzt z>JmD}X5TO&>zU&VW27X-fHG~dEgvkjy;|{^on6p`e6bQvUDSC=6VPB<$?%v(qieu! za%g#L&aD1LV6}S}`U^({m8V6h?7{E}Zv$thLP&-0?P+T}QKlH8c|8KcY0^l49U_k- z#wDHqNdtBJH(~z`XtWAFt~i=kc;HcY@L-d?fUv z^aAm-Ih<(wDkh^{Gh2)JOBEmX`ROB5K zc|@n-wM5->vGMZ`%-KgE>NU@-Osuh!xD(~uL8$mFQE&A)L_V)egV#ZV`ccK8Ja28| z^r5exaoI3n&2;zpyLbHIe&`)~HxU_Y9{G;)FKkg6dq~Zay`ej;d&k^=q0#9neT75G zGIzx)&-5xN2ayB+(LP4mMa6V+22vz*@;KJ4nr8?03OzBDMsX4X`;L6dpb`~XsVKrq zniAT!W1qpMj#bIoEcb;~v9dm49q##)2QU%DcHpNi-q#tmR+1o<0L)=;R%>l{Www>g zp7-eKe4Gl?;R9W~%_J6o3Yb>U!`eX~M3eOF!Frc0-!m;Memz1xTajJUe@(QeF?8fS z%ad;`%QW%#O(iDpVb4YYD;^7)GbuN%*4*#(lgyZ<64GSU(D;?zNz)wDbFsZ}U z>0gtg4L%AZUPkBEi(m0E&(|sj`tI5le~d(Cf}~}MhK`Br>QRkLS6IL{=BD(dc9liHpgrZV>fLj%u>R4fYDMqCq~~L1JIavNT_Q19@yRg{(&B z)k>M7x^7*AYxq8~J#}vdB@f$TP6kH1Gsb=u`n0L)^(3azbj-|4?MZ2} zbftj)e%?yhhqmrjb0lCfY|g6gc@EMtS=mSWWdj%(-`-Md9ZSX6Pd0&iq0Snq9_shM z+Mk@+M?K7YH-rY(*T$duF!>|79C~QRVKcVUgLT92@5XV{~=Ta?rs zP&F$irYd`d4aBlJ2g?Sl6b9qrw7=Z*SWn$+KZp3|N?vT;ln-;i@7*gjj)BkmjH~xf zkPf|ubq<|WmgR$uwKrK-z=-^av$P?rEc%l~|HVgbD8`CvRf!&xfL#WHm_SdGr;HuB zUN{#HnOt#yb7&In(|NT(5#y%Zh7-YMhSSHJR1G+&< zh47z4O{L0i@!5CLA*;wqNHa4q7*0#Cs(3pLK$w2bsy z`m6dLcczoMu?Vp|-e4J~cuhr@U&K7R{3YV->qT~F>I zlke{2mtBt?D|0dHrHK%uT^8-OU>JH16$0d&a)@RKkA#9SiHnk0f|Xf!aWZ%@Oolbo z*(JEij&4v7>~|@W?*!E9?}P}E={}QTl+@>co>tj7L6B9+i=7bh3%a!kS-cwlp8&2F zQR(x0P8(Ag;9Zk#d^7=+;uE>_i|>5w@O^*p!e}K?@zF+w2*o2uT_(1%Rksf!jUcD# z-%>-xv?>0#`uG*-w&>9Ll2-`fG!<``gtG>S%n6)&JATzELYy~b(x-6R%h05m{xV5_ z)>1U(J@+0Fatp{{`BBNCjZ;6PBzJ%Av%KC7MJ+RdBLBe`Q;o|;Xae=jsE2vq;ZlJj>lj$ zY(9VDk1HADYGx!z&(-09#5PFD`$d3%6I)@d?Q7XB{~?C~i7;uS+JI@`jj zXQ~laIjvj{+=)L}1|N9iZEvdj1vMO{)~qrmMhkw_zR)#e{=e^hS! znlMY;EGXmV!2RC7{KPCJ8z@;FdpNlElFaLcJDmZmpOZLq6Z7==@gx`vOnD-Iu+Qq$ zN+dWP{@Z$JF;GZ9x|$P*Y_6|zlfAfz-F{BnJ6ykcv~@& zzpRgmCd}YsW!Z5kxaGP=8KT@(;i%BTK-q^3@dObto78QPSgZx6SzzW1Dk&P`;o+-& zKME~vfGYX!6T`LJ5-(4|DJiki|r1Z5z^iIYR#YX@&9aVpa!UpXw zZ!p#pp~E-x3=Pd)T3)6}?Y>M4FMeM-{3=a@`_Zx87$*jBFJ5zfTgv=pj~Id_fAqT@ zQaLlIEMdBoL!hhU@k#onG>BJH5;sIcNlHR3FPe$|ai(fyk}u`jO9yFxLr$CVKZmt| ziY!WEl2%wnI&1DF>*E)n?AhS@zs`00&nC?TNAuY8#e_M+(dWrbpw7G8#oN+fVoJF4 z0aOSW^-SB<8rwZQnqR{fWTL%q<~iUCQK!7zu|xX^HQcG43Gg3gT$C6k@j`Onwv>i- z0mI)J%TBL|Au^mmF{}`Nq6KL8zWvkJWiw9`1 zC(Y}ukGlPA+CZW!<;-@vGx2Cifjt2Vuk_R`U|MXdMu#Yyl|OVilm#|=>rT&(!CRHQ z9fxM5{{0cpw0W{E0TUb8JTXbSyXtBOT8{OyO68)k&@ty0j5YuGPTr%a9j|z^Y@@Z2 zXTY!bnE?us5O$A$0W;EVbO`c#O258-B?*C>=&5lPp*)2uv?;%!MU#bl# zDVXCTb{PVo~L+>Mo&ocQM8?84uWUx93p+8ftRJTMtdhR@f$ zlrRV)hQy$aJsUHkJI2UeULEuK*gi*E$@#5k%No7w!Hi~M}b_ekkB5kmJOsuU*I-?sp= ziYdCX^Q1{bCxaq?(wLZFVpYV9P(#0p!`nQXOZFkgQ51EozBC8UsmG=8f$a;W6JZx5 zgu{9PGS*0cB&EYn&(>{HfR(9q$uraXU+X*1lUn6TPg{!qrj=%l@{V*#aN&x?fg7*k zvGj<4*BZ!Xeq;!ug>Uw3zfHUG_%4ZvUdfDpDsk=?Tt1C^1h7FyoSF!e{HNG>zSg~z z5HO!1>66W#l*r9*F<t)B&`3}mp&ZtPi#lC@>NuZ_JRH;_#szc=iJxZV-trFN zhgoI0#FjhXyYAOzz7ZVV`H*VIl@|rdMT%~=RZDO6mko~VS+l7_0JLpJFRHVs-}4Tz zo1C7!O8eU?VcvnRcbd(sR;jqORhL%3qbM1!uw95OT?PUUqePtU4!It+mnh=`q3DL3 zH9*aOvv%`rzYiA*`RbVP7eHu1AAJVf=SYfV>g2mPc)NP1pJeH{GU2H^%q*a6*$$fF z)utJb{G|F0pR3BPVE>vn&fB)~NTbGgrbgG{K=J<9g5+1Nvu!bMGA!^DvBIulCdKBLM4%iDid~mX0iVFTj3$6MC7jEcduw7l6(Pw zW1mjP0q|d5PVqS@2r3E^wOS=)#4x?vC7{uyiR-NS0H@t4?~_v-O5hk69`O0}R>1(H z_}EolaB*I{nrv=7&jig-ZZUfS36`W`INmpt?jcmuUj-9kOA+H$)TnIBP5)yf;ZV!P zOAK1Hg6328OoaO4;b~_&I>sPPXQf7e6WP~5yvu%(M5Nj?(Q@VjE7lP)$1ScyI&Wqc zV%#lHdH3mDG^io0`b-kyV0NL$Xo9EG$cm1;9TMY|>*-Lg$79@8g@_Jn=%n<x>qfRu=v9=D5tim7i=hhSSSo7 z)C-^*p4w7zjYOP?JMN*LP5!F#BUHAQ#T#+DJLIE3;}Y{EVa|!;M6>>dn3#rX-$M4w zmTKOyeItMiO=1NA{Wtfr+!SJlB5p4Hq`XfLSkslx4?NH~mD4xi2M=MIdUms}>2%K^;#&5Nb6(wE{U*+T-qjr#0_^Zy9tA zV%s+akBr9z{8k0tJ>HD}T)1ymEKVEmXgj`jC7KB~>WxXM#gckXu4Hv)EQXSuZvFAT zna=tLC|)AEqBw<&W@w}|$09(vYWCV-DL#9j#=HUokK+JBXIr4+jbc6tcAvevJWyl% zH6T2hDi62>DMswlS*+zGe?4QhFFJGZkEw;z3-oUM;*cjByRz)AA zL`fBJ>+y(*h!y>}+eq;)kMscJh7fNFQGI`h%=W)3UABI8G61f#OtO&>|I zdTB5ngqh^$`0T~72H4#97|%Atx0l(89A7{$(e%n$OEcXb4y&lNlLC|Rv$oEp%|V6Cft>? zC-Z;bgo(7*EOH|^q)d>X3qA{)a%8kLn0o)=SV(G1JUz#@rs9&fB#BUAnwq)A?l2Oj zTYA$jHoYh@Re7#|H-5g2u|QU9lWMSQt0UmnxH;v=I5KS*eF@Z6)G+Cai$HTwt>Bp6z|aH?B>KVPmgWITf2P-XIFXFoT+Le@Hv`&4PFZ25svk_NQHO1Q=# zm+#Yf^$hcW_lG!wGnY@EaTykA-`NJ%0Quk-!QI=^4NH2f#=oDW%B@-~nf1TqB$S_CuX)qfRsJxLbOq8EVKNd5(}% z#zRlkpSR@S3r%ZU(-D@@t?d;D0``we#LrAhIW=A$MYwMH^Mk@1o4|C;4hQTNy?bW_ zH>MGPF8~GJf^cOp}|2j-LL_< z%%h62w!tof;)Kf}8#ag&BZ-M(ZS6N4HF@!Wg38^*$#L6)E6WOdYLYv|WCJFVW*163 z>=tfCWBv>m?AP)Hf_FbuEE=tjZ4nWVmM4*aNtF-j7)TH9+0XU%{gbr&f_t@n?4%&? z!-T}r*(?u5JCt*q)N6?rzh`RW>;TPLQ8{6D$K;~(5e&>3O_QGuUWj%`^C*v03CG@i z`b1Y2CcutT67s7DWY<9#msFK^hWzlENBmr)9+OdQly!TjSw~#CG#!L#w;q0f zVSj(}X@0D0nt?RL=vX>2_WjqOg_Ca3Pes7n$jP4)&Oi5caU{_g_tCRPwhia~boCmJ z%Ek}a#UGIdgnSEiZuOMEd!+we;rvxWbXVS$Z29yyB_Myv2FjhAbUag-t3)=W3cUvb z-@{A6nH{pKpE3{A_-=1}mVGQF`VNLZisI5CCB?9+vygY|h?7nR}~G zrv16(es3ETJ9Ohzn_KK~a6mNIC!h$s6+x+?!J?|wEY=FcyM$*)FBymLy?tnZYjD}E z`W$Ftq;Q;Gv-vsWGR;}TLlS-QW<>NkdyWBYnFVJfi-p1%QU|yRzar&GHE)6sB&M=S zM}DzbJV#0$gw|OBnEvU_GHLDLv)HEudu78@%vw7=Ky8v zn(~W0O1ANqPQdjtE7F(_@s$sMJ&X>7fd)Yc!tpP*!n=@$J+azM582$RFA6c*^ybWB zd?RCMPjX8|nV>0<*_GiA-7=NX3=d`d!ZfR`~9}7+FScmHEF4$QEETonU4(tpX>lJ(ov9LG_at^h(TsGOQT zSucN4KDrwHkNrmqL;v)I1{>7%qj^rx%)pTZ&M>LpwFe7znGT0YKM3F($UE@0#iXg~ z@?6+J&Ij-%tcV|A_1&PzuH*!^;jhyX&PC3T#N?*RRLr9P;X#1A_dZss4K+WgY(e9k$8uqZn0ML9u zB?|+!(?Fvujb0R@{j)ZzGM}_O25zfcC1z&s`D}8Vl$$A;IlBo4Gr3g#JJn|t*K2kg zE``-z7kDPC8I|-cjCBaDlmJcTWUi;@KfETXi;;Jdnn}Z|7-UI*)>Gk%XZqvHClEgp zNv|b9 z^Q2dB_9ugK>f{+k!-m2We4Nou+QtrvPZn}P_YUIlg|KV>I(71TT=eK(S)2uOlfc;m z^UwXQT``h)Yx1Fg)4~SN%FeYixJ$X~T%L`1L*k^{er3`}vJELqBBkG7LM#}{RNvRe z;9_CIlPk?}2fCF$mWcBbq^+!)xjJPmVdQivY8kMiN<^C-9Si4f{}EnD+@z)W4L}b+ zC>$i-9;~z+@JaJVJ`nz|C485gLiFnXKQWEjbQmq6AqHxH##2Uj!%u8|@Ft?xQBk?i zFd|A9=6M8L5&v@H9y#Id_&bu_MzQ_~r1$+=)|auvde7VLoUDF#*PAk=l$hxWS@zIC zd*sX*L2>VHH&b1dmom=~^W({AuH+d?P8Aj-i4py{scXWyw1xy1B#n`#(*B+tACPC# z=%Bvm-50QbO5_ik!4~I?Tu*9sD1R)5OGskxtRkO3X(sw_Fj`)-dMO4UkGCCB-k}V% z1J@E}FmP9o)hC|@)u@4@NQF|d0He51#&pzOO>%W*dZS)l;ycs>@=mlKy53D@p}kQ4 zv1{u0*zxhvE~s^eIBdz?E0w7x*}ppSD(4$ELjrO>xPDSL^OT)5gGEbnf8VRt=^-99`JpMkW$=BoFS;%_}ehP7%mvCY>W zq@;iR-pTTp9vHQCHPX$Bsxr%{Tz~NIS#r~$fFj+gar3XYXf+EQUPP%zD(rG!NO}#z zrkW*xDM^gy-AE8Xq)xfN(s%X|WSe?lX#NO7Td-uv8&U>!+JoM$KxmZs-~=^q-i%!tB^C>ygf zkZG`*6E4%@Rps`QTUMSx2~7!`J~Z~1%G_grXPG||nC>HW#6GrP=_tzj>AyEMKC-d1 z3pMYwxNTe(2O6mSSUOF3xISMMaUJ?=O)q7OcACzgR6a$ItI8IC zR!nE{k;g_NaGTmF(G*3ga4G<~sC|E);_bx2gjj3bizDf|Lj&ZfNcdRPO;W=26dr=h z7t@Qz^#dZGBArRcogP|-aSYJjL(meO9&J}9O!fYD?2x;Mfc+hk3uH)BQCHFBIj0KF zx9WgZ%R#q(Z%af5u<#|yFKAb0X5*`W=Bf`AxUY3^1;V+rSLOuymp4&VH^@x?#$3u* z&8&-gQoddPEg@~(LpJ>)Q;Me-9xqoAmfO9rc-cMk`DP^w29 z&9w|1W;5w~)?0vxUz|1JwCE-PId?k>ilA3P(1#mn0-`*n=q3~+-+ILrvxwu&9X`b- zZtI$u_kU`rH2q+8$Ajpx*>!HZ3iZtqNL`&CLWt`VYeUG^^c4jex`IJ~0g0>lnI|`Q zuz`NA7>1EeqPR9uu-2QP!e7jPiJo}E|CX>W8Kz;#5ER!_3v6Jc1p$+=I9`W`+&W29 z7S*2E3YGwiDObhieWejb$r5~%2arL>ZO1?bnaAtf67ObePz3#MT1!FH@{P9_bgXk! zy)ZF74v6{ePpN|kEAv`QBgyq;G5vzBOC!Y(qbR(-o(MOki$*jr2E+Q=6`0 zENNX|dUm4fUUdcn?y}?+qJ2~3k#=_IaCfh3RQaHg7#>OUb&iDlY|giHW4g=u4i>;B zm9`z9d9JYx8eUuKV5!k`U+)kWOHN)q` zbN_#>?^{_bdG|BV%%0iv%uZG~Sal8fZM5rV-IwNOZax;p{@0s}xI5+G3tAP^t~ z1d9JnM7c=-6d@jPJAjq|KplmIp@}&ZP_Eu?a0f>WcAvi=0o+g?07zV1^xkiGfSe1= z4Gx7M0a_4@Bg_T6BNT!F7@(kV7{>d5A0fCOIASoa5`u!Bo}K~_7qkG%%|V*y9>5ch zaRlhY&@eX-m>u9($pCGL3+%7b1c*5RhK_LbAA^`W6|a90dk01Zd{ zs!{M)80;}CA?*}UE-o-622K1cKSj7342nH>Z^6Hs>x@KsB7Of}*~5``_P@%ob9WUq zLc$-p!_*Z2;$R`-e`5|X3_uuvC@vx*3{~a9*!|ea8vHf?0 zdjTwfSowhfz+bO_Jy~KEW`{x|y#G!A-C{vw1w&13IljM2{+Cf+9_0mp@Z}d02k?uF z00AHnNCY4%Dh%-dXB=G!{I5Lz!&ePyj{=DQNf&!gf2Zv6mj<~18W0}9KVxa5u*!u2 zxc@Emhd^N<6#EAHKg<2M%l}X1zoPuFLjUiKl-&`C-*)alg#X75ae*Ve|6*X3>yE)r zfffoo3&{Vbn!x^yt`^LH4({&q-&QpY1Un6KNC&K<`9b#ufcO94aI`Yq3udPa$3Pwb zsOArD^lRP_a3o9@g@*sSVX$66;D6b$Lk4xm-XdtMG=H05*ctlgzDh_a%I?>&2?>h; zAZ~6DZ(?k(u`6MKF9f?rv__8UL+6Y|VeKe_tptm=_F6JU@$qN`^YU4sAWJl4JDb z-x?)YU2Bg@Fzbtd6vlAAd+zI~NtmTF^+?{v?&a;_blthq@X1*}M&AANF|UVR*+DC5 zs<{{(rM?aM1OB|hZ^vB@Fcv!$gTuIJdejExmqa~gavO{57F@|Dvp>Q_yTRM9J``NG zqqoh)cL6SdqEiaiG)7FUTu%Eg?h`Xs_BG6q*+YuBTW%JA8SaK^M&p;bPvCK9@~tuS z-@G?0;xdPpm)~Uf_oai6@-=!YMP7ze(Np`Vv*rvZ4bamhW~(=#aX96LPZdg26WHhr zUBWq6@N7g^E~fMQTM`Gr?sX2@3PCq@9*@+!*Pw)FrEB)#336y9;o zNXRl(3L!S|{)N1VE`r5%*xqE}$AeS=6$1yAt{R>;tJ9kM@ZEa?UtjdW%T4bjBTqgy zzG)rmjyOQE?=#a(1tplaW$pIvBsQoCpT4Cu=2a4Z!BlI!Lv>j5#OK6M2k7VKT-R-B zSCKTA6`z}6i#G<7=NVGIGt}J1$WaPP2aHCYJSRnB6 z;>5u*SRYjde%?kB+OcN2bmlsB6SIuM;* z$(6rxj*9j&o8qT&PcAr9HZl-*lz-Ab4A7*+ z)prEFVo}bqJuG@T?#~y2AXPZG1QZo6c5@SjGI`j~phEcU$8TqA?e5*F@jpYzFhO}& zBH8v|S_SA=e6TEY3E!l63oj1UDAO5#oQh*ryBYI(`t`;3?XUWjSJs$m6Uoeuk;9Au zcUkVcWfYDjqUtp_W*Tyg4uFNPNbJQ8Q_^|RNqIT{sf$(+>e%B&^3^3H~edXT-N zlUmdTq5U^h$dhFYw3CFb4#25VhFdja_RZk{25-Hhh>#{7p3qv-3ZUrphba!Sup6N& zBn97-^nG4X9Ut3&@{O3VqEvKTI(e{}@0*#qE}uHQGwc7ovwuDZEo9GsrEu)MvR-99 z@M`*%tR<91EV&xVAo_?ag#N=djmRJOopq$>_O8lhXN>?!B}<5V%ep9~Co6OxoN?b~ z@{)-XJ;JkCU?uo`_Pt?j?&I`BR7X#-xH=RIN7z!QYd816*;)LQ9J#9#F(UeLOZUCo~;f>{-%18H$pgqjC}x(!#Mwl`3}aI zxg|Ohm*KEV^B)Yo`I=;6P`qJ?@2>aVw!Y4hkTy+>gu8E}<nhZK^3dMjW>XRICn@?&x=)y!V_65vlcP)Mj7j11 z+pgl?Y%-oXT#Z&KsX&MZYuGcIQ2VU7SdkAVneo8?>;#3M>n5)WsK zo#^=z%noFpy9%l;?=hBvcig%a<#W6(*5BvXQ7CQq)5+T~D>kU7&e&z(L;4#1qv8<< zg(3QX#N)&-bDhmu*TjABTeb`%6;=WSdohoj6Z0|%Ye>+&N}C#^?qTn{G9+Exi* z{GUOB=VURtqCqjdO2T*3?II2fP;qI#mI`Hm((G4w$~Sx*SSKQRU!af(2%yBcF|R?^cs&8b>`odGqtfxeF;Z0y0Kw z$wB>DfUU?Tp{3ONm0km!DS%@8p#5|76;HTsI@@B>r6Vcs5p zPSL3yNFz7jxx9QN+G#nUJfDaW3G|^WQ+dU_cIQ!4L;NnJ)I{$ShfnDAZS~hpbEX9h z`Q2cQnm4ew{e{5w>AO*V7Rh%Dm_rorD!mO(a&@g#<}EMzTD_9t@x@JN+HMRfio97s zIfZ909>QD6_}NtAYx}nJKx>u+@92tuCbK>6Xe>>ScoHWh$w`ur*_WmT7;%GVVnHs+ zp{GiNcPGeHqZ@b8xSq>r-u!q(j(LIS26F#&{ASIJVQUIyPiDfR=GZEk`tFybPgaWX zl1q!C0}1qlXG@Jj-K>YyD@GCD{hs2a-6i-YY#h34KWP-b^GG+y|Ln(;27^VPew`sn`jS>z zmp;ct5g_nMP`QMWaj=@`RB%GSGLB=>|TBZO*#59__0~plW5S zs@Kzkep(;w$V~-+i`VsNK6S`{vlyQ|W@_rp*G)qK5!o)u4m9G8mw>K(| z@68(Y<%*nawBj>8cPl8iNL=pnuz63?T33A$OLx){;B}_L{xg>`v~XvCT);oCY3$}m zN<#_V(s;Y_Xl4qusyZt%SnBr6E_+tGYj=2u+sXt81h+j2dZYBknz?1?=bvQxkU|^V zWP7wZ)m+kZmS0Glvc7Rig&hvbjv;8tOn$OW87ruMJbxzk)|qZ55&wbrdA7DYDI|q( zr?8~0PoSv(3ob^xwy-yU5+U@OqS0AS%`$?APV1aJpxz+=!%wrcd1M_!a4Z2qX8a6i z39nTg^FSik52!2-`TFf2oDGA14_3$e3ewNoStc3ws&4(^@*&<1qV|^dd*_v@nv(1a~etgnCIO<&D4L(P$N1x*?0RoSsR5!Xw;}t#E zo6ao@0!i8!6KHnrp8F~#(F_&#Jn;;gr(esY6kw+@UfXtLz+|8LII}xDvs>QZt)#hr z0JU$-`(8=WqHx`RBu(~c`1k_+>@?l=4nnW;d9vPz%&6Ld zo)o)oeKjLTnbd*YrP6y#_%q){BhHu8NAkf;M-D-d%h84fTy$idwstrB#UU3j?d2oW zK*MXuBg_NFnHc9IK_Zz_As2d{oZ)f%lcvhO)V1~ebML!<+#8iP91Ff>j1Rik1El)0$m*uD|3tCAiAAzLQ0n&r?0a-SquwVcktFt!Co7no!b5{T`h4l|yF= zt6N}goO(@jbd9H>uDfp{ExNUNyy{#x=LsMGvzMiLMo-eKmA@LD>$0_IjD?5umA6ir zwZlZIWPs(|si#D6J4VJV&00wZXF~C=Tij-9{0T9C2%A@5_a$v+XtqDdO%SO{)V_MY zW~Rz)3renAZ&4laZS)Ko(6=(1%%Uf|NBo>!x#Vq{s^a{SF@ucj5ux{FdK0zo3Wu^( zOK|rHKM)ipHF-W6fjjT8qZ(YD3mLk%0Pw zKK5IGSqU_&&eeLkw#;thuYZGpJeY7H;9*H1<+`?zvwc3~80D@m3Vs$qu~U2Gv9{B3 z5}>hY;+w5Cy#khb7av=yb!7QX!h~Lun$qJ=LKsB`zUjIoeyIGNq#IGird06)x@&5Z zGP$gV1(5)On+<5%&v>UsmYc6alB6b0qpxm%UM30Gc18!f1!`fWy`?I{c{hS=74X_0 zTamV5`WWThs`C(B_2+#>sXvadJv=#^%N=CW48q+F$tb);_Eu1 zi5{metCVfdiRGm4kmgkqXnAa{ay!v~VTwaGRsp1k7kXQIk7sN3Vc zPP*jc>qjryo_0AT%SS(p8S9(Z-H$twl(*80*C|Z~f9v3tzX`4haYwd);ITKXs`ZoY z{LHo1A%I=kyd}Pq!QQ!Q6YS3~PNOH-TeziF0}ITNnd=%D+?lGXyT(HC*>MxkGP=n2 zpyS5nr^>m8v7ljoyp{e0IcK4X}=%c?BKv#TTN)$^`Obz}=Tv=Y^VS3Z$qit6S( z2tvYV9x^lu+HOqt9BCPUE7J@Cg@2CmIje06nTSivQ04OHTd+SfYn27rFpUrtr zW#L6Ver(0HA5QiYW{GnL1}$i&HKQGKapTNx(bVwFp@c=9X;!b2?{WkXswO?exmV#e z=68awM0@QOs^&aU)}Y+jjF`h8-E%Cy*<>yb4V`a?yEeCmh>Bg4GJG3XOVmW@6w)*<74QT- ztDd<~6P7Ox8N6kGf2DW9GO3_>l7F1oNb8m1dE_KMZFlK}Th1XWz20+)cphztn7&q^=up&uV9_C@?~1U0%IzTQX=z_% zoH^WWu@mrkHwL8q?GuX?xg6M|;>N(b&Qp)6N~U_DYaS%TKHs+t8&|#$1Lv2iZSS5w zy=L*$$9p_!hW$DWRI%thBb;uhFZbDoyDv=EH$e*D+eEtKAaYasdt&9bx9o?$pG`(< z--&+zrO=~)Dmei4O*?qtEpIDYieTmRif=x^mo1HW`z4i#-!AX^Vw?Ns&O@B;QQQw~ z83AWp?)yW2G_2B#;0s`FEL~6Q3#*w|DYtoMGWmTQbmE(;bY{N`QRtU+*OGg^`M67T zCsMDE=)_arVIpz8_0r(7CFd#IyE4R6+k;ad$)@Um3^nhWhf448yM}k7T-{2XwMZId z31quroSo0XsTqi#p(u>O*@s>Z=Ab>EkAklH1LrIAon>sdh3ediGn8OS!smRw^Hu0# z^CK<>BI@d<;;$L+w{0W!UNf8=R2d*{I`=kn`h;(cBnpNnPzXydUHG^N~(^T+Da+}t=-{O291UC~=9X16nIPtV^R?A((R zMh>a1Do3XZX3P8-iOyUjwS=GrYPAKg6lPj~aLF)qOP8u)D#Ac7e;Bi^I8nL*J?FRV z3ZhRzz%94-_vPxvEUJNt_(3PQ+Akk=$XMOy+Ry%ITRPY>ey5X5LSxFt(-k^yNR<}P zy0mEhljKx2gR$y7x+!)!Iy~|CirF`e$hUVvFoy;!ngcR92C7*3oH}+CH zZolTUt~y=Ogm5PEX)|Yk`RrABjPJCto1sM&53|A+6{FW?)wtVhw%Rv6Emq(;ahyqjS8CH&zA6Xz9afK7 z9N3pa-8uYX+}6A&M>8tJ7Oh%8xN{o_w`JCMJ~Z!do#@_nswdYo+#x+W?=4|}e8yxR zJ{I1r)rfydo=LwKumt_&Wv0tsPSgRUjmjr@=b|wppF1_x(bN()qB?y;v!MzCcN%)J z+Yu-s<^@gp#BcHfw8>)iC8Rv4&_XXqiOwGx=SL<%wdp&`W)T;{3kLIFSV8Bbr3t-! z?%QBAR(L_7OXdtJD*1wr-tFUm0m*Tg+|+H%KAM(FvIwyC14JnnLeL(Zye&lAKokp* z)JWSmvT4(&NC>U0qM3SO8~dbCBV%#oQAuHa9Y9$ZYe&Rv}|j$bvSZ`HeG zPF_DG(8hUv?nxZRwPg*IPTpZLq?jb#H{l9jzMw#wE?sL+`WE(6@{Ngq+&3HsmB*{x z2L(Lu9<`PA;3_5{A1-p^wLXdL(i7NmTm~gaC*cSQ9ln{|$Z0ibi?PF9^IF({{LOXl zuDhc}7Gn?{uWgmqyy5Ko^j4bYX*J$w08q6%Sm4#s*e-F7{luI3{M(k{EN^iAmbf@B z!Q=5GM_0oS{nXx)#`{Ts*7~LSijKW*if2yr4Wjs&7tVqsKrpmOQ?{O|-uVh$F4XT? zg`YZOH&I7v(7zHeYTNsb&2U!nN@_}OQeW=k|!jhlEbTiPDE|dzb|U)t}}bB zz1raX*<&-*G|^Ngr@hzP@1FM_J12SNkl7=A=F?%1l0Qy3$W)E@wIn#~YNR z0u{*H&T$Us$0a1}bbV8NAmO)UY}@w4wkEcniIbVwPCB-2+qRvF&51d&o$T!WzwF(; z`_TRJeUIJ0Q&s1jsx@{hT93-BMA~`Mf{}bPJC< zwSKb^#7LUk0Uxw%-Eo&}P59dh*OJQx#DvTFeSN#zQSOfC$hgpgtetjq`P6Wt`sIq? zFVK?_YUcm+z5kOPY-?&~YzfE4{;%;(*V@wtT10@s!A!zTqC&!?V&-J$;%H*#M8d(6 zYN-f@pBldeN(*o>bN#nA_ywN6(?;9PpWXnw;u2J(Z4kDF(5CL973uk{VYZcYJ))oK zEvtoMp+)Buy*-^EQt=oRqqh7jnWu@u_U)akSNdU8E3ooEvgfYfj_(?;e!yijO9w6T z^YqG8QL(c8PLQiRcxUyzNJ)?W|9ZsJNusu5c zEWYk9$-Of!Z%ck+6HkAA{*f&~laQ8R3n}{9a3HMZpm-d5VLZ;3(qloK)BluIqMjGl zDeqHn#n;QYUbA_iuN}%{yJMzqt@GvFx4uy3fE{J3i%DGpm-=srD43Oov@l$5cYc#=;ZaWZ|tz`*-!%-0!ii9~%VV>Ca z6AM%)vd}{@(q;{K#YhIjri++R@MutrcK8sbjh2~U@VaCo!=Rj#Y-^=%M{Y274Vs9A zbI|6yE(TXds%0~25~4D}1LaXgFHnVqD{vXuRYs68oeoOX14r$HOp!z&0A{-d4WQXv zjw+$=npN+TPfIpaGH)YW^+1h5<7Ph9*D&R`0Ck^7kdxTMN6#aQY3z$dY}7nD<^XQM znb-@sNA5q%mDCrP9msm`DXv@%uiP9SLV%Jpi7}4h{Y^EXE|D~D9KybGIvM9#{JG7R zyU9kWto8uQS_Jl;`*3>z&`u=~?G{Jh!DUIueW5tk=6%5I4gC!3t?bfyD2K>pBB2g0 zmQB6hcyNy>DbExNLf$?&>-ydLARc?#VBP86NmpQLjv`Z(wRU}v0wTKmuXyxip!WWX z*l5^-G$z#miA1%OrNaFw!R??$dwC;t!|_S2a2td4Q}QQ{{V(fRptS74i~@WM!Jd02 zUr*s&LKccDr5wfNR}?F>PoP~?9}$}PB_AY6wh!R@coWsnDep%JW1X%R&T6w?v z_J+*f9+YbM&k8+}54uB|d+0a9ocefYBk}hO?q)b713yigYMA3a2n!T@%6yDK5au<_ z3?Zf}`xkM?y8UVcpht_GN5@EN$^|nldZlv+izlCwxmmkKRVv!v;^|jS~-#S*wDu?M|75;QY zuV-M!t!ULQl)?K+OzosA>3h;`?5T1|PdubNzt147mQ5rV0_0s{>N~A^6+4Y8SMZLj zL&n&q1I??w1{WD6tB=aCoHcwWP&%oDT%V1OPT**;!aj(|aW*SSl}MEkK^+y96%uis z%e|M&W?F}sd0jR5W&2#d(1b(D51-t4I@kgNQm)YEfPz10yBnN63e2MCU(B79{kQ|AbcAz()t5-i9pVC=-^MyY5P2axJWW4V zna*3jF>!j|UPOJ%7Y#f}(oeOitC2?(Z8$YkCgdxMuNlcARPn1M<~u0z$r?5YMXRW# zrx<8~;TOqXP4+lU@7AYTJgC9(%u8#wP)fe(Px?;D0$^UU_Q@^!v@%x4wUA6Jf?+_M zid1aiX{&PTGhhUsyX&&IwJ{n8HT6+!0iN2#GHij~rKV)`_f2})3DolJMT%wY5}a&z zMsU7Ji0v3~lT(iuW>OdbhJi0#n50_m^XJ-T!!}+jA|umi6^hiU!G9Mz{S}e7BGz4q zX}p4{1Y~>A94ndslDt(YA41BYu7YTfl&-nytvg&pzyy((eK=5?Lhi2h{~8U>@z)zK z2+qmQGr~jW1IZ@gdJ2T)k&cR4Np^DdmWUxNho^BdQiGGlSSkGr=Ep1{Prj4nWywq~ z-5)kJ^ebK9FT#`MN!r-tz8F^R&pJVsRZ~C72cW-}Sa6qLHbhQwn0p~}_I%({DG%i2 z%+1%%K%@`+eq9-R)^uIoC!%=>idPf#$4_k->aVCr>4698y2R6c70{+ESOWY8Uqh5e zQY6Rk!%hm%wD19|qz8+BB{C%qdZ=^|fh47LuO#{yTF-K4D-$WP_NC zGhlt4B)|)v(^DgPY&n)|K!$rmpJ4iq%#Y7-W$TR_x+YYjBHzT>XwPK_ zRlUZAly6NiQ|=?4b!9bC^3zQnySgI}4?ts_KkX@D$YUCSnOzA94KA4tDGSBS7`>$S z;}g|J$%c7Cw>z_W7}CTLs?B%MmJ$CB@pNXp5~NQprzgA!g;zr~I;s@A?+A19Y`?T< zwB&SIx42sgsZsoi=&Umk1gV1K!|{&RO+;BzbAYg(e5ggeDVIIwHlfIm?K3c8Qwe zl0)zF;f_sIO#_|rz91vsA2KaI4-L-FD%xD7NE=+g)#8WN5CNA8tE%A$V*zC!Aat$+ z#CmWA-7t-(rm)*XM^bIEPUi1BOD~<+b~!KIn|AvCX`4PO`?+`cJ0?P+fLKvA&}c=t zNeN-NH@t&05bt5f8y5VM$;jIh0bX3*gLZK>Z5q)|P+RtAsdl5?p6`KqB3(Ze5!>AN z6$a&pnNNrLY2)r5H-hf_mHRwI?TbTrZ*}Lu8v91$?=A{5QmETrLa@icn#jxWrkR4p zFf{OHX#J~6Sx^QWCJ2KDCOb%%Ny~-HTAq7NDGN9`qW1 z_>p@18qRcR(fF^g`woCa+#1=gxn&uCETT;J_eA>-M%f*Y+MEI)QXAsS{{vD?1*HYU z0A)|5Q3PZBpP(Ygf1qM3A{aG5!p6$R`rpB#?nc6X3#w0Utx^t|y0+FHlJzjMYu8!C zge%WlHHCT$aU0vcR5+uFOk?9&?M#0#22&m*+x@Eap_!C}aNeBHt1}mfdE$mN=gTc! zC!Xf-qq=&NjbZLz}%MNPSk}d*T#&wQ%BW-Mq!OSJ0 zluj~spl9$-z20^IN4MujW=m3#@^Ut3tGWGpGT6uc20E-hoODpw!Zzj`$%td)Cexid z%GHNl#jluI2(R zUFr<>g|qacg^ME}<&Mk^GLE>tAxr&k&&G>NV1YG3nnigL#qxqBxWL6ce6K0Iu!Zc` z2&}qw0WBUJx#h%4y{AYr zcE;am@^mEPVmH6y4Q4=^#J#f&t`=I1pgNkG9hUPE3(*k;%=*2>EWsxXOX!+(O8St; z01zNrBX{IRPL?!DstY^x%}s_PPhpt>3)UaQNFoO-44k5gb{08(QUx4tz^|5*zZ3jc z5=lx`MoFw3uSdvKTZPU|wo;;(q9}o4fuB;{t1d@P`E;@A)sffD2Uj<;crOp(D`cUJ zgtz!NhiTed9o>;0I5HAP)R-KF!xys&;Hg7zhmBPBhD9#%{@2gI7ot~|XH!Cum2!Fbs8XNlcliMOv2kWr3vB#a#w%;& z4B>?+@D26NK~bw$4{H`J2vQ8Q0Kut9RrXqm5|77C_S%{Jm&ur+JKE|e_aAxX$u0hn zQGzRDt|#q_fSiC6)avbIvslls0wL&H-A@(g`PAQc0}D3u;Ja$JDurH#=Fs{m!X#P! zc5(A;%M)Ns4*eb9igMH!ac+fk?E4hVk?My*RV_$9U}^P{RlZBvA-eOH18?-C35}Py zM!cjd5{Yb+=eTN=;p3*Ioot);`e*=LLUeizVmmE9<#+I^a4Tp}BZs6vt`A$1(>s}S z(l7lUCV%h-sIss@A5eI*-KTDCvYEI9KRc|huNoMwP4qY28Q{DCY&uiyd34tu29=Mv zjCAp2UFvCMnzh2&?XG8Iz^jwawh-j0W=~-`%*mbZNwl8+2xs_cBvDMA?FrsKS($86 z9P(MXd(0o9oWn?&eA`yvl^h~a#sW?H@tT&lf=^lLNu`(|!jT+iB~B%_$ww?Z5&-*O zJ|w^7YR_K12>h~-1Jv^v=eFAd_$ivf;6~T4H*GW$!nHj{(r)8248)>V7$V8y&AK>-)6hVUIR(P{;K|byjTHa4i_G;&y6M0bL>Q{5kV?1R9V1mI@SUXYvgSW{bSDW zL8o5kfu^dJe38zx>!4vSHztvOwdJBKqOGfl*|AZ_ry>J9ptE!e<|;$7#qFzNbxYQv zw|z^~fp7dO)MHv%QQ=O%%XaSp3APviWzdn(;+W`-Iq2-MCyMLv*0tSXV)ApPb4{<} zv=*lg(TFl8Yj4jSJ*E1UI>8J%DS^% zbRO~&1M83dGco3bjGt|R!b{{!<%f45S^fGrA@ne7fS>)M8qe=s%@^C1lq1*P3G_EI zTiAISwip^5+(7=@Aa_< zgEERT>Q>;cn^i!+FtJ|;Yn;+-lhE_?rZTh1HD#PBM3q{jL+KZFswt+pXY~1Gk#QFx z>CG7Z5rjG0cUGUK7=G}^brh2aF~2!fEhrW*0HV?)OxdKFcI1kn5*)tHVwpzYOP66BzK(fDFEYD&%9T9<9qqp4+XacFM`>(^|tz2QYjgvqvn?m^J-h z0ZlvQNJ#4t80{ru2Dyd0 z6*@$iN$EXuj1zv1L5?2unk+9|>dimHf&6&?Pc_ZB8ksQAD>E76cVhYoTlHpbm$?!t zq1k%1yffhj$gPn_|DSd@V0O00HG+vs)oS^4HkYebVtfi|{0)&uoY>5qnizl2sL|b< zYuv&Ty7VuaLMl5GeiLI@)$}x}aUuuoCb&EbdFIG{gm85oqgDnJzVjfPPF@K%02PO` z#*235N)9C=Q>cLhano=C@t@;y6X&>Idl^#W(~YIvGdZbefS)4nB$MJnAHi_*k;RZQ zD9E?hXKvmQX0Yd?7`4oSpdi{|&ph?_YuxtRiFu#BM%q2qLX>UX$d=ggYv`4hmxBbu zkD=y^A6tSu-8GJ2^-)8kmu+-Mz&Prtma+Ib+E;alV^{)tdu_X4%mWKAXPyz^nwFr4 z)y@}9CyLqcnZ(X+>$fHv)J|iXyR??Vfpf7WsU0#x$}|?i0YL_tHbv;Rh4dk@N#Uet z-Dg%qW{D^=8A9@mf+k}zu7?;Fu<}+u>8&A~=(LW}>U1rLec^BLv;x!gQU8{BEVLM$KJ=Ws|QGzSavx50y_`Xu9_l5oNdB5qe?e{UH z!)+l(ZoxApSVL1QxZUpOGZH57E`@29K zQY#k~Gr1k5ZK_l^qj7t!_z{h}cr)2u>gY;gN8R9vsoANB0;CAi61tE-pb4@U8uqbP zEsA2lAW!!6ohduu_rnJ@(@&Y!;^l7b{a85P*!u>3K*GOnrFS{@l(=F*qgNM(XMcJp zuIU|IC(WfPt3;;}<8<=eSQw^WDktWA43l371?ewD5%rp!6U9hQM}LF2&Kv#B-n9fp z^Nx&K`Bj*DNdu-=&Dqp$YS;3i1Wlb*|QFZN8pI68e{@4o6d2^kfJa;%F&b&B@esya0&{`RsBR&(~ zZra6^KI+|kzrJ|V!%RZ^MmZ>uG|bT$1b4wj0t4Pclh{aHA?~%I_S}%t_%+FJ-LSQi zGopkfRY(EM%P8&>>mD@Kc6zRGZD3kYU$15IR22&JPNoI%3pTrb_Vz;m3c{t~;Pn#I zacS&$Vo&uwx9vsb8!WY4TG}lhg_43$Nl$ieP{Fb7G+(l=6Xl5?c+DO%%Q}Fo z5T3K--p}QzNV-|`J^o642u+Bvi9=s0&q^Y}qtFCiHMd`Aqp&ix^gScV7MZpDX|%?s z){h|=!~I^ytGLz&v>g-15mtL2z9w|25bZVC?`C>>Qf`Fq<)grAXAopA)^JBO+w#X z#B$OdTnis(mWFp7N&B0FK;_GCW#EREzm^A|HU+PZ58&n_RU2if_3klu9@)>+fSdQ@ zprSDOm~Jr&NZr~G7M4azw)>}9C@N_Cw;jOq&EIX(Wa-q%q9Vwh!U580$J@jp_@TZat2eNv z*d);QM8^0mQcAYOq{>p7?}{2B_Px$WN>HDeh9L% z+M@I!g6;FAx(@3tP+P1L1$u|!Au|RwMbCV0MTtr$D2P5~2j-1B_{t4#T1x?4hSiXJ z^F-(eoD@w{j9%P+c@QT@8Oq!@;Kx9=fow2NP&Qp8twd2luqlf7ftF_2dtnU?czJXZ z2QLdb1085=k(I^VH;Q-(GAYy$1L0&W=Mdfl^8s4~itB|(6-OrrCgJc@s>al5i$0L# z>vxnP8edj^$1pS%XmbPc5okbX!89rzrnrWNbg>dnTMKb+k7BV$?)SjYfhxg&CBw$B zbq4M39~-5UkVCx-tEaczzIh?VJz;$&NE)XI`Y!beEy4&rQ=9k;R*={PqOOq5 z7{3~^PE{oBXz2HS8$N7ms@R0|0A%lx%8w*Q3&zsvG6B0`GzEgb*)Tw@jAf>7|7U;U zodO!=JfcM+DU`cfK@;)fvzT?agj60ERDF$%%PzveaEtAFNKo(_KhT{$L zP9sgH3r8RbwucI;TyuapTa)t_Eq}1D2;T=x>3_TEJ2E>w;3W6%25v6&Be^0RTDmcV zG0Z`|BKeBN($-w5Af-h0Eq_*4f0#Ft3rB`(lKrjt-r`9g$Y*~bJSAo)zN%_+7gFTlaE)X>F(c&*o1CyPvajOXK2UkJzNELUl0i3iMzGc0N}n zuNY@|vm5t4W0{>ZWy@1=1{!2~#rBl3eg8t+6he6}s^L|MZ*ops+k()bIkyNjoc~Ns zqnE$$cev0FlBrYzL`1x96A$fcYU5|L)JFc6^{Z}6d$NZ6jO!8|*i~E3oq|W$6CLm_ zguVDEbe@xT{}Kho9~1dl{m0e2$oH?+Ldr-75!c@A4^vn&=RNRaA8*mIw&R`h`z=Mm zgGnZ>SAx9wPHxxlZ94Av-MkEM^VCl4MPR6!-k90+KJx1Tl8ClWA%89#g>|q){M7rs zz#1eBN&n<6p=JFQDC2O@{=}Kqk${I~Vi^h2c-_`ceHy&{7RMC`I)-~6UMF3$M9WUu ztu?o`N$mF(R_Ghq!qGYlJwp{>43(>_U|pnd_;22b5ar=vun!?BLd4K_rkWgMwBBc& zge+S!lEXousnr6`_BIcivllChHp-}7DWcUev_049L02|S=69<82+@W-U| z#69l;ggZg7U+{BD$c&mI^&3h*?kqr%q3a0PEa8~EgiWzloCwwzM^fW=1ZMM{eS5cyx zaE*4I76h*QDAfVfrBdidCl7O;ys4T>H~(!0FrrpB0yu@(sZb8zxFLEcq*#G*O^N5# zps%aUrJl+UHJP0uKc&!I-j})0p1&sF?!p!*dcFq(ozs8vN!` zX%eQBX|PA&zlMP6^+KDw?JC4VLsSxFHx5p|2ZER#Dw0l9s@1QFwa(71e?Rt_{U|J8 zlUtIO_DguMl#-E>g)~qq)G1^5Gf&$ZYO3Rr1(loV#qnNW+Vi-hBCuBd)9z3e;;S=C ziA@^c{x7%9by2|zQ4LN`SL5|ne#A!2dd+|p_y_M5pEtS|GaV`a{zvk51P(%PZ~H4# zt*ANp|0|4h{g*I~%=4ew2}wsg7kd&8uK%x0&huZu5tKU>dj^apwN(*}0rJ1bE>dk~ zz}Q;}mB4(wKzaTRWl#Ym?41AIcfd?#+;)Q*rTgrgdy!wlk$wCa!N!pOESL=)2{ae9 zy16M>1BBHt!~5e2N?Q|52<{DXi=!##MY51B3v0^$Z3IxTewqbJm8zm*v@#y^(n%{F z@jf92DAWG3n3A{%tkk}vebm{DIG;O_Q8+*3DJ8kqJ7ueL(wS#fW9JGihGn3B$R1ba>b z|M7QD;lnH?q&4cU4G#jc1Z{1lATOa6VY0iIp zjP{D;H`mg$J&x$pkUIWgqw>dk)YG+hKy@RV>G}AlB;ABmaV@@xh`iANeR%@a1I8NV z0xhcyxOHRl9tUi2iKx@I{ZKD{%xJNjseBE{Ti5q13$mn<8svtdZHudH^Ode=X|$#O z5bQyBg*quI81MQ!BbfY;q=ec>X*{~9c2gknG4Ht_gY7c_A91hs$P7UWp@jbQA?h6r z=eKEE@3tr7g5+N~XH7Ez#Q$uDAT?|PjJTC-25biul;wYWP@r+K{vRF`EUYZ7T&XuZ z|4b;@SpOXe3c@)#|JVGEdsg%#q*B(#ydV7jC6Tkeo0}UfQa?1#CN6zjXQ!1tylsB~ zR47P)wxLMCo7u#gMefyCHgx2;9D|{^o0Rc1|3G1k$;c6Pl(G1cQK3xJGI*Ax7Z`<8q3|PAmV{3&d>t z9Qf+Xi%0sWGj!NSpkCFK9}^MxEbBaFT_ut*! zey}DtGY98-jC>0)cdfu`kiR6Faglsu1lN+|AeeaqCs*@Yab=(x8p|~REjs~2ACWLN z%8tCDg$$W{Y5`$00uRkkn^fcx#ktPkS(%@O3B{`@QGZR0Igco_-c z1)rKExXAWH`mv0Z0s?Qvhq427N1?&5qEAAA@TPqk!8AF!c;7*HfLCAmmDoW6M1(ML zsG8s)+jQ@pf|_jDR@8OhA}gE!5OXwqq8?pj6cbKT5?)-0AQ@^F2~AU*U4XHAb-FPv z_hwq1?VRlHd=NL(xiYst7a}-uQEMp$a#7baluOA|hjZ*&oRwiIF%Kq6aNg?pB<@>+$YwrYgkP(aT2pl%;NTlWCi z@N7auTN@~-v;g{Q!njZT4|#-!=g95XE8`2;Sqm?GAy<$MVxcc@+#dO~_QJsI6=3Si znx(R%rl_cecYmAms}M+vv%iOMXLGs(N#ki-135qE*8|yVMc)33E`)3Pd?Wa}O?IoZ zhq(T7*=+TCor(YRl>^$*iycIC-CM6luuX*xk@t3$hhOK=nBM(i{Po3u33R-FW!?%E zy!Rr#ehI`!WoG}$_3Y?H_yq2Sy{!0Zdl|NoU4jp zXy#xK(fjYC0V3`owYWP-KIW8(Y(XlYi3@teu>0s<4EDh5WIn!kS%YY#17We~eHAyz zH@z>QU$S<-C0~@jAeC!E_ma_7M_;0@Am2_5p0Sp14aOi1n_sbe2$x?Co>N9I|GmaO zd!JjttB}41TE$|%NLDg0Hag##9(1Wvfn8my6@U~#_QQNf?s*8nJl}o(ckp8S@9GZG zmv~I;#DFW;kU$r#p5db7zn*VTqU6CnpMh z39xwNjrWz?N0d({h~z>_AVFiZinw^==X?7Jy)N4N{gFlqo4fNSzZ}bG+XG?DlM_j! zCMuNSy!>M2hK5W?eVTRDau^39#ix{!ed?dBwjVfKA_=o$wpRhr+mk-{JJ*v^RmxQC zRv`TF{h+#a9Mw(e%b{8)aj^M`aEVU<3_v@vs=C3&vkMPohkO^mx}8r$+#TlM8hegE zjPoz@5WjH4@U4JgB*mN@SOb+2SXJwOAu?ZMbX_-Br31m!X^?=pQu^zt9eJShd(LrR z&)Dkg%|Zq(nnGX7X@tqAsGGV}M*u-k`UV2*yk3a3@Ve0|Ot+@qVsIj4i2< zhaR`+%@KN_(2D-cwX(0b52a{=<8~)`E*Hr2gF8{zok=w9fajWW)>r-THk!uNx^8NJ zwG+)s6xIbAxE5 zK$72kidF@T&$NcFC8%~HqK>oRM`+v~?a%95GfqKrEAup3Zj^6Lj6_VH!pTE^34ghSN!YLuw}#`7%OQ+|)oA z$`&SF=Gb!DL3CaEb`L&3Nb>2ukI{YKMJIzCw_L+lTjpX~@yYnIMY(W?6YH08Zmhb1 zr}*+(fCpW!^47P6`dfjnLV#N`t-mY|-Qeir2MT6>+3#=D!_c`!(Vj4@ljq{A4&+ZH z6JvQYC+C87p_Xw8y$GVo_RQ?LDE&UU%%l;!=(F-CFz+^{>f$ilSY!syloeOXkm79u zwjol5PYXrof8@k{pF9O3D%%O9O4zfpYNPvIzCc`Dd6gEjzB(c78vzPDavEoCAzOkp zsburDzO5Hie9telqXzLq^bg*` z@CR8~LCQ7z^-h`A$%6-ft2lAaCGgH-Pq$&ohnVksV~)+^`}2z}nk9nBxI9Y59g_nR z%+q>Fto<pVf!E?mUX{NLo?bHb&T<^R+(nSk|f91GVo@5`SZaO6EdHX;bLj$I#^vJHiI484{|2{KzcA0p9`L#DhH@IaZ( za(=aT9{HZj`>dmLeSf$TOQy{JPK$@e+E|Ihn`ueQ0 z5pFOvIz+!T6vDeGv+mbIVMx#=6R^_7z z1OXgY?lQTwMmDIn9MS|SOb=0xCstp^ve@j}c)iHhNBkiS9Gvr!!|tswD7tJF7zT!LK8F9nRYHXah`$7l))3I2c|K z&Y{sy+#X@a`49zVSoTPPHj&H-};sSz` zX2vvcll|tD8Q(T>z01@jD-#~zgzXMlO9xk#!na9n?@Ia_JGsKZaMoiMZ-0@SZHeS$ zN9Mx9EBeP`>J3H==~+tL?#1v<{yENe2%lz~J14F`rdCt- zHIJbh_)ut#KY=$+Ys*HS;k$ZR1qKxN*||l3u)?r8aX3QgiA`9b^p#N;u~2K8wS;L^HEzM3k*pLc7>H7Jd1Xt7 zzjk(GIVh}vx+X%<K#|@ATeiwkHhaHIWzs@ zW^#VjB~z13SO4%bc>+~5qS(H3pNS}WepSFlJC8nI(Ig#jGdqy$6k0(5?QT9%en(_2pho^88j z&da>$RyWLF@x68_15PbS3h<1=s$fhkC>N)?L`eHLa<}9#$4FuS80o2^=O1akZ zOC|u0j0-*}({pKjO`q6~6JoRY6%3E+i612b1pM&Cl_6qoM5K{4eoZ(%jD$c}m-m4^ zTzBk1)BAPMx#x&K({F5wI$Ro*KcH!)HQypHggED-EjplxsE@@>sS2Uz3pW!N2PAD~ z?+ln>^Am_HojmNzfxAhtJX+b1j|}v815OJ4Xjj6*u0R-Hl?T5-VKZxl_u|biZH)P%F@UCT?+em zj!yAGpEYiqJj$MQ;^Xle(V#y8hO*U7)({YvN%E`P!zY2wVSM8vH7Ax`hlO>ks^N`* zJ^MYF>S*Wg3nc3F$m`udpIrEx;nLIM73Vn+@4sND%>50ZaNC(H8TrvcQj7J_R!wpr zgBB4KG)}wPGK8(%0U&qt^pS`v5W4&f5T&|1NoADqX`887SxnE|&cQ2DPqvBWOXYmm zlLn=@Buyz$7&T?w7Waq%gs5E!4#jYlTLcR<s@o;x@7Wkrzi`KMV#0Q#RsDgp0n(%+Lhrq(U!Uy07a^JDEJ zE$EyThbrm4bJ->$uXuScX610$qvu#vPy73uW9o6%t)?wK=?+U34cw6J#?>{(Jg&Q_ zWWoFY7NKn_M(4;hP-rbcDr`vx%VGOPk=pZei}DP#Up+l2O%Dv42473Ov#S#-O^z7r z0P#I0-)maYsi`pZ8)EUC?{4R;`Y-uD&e+7k4G-US>QTHbsoUJ-C$=0o?=XzQ3n2y& z=>DV%lDHioj~>YTyNRad+RfBxike=Iqrelq%|HjT(A~NsnJqbflW0xX(fW0Lsq#$yGjurX71S(O9yn-Lvj^{_?rBc8d>Z(PRv{d8`W*>Ad~)AX z2G&$Vki#_MT=N}?Ak&r#FHDu6AwxR)uMFpXp)1wwQN?1XJ#cFX5z+2npRE{?=E z!4!Lf+qnj+xgkwP1Fez%o4Lw?C^o0@n_$uYOcRwg|I61szl3}d0hyZ;ihzNL5ui~U zA+FK66NXnUwnK%|cvjYL51EB7my$L+WAdc^n}&L_1b5-7ngSH(@Y$cfLI2~Wd=1ZS zo)ewm?`EedDXo{eZpi5Ia|S`h|*tdNXZ>{1i^K_nZ`0vZ?-UexM{3 z@r5f+Rmvhu^oT-_5}pSf12emHe+!66NnvF4-x#f=U&*Z0U)3tjPry4;->}XWb4Be=!NO8-42(v?aR0A)pCZX zPFh-H3(4G-5(@Au0SeJse78ckt@V2-e#7lNeR6x9i=SE6reA8qe}0=s)MX}oU z#VO+VYftJzCPJWsQRaJe=+#mvv2uB3V$HvV^Q&*#EDnmCEGbrNPD(~1gY3rFCcEd3 zs$+gGI~0b+(ycJ95=j8{xWnK3vy`fv2~Xkvg@6wa*72$1X>?3J$By>m%_g>o(JPfZ zeUFgI-MH4yid3xoChAK?J!MsOpLw|T&&1bvfyZ2kd@=<+v{}8pF%uDLbm{>49Erx# z{z|%j-2L>>rEtzJ-eSq5wdh7^d#7vK$Zb5yP(F$#v(tC3YB%8K!R>Iuc_?^j9m%yJ z_{_sr?5qx%ft1;#Oo^j+T!X*_6RM%Sjn2V@c_Y?0&w_A;mtyoi_^bb`~6MnOUk z@z?yBMhl{oH52ggkJ4p(WLM$$u5Lz~l`*xzWM6>z#saM~}$rsqXpq?5)P~Rp^ci_si3uL zuYd9${Q#`KZNi+fya>OhM?BaxGX;>)L8ZAx@& zj>R6Bw&F&?ZnxyA*g+6WQ(vxV5aYyg!<&hh87A_?pTF6bQiI@BGNNN0^n(pYwh?6_ z{WP5jIJqeI`_6I$Ej~oAJkjQhlPq>zSLlqx7zRKIBE0&$Pbs2@1)8IDYgrxQ{>8gc zjo7Awh_PvpU~lXK#wiqbl4d%&uY1_`yKaHat{_8u`d1 zm+cTkf*5Ys;ev(Jv^|$yC9RQ9<8yxF!{{v`Z(CTB<*56&g!V06!|0V*f+@o;m!W(G zre@4MG6D><$I`06uG<}#uxhcZMF(r+&Bi>P{lsC2z*=7NS!__j>nh?~T5)Chc5)s! zU)n--VeNst*{5x{LsACwT$Nf}RH$}$5YSanh?sbSlTzms0S_x^eu2Lu!UCaMX@#kwyOAJ^F4AYXA2Fw25p*ErQAv%r z5Z8xOpS$*IOAAlLbk*Y)cyiox^lEV4RsBXX8|b+`HM&`0Cb_dbwZ0=<%e0Ox*+jrUEg_v$zK;*x`}X;f8gHitrXJN^Zxp%i{Yok z4St2*x?{~wonF!oYcCAWf88HzoFwFws2?BknBu^kGMfALo|cfjAZ%DFnp~P{@GpA~ zm8!i_x4uys9^899mB6W!)XmFVV9p^B)r^-ztER%ADBY8eXb3Mfm z_z?Z`pzQfeyTmovXNnxtPbkskw@4Um9V#_Uw|;wB&J$;VG@L+-C-M$xOjBiMF5uU@ zT=zUT!ZiqIo_b44**8w|O)quL^PBMY@PmS)D>B&#&=tH7Nphz()5xY@F$ifk1~SSW zF5X+&mwc0A8p9_5Uv7w}B{^w3XPTXLfYfAs5?eIXC<+vHL4q(ss)feYmcFC6y!8$W znzzl7#;N*#;kGl1RMr64_jp<%(J>q>GvmZTo75GuDz3h%-+_ww^IU~+WD`vx==_o< zV{ogBII^-O8|%@MyGw98K!My*mehbz(5X=9A4d126=5BJkwEP!H5M}JX6(OkSP2+Gp!ia}gdBH8`nm{sFraL0N)hbUyJbhaplZE4j4 zi;ol?ifeQm2$;|4ff>KywbaChPfaz};MLqsn$ggco9HAwmGGl_G88!sC1$FXd`Xek zpUg3?tP*JaDbwz*5H~JGO;v-~j<)Csy~8AMWHPFwMHOg7<$q{|XzPqnp}b}8>;#+6 zN4Gf^o-`tLP-N=3VI@SK`-v-A)8Y2wh%Ppn68q$j75pzuuYP4f!@=qv$-{XQf{XaX zWQ89~aF^NqZP`ilmlp|#m&xNlNO<{=kq~8>3r^e`ao}X~?lrJm=S>{qnWWT<5OJvp z(pRh{XO|2#QhzpL$dw+H?`79iq23HlQ+}U&QQ}C%Da6v^BT#qZuLdI^MK(i3W$%^E zA>vU9ej<0dRi?G8ociLk@YqCl+l9qUqd;}zn~JboExdlUIW(nb1}VxQeIk{TD;(u< zzwB0@tc~n{*jRa7>C%!I_@lKrq#)7hgKlk`@`yTl>wgCUk>fqCrl$)2yxCa%q7c(5z;z)}4hVnV^cgHAckxup;h9z~v7w;NaZ0x)4M92Qz zrtng0xnJO}9~?r`+sGlE^L&&RR^ucU=0CvTrwz+OWUJkPFar&74s@a+++Bt|pb@od zoqes6W`FPXWxSe;<`UPO)+d42vy^8p#@^4nrrP^1g%yG=x~R7pu~+7LVE^;iHReN} zc8Xsi#Jh)v{Gk=7)wkp|Fkpf9}hhuaX-+@e|Myx%xS)*uOt1{ zgntm_Q^8C;OpuQc)!1k;|5P#oT~nm|4K>D&c-Hyh{zA6(04K^amh9JxwQXEdEQpG% z=uHfSCVui)F$hrl21@eWem8E1DlA~h_guQ>IbbP<7@SI1D^L=FL5=f*QVB# zqNeObIQiZo7HWnsDb7Nxu84_^Q>NE4F@IE~o>U(D#*l6{f3_+;x{!EJ&U%w);hEC7 zp-e_JeFwWm#)->}Nt>{K0nx*8P8!N`3zuPs`1K=v-1bXE8lJ5vM9th5S=iv_hwtsTJ zzJ?h8soq82z^R?E*7g>&_#s|g|J?h%oWYBtTdWbR8tv%zy_cJvSecCySuz}o)h_$7 zgmHngAxAdn(fVYSSS&v@)mAo|(?(uNx%-)0PAmRib`z%Ex6dEe54T41awBURfElwX zAm$*#>j{mBf&k_qRkrO5NhGmLgMShf9z#9yz>!m-R*BM!1^tDSXg8RXayeU^=}(}r zcao{+*7Fc_uyk6OoGgYMC%tU&m`n2Yl16r~uOoOqPQvcpiKTS$fGfY^9;F1LQ$+-~ zywq|_rqN3~U;y$MTH_6;`949`FzAU1)g6Vx7vuV<&M4J6b)`KQ>lZ)&Y=3rsHIaNb z8rf%Ryc>MHgq2IL%f~d2U!GjtEFJ5JABojz$(_&S>Qa>4lIcuo2#B6tfQA@yTkvG*qRx zMHUY@*CcOQmk=QR&B%-tJbw^mb{GE4+3nu&J(x9@NDg3n^j>ls6HQL2%I`GAnPMOn zzQ5`6!NYpRbwaT2G96Ro!@2y|%+5G{nm{2F&HA%BEvfgUm+_0!i~(Ea((ZOEAAG8N zHl3iM#j*+^7Tzs#h-O==*NE=Po9!lPI94_oYrHPJMXs;+c>bP z=^b00sM)yjsf}?*Y}2n9p#^^)k|$5BZsdEUJx(mKf)C?GS9iwN_~9b?Y0H#0=sG%j zEHK%1r5MI7Wf*3EaDVpKuPQgUyAAcMV=4C10gL4zez(n_3b5oPG$A1%W74>qTR&yt zeQ2J~0C%hAS^aUgno}E5JG4cfO(X(L0dzhA&Q;lj{cN2TY;2{hc$9}=CGqblCbLhQH

0z)$rI2UR1mQo*nU>^6NZg3d%`}4v3DJW*K+ggvuf=_ z_(g1wd4hf$Ykz87aP-Hy=Xv4aQHesk6o0f9pM?V`r#f}Jr*yD<3j}Nq#3$b3-Kux9 zE%Ggm3|7AbyBA{l4}2pN@58jtHXt}Oh!8*f^^$rPN%uF}MIjb#7 zHl%k}{P{WMBrkvMO0ZJF&{DEiFvn`wgcIluQBw9f0TpwKq{pg^?gW`qhE8nkn@df^ zbtBz>(0^c3gX`T~xxi?pzs9bHBBg51MGB-n!f`m@K)x!=7%An0rZth~Ysd)4k0&E{ zwAZUi(-j0y6R3zTne{R;X+tKls0*{9TS3c_>lnjr)NuQ+r3@Ic?Pk+!jeSY8w}RXY zpLsTR8F94pd$LBqa=S$E6XZ6QoWJB|O=3`v(0{;L9Yp6#YHZ|iw5aiP!C2Ynkf?a_ zPbxFR6N56+(hK7>xQnv1?cA9Y5{#rYtK%@Sd}Fd;&-Ylug0i3;0@CzoL`@(BurT$` zeirkp)n<~7_N^>%(UE~qSvHtwiJpB%_l%Y$6vv^z_Etta-Mi-bxF4I~!JJVRi<+)P z4S!e3$Xett9!yg@o4fV=B(|&gyu0uo3+uw~+(I}y=^{ROE7sGm@1g(IC^g{f>4y(A zoV9Ado|3n=R6v8&RZ$Q3L=Kx-`7K`TYu$B`EXNO&(9-m?%^I76=Fvv3)3W#PPmm%c zd0)QcB(&!&@dB#j@T3`#B--5SD7?&iJAc+#wqYbUanU^|Z{FqT3zkR7@s@tm!PG5Y zj2J@xg3t-&<^7%@I2SA4y^CHUD&|=WbEl!K6#kjCA3M@acnClbg5OK|ijP76Rqt)= zKO>HLoRHqZ&S_j88odi{f8e36jYEcNPNe(BMm>NHA?L4``x|E8f)G)IR!`%(kAD=X zYM*(rpG+D3(U4o%B!%*s;a>hyVqf|gULo_iGqf}?Il()fTewaLyQ+T2I> zeqTKNn7ozfntr#g`_QW?G=q1Q|MS zK*Gr4za%Am6U)2=;s}X`GpliTY{ZU*_*mh`SP&y%y;q8PUY6js|VVgCu@t@!|m6Yu#@L0P0{k&Qh z(w8o+%({|I{$w@KQ zC354W5{faT&QW)2mDm^6Ega(j{$8q8EG7{q<>ZJXX>(_zx>dI z3qFGnU8qwTZ^e@#HO`4abxIT3oyY6Io*mmp8StCoTjARGnwSt=et7Mb^m}!$#$`;b z#&GS1bSu9W&3jTT2;oKFYCcCt?%pMY`XD3Vc?0KgfS|X^UAE;UUmQm3Fsk>2oKeGH z!8)UIrQ&8KqjIj8Lw|rXiftsG;bqy4tv656Td;{jbB|vk@dN69Jnj zx{wI=B66ATYY;T|*k$K;>1D6uE_v>Q(GE%`n{))~srUIxvF@q-LW!4rws*bi?4zMR z{H#hlEsO`&+6FfO8F9H;^~~b=Vw~$=hqb^@&z%HX)q7$4N6t!a&EFa@lq}L{*CcNUx%c#sbcovFeu+xq5 z@3f`vvcfua%80Qy!QL``Cc%l2VT9`+YZyyxI_;4qPJgBDWrVFhus@%#M!7|E(mRJ^Z!^J+aLds;~)TAjupQp?j zpqYx&dc^qt8*E8FKJ*%h2!2TWTMO?YB=9+`;sh7aVi8DfBl{RW<_mtX+ zgSdoto%QVZVaSF7<$JkxQCZmCipkoAFsz?&<9~@!s((KrHGRbWS$u-gJhKxbEq~kb z(M}?tC^ENVQJD!ur|{c}|3+`q+rKbrM=U?LvaTc|5W_6nN!eRcC7^~Z{&JNBXIK+t z#8Mf;{flo(XHX>mh8e~-+JIWzb*toM(GF!u8OQ6R#IeUt_S_>bqhD#H-hl1bO&n~jC5n12bh zA2zjH>Kj#>nUU)UEL-P&U26o^!Bm=Nt*wZwDA!x33_Dao=Q7_r5scq|OfR>3-%Ccb&G_E{Cq~yG)#Nfd=Ri zpHLB%o!?nu3pf~~36~OX3GTP0(Xz<@o~DtGm2fUm&TADo6*3`RXSQ5Gr}*7_n7BmS ziAImt_48h8;yj)T1N|^40xpS|+YhOeW+NV~NSoe?2Y#WB$EFL)5f}Jj_;AwI z!1~0lRKQ(Nqo+$K)*%n%z-pC|UGbN{UzYGryAh6YM{*T@l5X`VdSUDGK|C)n))bfZ zW1(OgV_}gN7-4ui2o~{rS%0y^`bCNvXyIz~5juggXi6Fmu- z6sh7Y8yiADMUO&VgEGVL*Y=wbkrA|JQ2YP^HLXWASLiub>K>CSL(O3LK~LO47y@T` zX9lX|%e+Cr17_ozlXx_=AINoPS};;ZFa zMR2(x^2QpYA*VdL$JjqzooF0%AQFADBB=$cHj*IV@TF!M#tLgltd}6AUEEvK#9;C% z+I4M5SltE4h2RhU)Wj9w9N)zRS9~7XGqli-OuD#8qyEi{kKoZs8?R)YbNRAdnP! zMf`L|kwXh%s4~d~+Y$@=Zozv|wK*aT=1z)}l1R;%>>n(H7ZF3=XQD4*g|Q{=CpFVv zQ3(AOD8qTXnHFZM2ZWIufv>6ed@h8Q9GWleLBBY$7$UWe7pTTsVY%w)db zl~5SKqA~A^#2f0XtuI2!ZM;CD+BzZ6-F?*31k5YB-=51bxLsas_?2)K5WJ}}YNnU|u1|eZ$7^Ovk*l@(_dHGK^GrN(&Y!T|aCwxu z*gkZ%H+vaYLN;Ml0#8Ct5>ro7N92qsZM=0^6ykUpT)9o>?(00<_7Iaa3$$FZm>xJT zF@Sv4uaH&>C$PgNxvHGFEk!pv6%L^|x7z$^H@_g(=zop1dY_1oT6F%DI9PZ*Y4`yJcY_=}KMksZW zLiE5#3>c}K*yGF5G(E=zqF&L!YBExUY5p+wTc0>K?^cd}4^or}aE$RgG& z(32@BvDwLhzJ`P^qUMf z&6qci7cDdON|I!aoQEJhDH(?#cL~R`sE%Iv9$%1 zni)3RJn)K|ucvIibx_{yP2};&1woz2HdXoFsDA_=^ayWk9dV8y(_G=!5b|E&U0KK+ zAzVTp2v9W4NyiQu`pfPbfwsp)q;3#8p(E{_4Cw4fPs3Z~kTH zTOVZCLH*PCeK_9P(m+@KiX&|g?^UH%_3_aE1MVo5s+aH30zJ1sGXlgLm(T$N4U=r4 z9=G8Q0v{U!F*K85p((d4(E_C~Dm5T5Aa7!73Oqa@FGF%=VRUJ4ZbV^pWgsX-Ix;Xa zFfcSRGchWg6 zNkkx9JY;1sW@9vCI50D2Fgau~IWsjdGht?9IAdgEF*rG6F+MzDGc+ zKixG`-Sc$tFj7r85*nqlgcKty6DI;?&r`uC0xM@c8UY6@FExqNEGq%h5im7jGdJSpU^i#sF=1!nVlgr2;N&qg;xIEaHRUpAXBQGMW?^ArH!Ok6%GT zLI^Id&Spk-2p(A`hK7dbhK5eYhDL_UCg!N7{tzsg&=ljn_3<}!2JSE5Fv}kVttsur z?$tua8A3KQf-B{)j!t=O#4yE()gl=v;V*sWNr9H0QWM3iu_Ycjx4#(PEOM618{PLV z1_;)EIuM;esDptK1(A>-nAw~DpM(Ef{g274ys3`6;8@@+sUMIKOqd)z|0hCbE)Kt( zP5wi|&Xp<*1woJ~3q_V1=MMo3u(7al|6c$$f6BXTaG`gfXNMR9 zV|CEgm2>_43u_H!mF6guexRk{_u;nRM@lKj?&dmfC6X5agTG1AeVM=ZOR7QB;(qk1 zXL{!I1#$t8J(!)c;jSX;hhpJQy3y}iF|*^;wYT@Bmk!`+yK*`3_C58{cpD}Eqq)ip zC&OWVDdX&YeyJk%xW-5&kyQ$zh=+*|YEI1*Bn!1~G)1D3a%={<&^BhEY34#??wpRN ziaYLD5C|VKO@USbw{V%VoEmJCQ$=me?5LOh)m+cuE{+)acJ*bK`hY9nC|GSVMMF-g z)X&Hok`81I>bbtvcOZ^{lh3ml_&XV?m+kvZgtOu|m&3z_zSuUIM^(I!m{V#Axf;qn zcWpR?mfP)dsSVT6TJE~biwZN87f=EcjB;>9eQ8r?kTJayVlX%;f*&U9d!1Y z4H40ttTd$&34Eiz5nOb|VJ3msV!i!PJu2rbLqmlkRe>^CL*6ho~q`7J;domNEM=KVswZ5dg7NjTnhn-&s(T*vi zz}eXs*UdjMDVl%DiG`plq7Sr8BJX&Cw@?+xI;XQN*M-s5E@f z*gi2l7hJ2tk<+eM)l5LHiuXIlIWCa0j!~E7%}_Md;{UG;WEz|gAzIp`M4*Ajh%!tP zKfEQ4pA-Da_MA?xHP{fb_+w{83982gVNEb3HZYeL`hDk9QC!#s{Waa>B+O=Qk2epw zHFuiFXS|IT6*9o29~2Dn?7~`4>mPw!CwJuA)KONUzzLNXNDNiiPy8IM{sMHnPiR2K zP)YA!Voz$ILNhba2OA^n4z2d@uASpPY_6Or?h=t0h?f^RWdl+B zG---5j91`kXVzvwv7D~^SK1hcZ-o+nFX)2Qb_i|uZZidUI^BK15H)yC76<f1k3E9z$5^ey#CmcRvAw3VUMTZkOv`v91a|y9v}v4hQhrvYgzftY1AGXBdx1gY^{;d& zjaIW*oGDF`c=p{sos(~2K#${a8at2~th#+DU&!UAyj~?ChSmg+v5bV|bXP%2=t;rn zn!T#;63VdR?n_a!)j5QfIuLo|^B!3};eo_|v zi_j$TtI>93S?%p+0)iNg6w?VSTdxc?$dGsbnB}A@q&wWM_w*Nc8?3fL-ye+_1jG7$ zsORx+bFLZMM;9+!GveArrfEq-b@!uTQs;>B#s_d z=sj4Jx9R4M>fx4y{Tt_?U$SKJp)+XDXm3Oz;z!9=uIZcY05lsS?1>>C4hu|dJmPAp ze*HH2`-AB3G~t`u*zk`1Jq63r4Ak&@(#lKvUU)XP^!pW#^awpI%Gw_;(s&H)@Q}1% ztYb+b_ovw~(vY6a`Ynp{;j74cC511UzN@(9o6bEFr@g2glM$JjRQuoHsqwct1VW`8 zs_gC1^Ka?SG61HK=7kVl-FF@Q47IOh{Lbvd zxIWnzw~%r?Tye2-prQb9^SDto$eLv6N=2F}1amS}(J$B)mjR;Fm~s&sT*Fxt@l zgnPtdj~8j#+6~H^OXbA+`};#F1E8Bda1%&xsxiFn!b0xOlnglPhS{kSMwC&MyNzMh*Ie)w5^x%T7NapjKYo6pM!$A` z5;WNXdZB+c+Za4SurtE&A7$bc2uQ3#EJcLmC@~{#KGgCM4YY28{BP4b&-YS1)Qv$^ zVDPoc{e9EMaQ%|c-&t~l73bklv~dlOobEt_1I>`%ArR?RgjeejwLM_TAftk0P~={~ z3iJNNUZWf*!b!;j;B*r3nFw+ch!QMV;;t;T=%9Z>DWUg}#}TG&_b z3Pc+q4{NAM7C99^ob3~Uvkwv({qUcQdqdlt@OAC7f5YF*e#0IJeG4_Feu4~@xs*oA z+)%=mTLs=ds^Z2LYOos?_RS^Rg?KTSWbb}8X*kvBa}|m{9DRIVZY_LW_V|2zt3sxZ zJhc8Q(9c@|WJjo{Ze3Z^Ys?YvVe0%;Ebv3*V`_w}x~B-@z^e9QZF5ea#@0@aBhdQ( zZp8VzIzGRS)llf9){71)tdZJ{!?4FBFov0ty!+k0Poa$p`H{%4)z>t4lvw75N`8G_ z8a}n)fV{3YL$|tXTK>VW><5n+?S?rR2>lf#%bZXJnolER1n11NPHKk^U~6KLXE&L1 ze|@ipT|^dKbI!8unK~kQ)V~Zm4|3P*vfJM6d))IWoZ76t?n->>AVH>GZtsT;tU7k! zy^QkYXLuV(e5%nWil6JK53AgYy^sH$X|#KVl1p+$WK#Q!a4VJYA=H$6e$z|7lt{?a z={}_qc+93r_0>Y`ws7WF^nhJ{v{+$*9etQMu!XO!c)n-FweaxL^7wxgqm(EmCy z8p8-yRiBwl%DCrm;KvNW>vwnLpO=S`#`S0hIP{~=N1<(setzuN50~XcEbZZI^q!0r zbZbwaNxJ-ctuniJW$nljc9aS1$Ra?P@m}Fa!3w=n%mF;!V0Op0(SubsQF3*uu|EAp zTkuYZLrZh?Ag<5Jk-PX`?=4)$_j2^;=3p4@pHX_boBlYz{daw?+#sHGR|7g??yon2 zx%b${$r9V3?So13z6>Hr%IviO{xD~LV%3x&FY^9UcQ06G3>fK%X^BEdFyForqRyRQ zqRv39tZ@388Fbh6I**yPxhkmQLN3aKA2A-13H6i=m5f!Yr-S6n@~=9;{@R098;o?* zfSyDM_OWlW8>yc*Y1LpCo;YT)-i07=Ip)=vM(LgRMQHl^_cKaN{s6n5s9MVsZ&v#- zMY=%xcPUv6ZiII$&NfOnJB2OHs;q%ZQl0tJ?mz(OYtOsoUCzrkH#hd@&eaq zA%;S_ZiL>UG`(MyL0h_NXqDb#P2=R7jZO~~i8A7aN~HdFkVJR@h5L7Va*xF$4eGGB zWlMYu%z0ZYNM(p>m>5iaTGJc2(-3`lVj0gsXvYZ&hSu}cB-QZNPb3H>^yDPxhBwT>^WaN^j(is4(#1-aGnO!pQ)TT8u$JPj(X)k{ngv$azPiKfOkWmYA z7qJ$un`2N#zMcc7D!TPYq*5xx<+j#FL&*N1E3p8f3Y#ufSJG(Ebai5BLlZ6v_B-r8 zG32yIV6#X!g&fqb1R5AQ<~=AKWr8sUWoYtAN44eG$+H=Gnku`%`uN}QA%%K2c$5Td z5u)M)Qz<)BL^@4=6cyH3n-AsDdXhzcF8S^h)b0Q?XtN{$7Rwirn%uRG~Y}2`}jP03+{@NUNT_CLB3;Ndz_$_ z5QzekQTkpa7(xvyI0WQ^n<=C+=oK-9o?i+Z3>hS)Ac^d}GkYz&-%W`{7DV!K{=9ED z*6@AWY&)JRYn~jyQUm|(k_WG)6oOjTyA=GH=3?9%WF~7d35AVl+z-alSqxro`$t0L zNo_zPD1r;!-&=kkVF4mgq)m(_GeqA(;;#l#6fw*gWLWkX=kg7U@-lXqT7*I~ z_5Nhd;}=PVlSQNzY@Q_6oM9^oFYH@Z2uD-ddQzmv(JnU%I1m}ZSBASX(;lyiZOqu| zsA4|l+IdWWu-d`QvKd7g2>kx_xhnKyoOtrLc%;C#W$DK>8PPu9Pt(;rE|u&t#--+= zkThCgT;9&J=`e-zSVoRZ8Ul(yP|8UkUE{h*|42?6A8$dH4FKd5rmA%95nk&yd zmP8xe+ebnW!3BSkQc`CykQDrP#IU(>@|&5~#LLS^-SV%4{97{UFKsfyNK#viK`u*f z{nk#VPc=jjTI0pyK;Ptfu*vYix*h?P0VU%pdL7Oy-#CHk*)+ zt_N;YlW)mH+=AIB&c5tQ^p=yfN@Gw4{-ZVyr5@9$gZN$^y&n&R4ykV&1>UpYLy1EH zLk<|{$`WrJ!KgT`R~Uslxg;sr_C0zpkG`3?omxY(q8AaRB9C8}(w%2UYbo`?42kO! zX8OE)0zyc$DY}=n)#pzWXh*h`0p@dInJoQIqKPZFJWJRD=nz=Xoy`Zb9M6^rB+54! z!rtO9@x*&qOiGy*SY%Fz^#Hj)AAQC^QZ?+7 z(L<$|epjhqmA-mS#r~?+*7R(3Ajm1jGAB}U zAuhhU0w}Lp`jW~R&nvqwuu`2-Ten}g-Y1GO(iwAg*V%o8viUJKubhkhV8w1HRP#u6 ze7sa3l$o`>ppQ7`LBb&mYZ+au2w(9g;q0=vTR zefT!(NoqU`#MTcP>EZ$&+T;5woZ%QOSHEczmzs#%sd zyo@`P))PVg=FP!-J&ZWZ(Jtv%#m`+1~;m$&vD zG7U0a^TDiY(Yw9B?*(lDgvl4YMd;0)HN>?iWWh7P5PT7FO&wSK$Q2(u)UG%X|AiG0e}GaO86ChB_+#t6 zxwK%nuuuymhLFt`SLb;Bn7QOH3i1+b?^ajxq!zp(^oNutQzodPOV8Q&T3z>4GF8sz z5zFpqi&hCiewv*dR_+o{YyMS;X{9}9C#yjY>|J%;=Yr)3F>+;=;@nf>e^^dOJ zo(81_>ve`y0S{iFtzAFn-X1-+6f>|LPmXj&y~Uk@TYqLF!LYX0TPyiEa?Fe!-9VJ| z{R>QLArp-##H-2fiKv0`wADL_b6fMcQb;(gAm-f_XA|^EOc@sYaxIJ)%+#7j-0Etu zv2|4GJ$U>yvoGXN17Vr%z?og>ll}val=;vbv<>}_%^Vf;oZ`Tp}Hw^LJVXaPwOrT(3UsQz5SJKzw=4Ut5aCVq!23?jr~?j;Cy zhQbvQ%#&fJfx50R^+z7XdM)AbgW&RyC!gGB?nO0>-97 z(>kctejK744@+FfPJ#c12uA?q5F#QY!1FG_N>Nr-c2;1dy6tDTLD#7-#i3x01pVI( zfgdm&VCE=YFQ|EfBKpc;2>;-}iF|QiUtxix!uj|1()bfCg2PZhQ@=*zS%0m(7Jtd4 zq4cU=OZkcT@6;R%1Iye9L7*L`?yp&(MXPslQcPAS{a9)23p_aqRR{p%$c=;ZSCUcv zjtYi}h6NrTi3kqyNhE^;^_Dma@Y?iWpn;9`+;;Jn_P9L0l0!@jWAsBmyE70CM!V*N zO#?~xlr(g3-JalIxeuRz55JU-dJ5hRl0SR!$~@a!--mg>$ld|RIQq$)|yB*=H5ta!G^9MB{{2=HwGWG;_@*o+Dy+vqzKhK0XV4tfzG^uO6)EItss9Ri;H zp4fJ__t{mo?s{CGxZ$0;mx9-B{28}5e*{X@#N95wRkhEYZD|?^NhwyJ)~H7aQgnK7 z4yPItI$+%zXI1qwSp>#F!w!x3k0{g~i}U%pzDJNb0M8l!`Y?zC{V$+)(Hn;fl=s$x zw{_d%l&j9F4(Y@3^|-LsCws|yopgfypIze- zdfSlNfRmc!Q05XO4nnwxSO}xHJXub}2;$SxtW2HvDW(>E)sC=#0tPmUo@chZi>gob zFgoC$FI!Md@A!8uP#*8B%|+(7!P*b|8+3Lh<|_+_h<$@ei5$LKrQu`(gLBoJQnfU? zlzS$os2=kTBdveAvlBP*OvVjTM{)F+%*K2A0QFHkPU(KJIup!QCCvJl4+y=RlGQi# zQBHk9h(X{R-^coB0+!b2h1+fM6MM~V&Bwlq=3?(_RYi+V1}?5dHOgex)egT2wW@;c z{cngeb!Uu%5#5oUrGHc7t}Tefc=3a^>>8_CM^r|P^NOxkqSlF@-^F1qO@)D^>Bsz8>FW3&lA$NI@)|W_;$5@u&D{gHmzdYm>==AoFMy$N9j>)Rq?(c(Rk0ebaUf>reoDzyMNJ7%`9#01$Rc5_#;Wj!EArrICAs~bf{P3)Z61{C%0 zvU(>Hdf7|?ePliKAxFK*r1XdvFlgMhu?^k8D{!QG9&d^LJV9sq(b!d^85nMO==qe= zlxm;!{;8V)p)k6dwNPYGL`d{FuHc9#R!HLhbHi&AaR{nx&^kFL3nS2I}XWTSZG zzJZzcT?MOVmG62`^;33st@oFR)GW1AHnVP*Pbqozp0rtcMpmqOViTh*fCFY?=g=H= zF3${(O$7ufHbl1s^Ug z@1#Jz1M*4{9Ty{Y6vzh0kLURMf^*Wv!Iux3&i(26dkHO>72QQr!8`9lgg33@dfeB5 zDe26ARIEFzD4RSrb0vWg;B}~>*uJNob)It2Lp@$@%$I7%&gsNKZN}XyrpbZ`?VE0= zcf2|;`kS@0#?v-6?n>7dL+a_}@Putk>H$lE*zS0OKS*AOFdJd+zE|j!a@UJvEa!2c ztH+u2%&ua zq?FoG%5~@H0k9E>9ik4n`?v|-tJMz9!ZJQ`2vxxQq!(H=&-WFysx^xq9o#XdE zNnW3Mk$>inGA)3jNtoe{0-%T~n2l*mnJ2pbOrxX!)<45;fzGtmkdp4LA10BoW}NqZ z9ZSiQip{yso)}ae$m=nTCo9c@(Vo_S@R=cPq6k&;k`Qr8t$b0_cv%2U&4X0Vx&DoJ zJ-MX1a8#)S#q4k6`c9Za$N<~@hnA$^IO=iL=SQ6(_hd&6RX@MukZE;Kwg&9pWnHPQ zE6?`>h%#&|)csWm0d&}8QhDcwBVN0FE%(WKPr5K^t_u2?5wdlY^^U@GtBJ|crVjHK zSp+d&T79SjM+o1&?P`)hc~AW{YyaFz50yI8yQmGoSl>lUv2$ogOp1Eys8eWBViF(! zYtkkYTKN9kU!057&DGyy#)nP0jN*&KWvYH7mbgHHh%j8W5Ad z8J#T%ro+9(`@ybj;qWQZ20L~;@CDs$>FzG(V9{K0DWu+C*u^9b;l8nj6jhe!FBnXi z)G#ms65Q-CSKZ7%IzcZ>F*J)H2C8PFaM4Kh5DZ zaboW-IjVj^M%_AMi0jwT)vaySynldJ-aaR6)!3c?m>9UXMg=DEcNfL-H(&~)nHOkF zEz&s>;40lvDgKtM8Qn0$`iI@u5dEa`@2__x5D}-EE#Yee`2LAo#mv8M?XPE1Foo_2Lcn$`jka<*!d>AriPnp`WuZ^H*+twb(|Tp1jmOb9M}$6=Szo z`58N+fnQ))?;Kd4I}QGtBu%D~;6oW6_-E52({^T=A1E4J2Mcc{=YYLo0<8VCA-!c7 z54aY(nSIl>o;j?oK*jo9RQ)!4MH3D3Fso{S->$u$(?6ZlVq;G13-+CN8%VZpQP(*9 z1&-8^F?3esGz@E1wse*9`UaD$L0NLeYa+5vKGVs+08`o1*GWtLujltR=Q03@fI-CE1(KJj74tc)4*da|{C z|DmAi4mo5##QxL9#R=i^d{EXj?Gwv?O$~Vb!BhWqvQ!6oL?)q=0My-Kyd%3u>NDn5 zf9R8GJQ`PS20D7Ig{n57aM313ooInu?v$RnzHtP?Fz-#CQn)CO;hZZZ{F6=;pXc6z z0tGFv0I!9tl(~x?qAFpz=2@XQGKbAKDxCMk|6a#ktUsNP^Zcfg#wBaRgC-B85HH4Y zil&a(BN;1@87QrXfqFQVky%1haSGZlYZX5p&I2^Fnx~3Otx7yC-#_$u%J@$*;o&io z-R_CK>&wNVM@7*7$eLoYXbaXRC$s$Qne+$xX%v~JLcABE*c2Pe43=4245C6Hwj2vy z&9g4ge?hy_-3Yx60l(0xda+B$*IOT_hu|7hwwi3iG!?+=frK$s{^{NVQa|bLzY#Ql zDM0r;df|psAtEi)Loq+5bd8m>-;c$nVq`c0X4b_xD3m|T?P|rvTbz~S+ zJw_Zi-rj8<632BKDh2^sp}iX|F^f6+a(dBnrF*JQm~LOYsPySc3zu}F**r$FC0c_2 z1n-iktTfVX3-&*+b!zb(i((rJrmDI?uU z`kYG7oGwT@o(Zp%W2M=lQD==Hfw>3T$DFb%61gpy_EVh2RrW`Z(kmO3wP;5>{4_+y zuH=e)tiZuh;~sc|0tZ$qg})rap7t^DZ42(20u-Nys`#+E;22uj?-i+ z*m+gC0EEK#6XK0K-)~lm|7vw~s&DO+EVc-J#XEL_x2ShGiV%FBG5iVS|uAxXGL| z+BT;c!IK=$LNf9uu+o~}p)>OerQwpyF_bZ)WPKa;|M5YxflJ1mLQPJa;0uZ@xdt+Hto}CBIehq#Rz6rL3N=j~)RE&Wta}+1 zh{&32v%Yf(kTDqJ8EMsjQK;SjZqIi&12|H#fG6`lwmidadek>F3-=9SN;iOC7G4yz z+_BA9;rkW4aJ?zAEC_V_e4d<5E;A}t;d~1gQQ5_#uA%7>A6c#Q#vn)_h%QU6v%zy8 zqNZhxNt%jvV$sCVhvoKNywLWc9Gcij^RfDlmG6`L*6^puONN`ESf;<-{=kTz9#E=t zkZZ@C2+s-tCuzex^JZskM!wTM?Js=kSZsAXVzad#SDwJ*g_$=`-UN(S*;OqNQht7;Z(XAToT{Bt;He3= z+Bnsa8n{W(UZ~a9mob;4&h@J+2dvJ*e_K~=mzGL1(f6RmAjD0Iu=p@FcS@c9SN4D@ z;U;+h>F402;XZqIyY?xn)01vaZn7>*g{=l+J5$&Tnt4=O>OI~OmTOW_G0qaXMrqOZ zVRiZbga$vnCtVK@9nZ8iSl~=1=uJJMUZH*GD3Gp~U;7%&*zIe{bxKx=_Tt&&y>mtNywrim`De~)()R_fRp zt+Mo_%bGcAlDYZOkFcx14rE#Gx$2Pg!c<_oAVpyoHY3|&z%yM<)KRtXVUk{qryRB>Vv5+0)Rg=6Yw zW)0!q@;$ljwuBD12@t`5TQ}m#G&wP==9n41p2#qLal|Wb-mztQ1{#fwEt6aJ(yQ*! zb##l1OaAMnw*O^z%{!imEG7(OdMG1s(r;^Z*?n%X+#Gub_?M+4Mqdt_B*>jHxt9Gv z7qy7?mC|lhh{^;`Pm3!<>@|ds-E%Zkn|1J?p{5E317_-_@%{{w#&}%S@=;AxDs+RL zQ4J5YG=w0GNvrXM0pA(Dp-Pocp^E+0roHy;dfq$3N>mV*hZ}eq*p1F>I~2) z6$3r&45*EUIw@zOk{FuT?N9t9+fsg65YqS1DlXGohF`&s0HMF}(}S`r5kERyHoa}0 zw;=uIW6g*!1-QK>SkPr|lRxU(hSNp91c%vQ@#gv=>})O z56H#7)MBn(pwGz>XTKA)SR5<-@oJyL=e_F|3oxz1=wPM`?J$3#{*Mq?C#YtP4TDzQ za5BWT!`NNc}(D;&Ih zduVxj0`SucXjtV|R4bNxXG{snxJkbIRI%iX=LiuKHMj}9bT;~HU(aF)iLQ3HQee?% z;P^$2wY-)`Ki_jE8veZ(S?p|;saQ^ae2S9v0<{pjhyV8KvaE$kU&Hmz9m%A2-MVUh zQesC)=n$@y+1}K>*{PH6n=1xs#ZJOq^M5CA#2sBK$|79hw9+RJcF*_47opD-#;=PQ0T8#%G^VO># z0Z}(NY?E~n{NE-bKkCcoBaK``19q}V0llGQ-iDChF26RXKl&!YFwSwN>JMlTh~@Q`hU2Lp4q$Fef{( znK^tiSHJrAz~7SEM9uoVQwVLm5Ymxr&xdo;8c70e<;;fe(*pCCI}xGLiZb@*ClK-r zg&93z=>VDei|+lJ${qcOumoo&E+D@<2nu>gnV2vkNWur>rK)bo)a-x zM>!G)vOT%*gq1R&`@S1^?)RNKGimWj;hCVzB4$fL<%vcH)AHUY%#7HhbI8p4xKnaZphc)BsBFS+~;sNch2x$mdye^_myKBPsyJi7VLxTQ z`>JL1e5SF8#{G_MqgCa>*zJvFo7`~)YM0Oi9*s^h(+Hw(~M*Hygs)P3SynU z9gPXHd?Lh*Rt^bC6%^f%y6T&y6xWq!t+Ae7W|avVwha(4$J7zlH*Vfv0{Hs|Mvi~D z4s)(bnEr0V$Dq!*-#g5l#%C;gk9OtDB5f@aoFbBxwKwB=%Hh8L>#{;L#@Dh(nPhQ7 zauvYl(!D3*U4p5Ge7_aJH$_c>oQZ*E&YA7{ZL3GZTe_@r`OHkQ$dg29#&tg+gip}u ze2Z;bE&3rnklks{D4aX=95BZ9oo76lDIsv_JQJ35h*A!F_LbwBsl0KuPD=K|I1j^G zOaIa9=Yw{8P?A0cDM0W$k$P}o@=YNjh|U2kYzp(0$2_TGIWRPG#ThrZoIoLSE>69u z1S06bIVpN1JZSM{0Nyiue&SZ`{Cwp|aL|U^uU+sJ4sC*7Rx_1>3g~O@qb}4#=KhB# z^NH@DI3Iy@Dk~4JCP22!>!j>CxD zhci4F(t+QbFPL&3`?}}pVjgb2M1@B!xX_SP6Un*mrl!+5f`i2sIW&?Uc-ThVaH(G; z@9ze>2#M9!0%%-p{~zX+hnJP*e=)DTygdJRt8jG7|7KpJl9C!-qmo?R-NQJ-2f-kb zI0q(W$TvwhDXZpXlzike0vLVSYI3}fjCp+-6l;=%qy z2z3e$`FEX^`1bt+&al}S{5m`wuI_6WInD{9uUA9F!XF0J2-ewa)Dqei>O`!v7Zf}K zgcxGC0OFv$0$p8ud;2UAY94ARbNaDB(N=IHP;XE#nk}?*sBmkiTQf`_7|I%WJKZT5BhBcGlF5Vcw^eZ98*J~u z*j=t8;Q56N<@Py%XK4oQ6bO+m*gM?}Mo>!*z~vQ{PDeOO*FySFFZX;4h;bYZ5}w6^ zbA!?r!hKiaL(QZ4^9@YM^;r{eq{qem?eEgx7t`Z?@Je)KG>I_1?2JlH9mft4^UxvW z$%171z~YWl-GjW+hqrfh{=i)i&ad|M%Pl*$NNNT^G?7~hUBD+F^qt>o~ zNNNE3PXeQxYp}{b4LE&h*3l!ScgIhbTK?YPw*Wr@u*>b-FM)I+mP!1* z^OKv{7ZT~o2i2|TAwWmK@q&mh4~^8oQ40-gw!F(Uk2pF%Oa4swMf%nHr4>#tBX6Q z$nwsL;#Y;bC>Y7I=nRNE0&m&#SegX}J z{OLO+;Nj%*6?940`ZRu$9sV3I!c4y4bnY{Rogxw0navY-OH~)lqT;_ z@Glz=jT)ocuz#O@uVG`K(O<12A|UrTtmS)(K{AA^ng&)g@WZt_Ybt~52E~rsH*^#w}6m+yFR>$5N zr1#nA0J?9$0 zMVgR_qAgB+gG^(@-r7TFA(j6$+C*``^W6%0rA33dmCC6%CC2nFOtzKbVN6JU?jmw| zexEfl`+hdLJa^5Ks@nHZ@4&P*&OORYIZbz8YdoC-Jv*_u%p6TBj7qxNc++~@w^gX4 z2NoXlsccqQAeP`Z1FmG9^Gp_dDgui01rP1|M$iemB;{=1dCC4>h>1h!?)IQ(g5TaQ z*(}4UEZjAQD(Y6ZJpE3Q*~9%;@4&-DqPn(vQdUXk!fm>H$Xk7xR}DttY{_K9nyjJ2 zKUmT4m=c&GnIC=~jAS$!Q4O?N)wXU$^yf*%n7qsQK$!&l)BaL~@K_763_ChWicJKt zxD<1If$YpDf`RxthH)_vSz-+H$F4cB%X4#eG-2WVNjgD+R@<-qU6E}gsD;nxS7LPK zps#+_e+`ui6~Sas6MZ`?HUsz(725M2ZbF0-4U?=&5aCU45G{M#Qk)YE*&Ig_^-=07 zF;}}BK&s5MiR16i?a>Y1-G-tSR?33TD=~IQ*RY>jB7Ch!2(RSb>XTP zqrc9A?$Ty`eBtul3IF`%N;C)Cc_`%7;4UKXDd}6jDQ=j)Q6*^dC+|FX$7wGm`tx}>_y+y zQt6UtY@0KnL_#2`j_M`k1Qv&F8OzxI3y_D<^J0Kr@hDKQ#t&P(P7f>+*`}V}r|56C z!#^8DxmdC{9>yiaC!E2?ol?re{eH6`p~2G*;j$t_qF<~6|V(b@fmp@PbP z96Ivdlz!Ud=V=oX*WbLb_l*h0I|NOVO(O&whmlk6arB@6n6=yawrli~l5VLpegYqb zsr*Z@Yb#FjBs$nb2t{LHoWzDsAN@!U>xIRyVp4lfT`T@)7)b=bwQ^a<5p4@FZr=_A z;k4`9ZmpCa>lny~`8l!B> zlAMu2!>ShsSRqJX(e8qB67 z583Ma471~B(2*isO&Jz$tIsgt!|WvT@h#&~h@74E#R;V?dn0=@!3Wv@QNq**Lng2i4t`u!YFSZ&i_lA%iZ% zlK2^Ot*3*$wvHu2tfm)t%f6tYE6V|URg?UTzibSh|1#}lv1abxUWPTp!ge%N`$JVV zCUen-*noef_7i>DAUUYz<~M1vi%vNt5zrQsq6u>(R^CnUW$a~<)DT%T3@KuNFSWVJ z{G>eiF~O*f7KY)%cjT3loRZg<-1Fyg(GFbk zq~FtXe*+JeL7mHtfCTf=4tbk@(gG?>(^l6hJsbV!HOrZjC=!(>^m(LfLpZraki~jO zR32>)D|#j}6t(*4PjRUsqd5Ms5p;K1%B9Biz^ZohsR~e5=Bi<3yqdL4a!9DSF|P7} zxPPy+FW*mb&#%^PNkw_(QOn{?D%F&2uo<9QM^1Bz&PLlu=>QDQH6ihToEx-Bt@0yG z`C+5NI&We_E`h8;NWwS9!q|NDz8pWnYL_ulj_#my9qvji(A*+JE$`(P#;Ib!0 zOI%kF!BgwlHE;3RGJQP)DW?fZWrt*h+MFfpW!mw$IS5|?R~PZ5P~S>m_nX|ZbYuXe zTL8b;U0wcLn@nm%o$qb8W)byw9SneaE`IbpI4l)1&m4*nqvi%_Z%ptxAnWHxSN3`{+=z#Yj0uYXn5O8qYQpvDP63k(KbZWKD6>b0cwP%~o5C&pvEomXywjT!n5#(ma~6x4w+>~iZ#f7Y znm;#Y_ar-i6fU1!e^#R@cZ!^sUNA3^dA|Om{bkcwJ0S);gANGOX3F_8{KFwLFQK2Nyc;fbR!ehx>Zw*ZZ+)<8Tv?kNh@@*`7GsW1G$`15w2f?=J%Y+ zn65={F@W0ReL?(onZ@(*UJHxWR(nw{Y-CcTmo;yH{qFDdix^q21Swxl9oNaOFDJ~z ziT7`>y@+CfqS%-DwfAhfbs~b@k{9OfQ>-O-icL%3eidAK(;{|t2ei(Bx z$&9am97ZbJ{x_-ys_B;vcTffZ(-A(f81EBF zo6+6j*{xifsGrEzhWQZ3XCH?*>Lbz{d!-#u29zYa%s$#pZL>I3WHf>?g)PV8E~MdR zq!;c=_ndJd7j?OI|MOZ0 z1hH_9Uv7d~lR~9-hsVn+GHoX0hMuBVy`O9}L_33qj2}Co=LHV+$>h@FGf$gptdjqK zAi%@KCqA2tHS;eUnb1nAa-1Lj?jb>SQex&Qpb+Ix?#XZ$FkrQ}z&+rg8v%XWB6Emr zR}6z=2e*V-ps9XKxO0eXZX8rnup4LElzJK%49F*1DyOta%36^YiF}p{c_po$0Mtt{ z)j?qI;(4}JJf~p&a;`5H!l5uiu@;z%?04@G!yk-c-1&nN>k4tw6-|kp2fSuWu$n^A9A;`|$x_hf%!|SKnsKp; z^Qqn+?}B`s3^TVlj%qcQWrjTA7H~_S*zBn3+fI0cG_iRCyqOC*C3{6NtStzCPb*%b z<70~Be&mAPD z#7uEfaP`Jniiad6%-uR%bFF!QEuwFYBtkNVa*2Z8e(OP5*)0@SVk8KM4mE$>>8aN^ z5*g88T zQM^l82@!_V$49+8WDFUs^@4GySABLcywhian6#i$vCRQozfr?(&Jyc4=Sp|n3aQIO zm`DW+(mbnmh0*Td$_RrGE;w<64HX{~%kU?m8@2_SkK8;=7bjn3&cS(Ioc8aevN@*; z)#|R!#Jo;V^&0sD@I%^vb2{D@Yvvt{<1eANI_xZUSueSNQL$5y=nX6mD>RKag#q;9 z+kKui?W+V_?`81Llb6#!DGWtTyW8$I!K_Tdnuxc0ee2PvujB8qgcAGkMpD}!PWkbh ze_Ke9ceBxp@mzzJZssk|g^_J1FV~isPE7=B&frnH6+V)DTGb$bMLf2-7{XzEfg>Yp zo1dDoxVR2YvE=d~jU4AsRWz4*$^KEIGAj&MY z%|z}R>RqYgQ7BLH`4P5Rbm}i$;->@_FW%_h(@Ln#-%BZ6uB%aIWH8mR9f#+`UNP`u zGMM~`;&Pva^0gxE{4~~oSLzaoR?CWPkqZO7KbOHSOVAg8?&KU6bjEA z9f~cboweDH2gP*aqMWni!+AZ1Ln=surt5rYK5wdRO{p2^1=4>MrdW>3PJ$|kwz~Ca zWsi_3SP^0;U@_zdqJ4VvZ9K zo#=7F+HQ+zD-LA3EVr9`^FLj$I+ijzdY*8n1K+?m669aVY4WSRs+<3{E~P+!q~kn# zo_9)Ca}qDDn|tN0ip_F=qWlV#5}nwGJ#o~3RbNV8oW*Y-`M|UwGNTH z>Cc5NrSH82UlP!e>eKZYHdQpvmOUbo(uGO*xiqM~E9=|nb0jPTDSFV5(c%zKh=zn6 z`f0#&BiXv8F*WS}a|`uchb;|uA+piCjv4B-x^tKXzoFlviZ zBY_%!eqkNSq{Q_7)gbTd)Dz2!pEPOMI0*Gn;gKrtl>RX9;j!&jEgF_Zm+x!%ib)8} zWUU688!Cw`?gDqgoLLWba;KFMF8bu}ip{M}7II zkM{X(`{Fx6EsRim*_jn#sbHy~jWv0+&(TPKaa1NTCm!;N(`}EP42#U^<1HhB_sQOF zECebROL%3SU?9*N*aL6j;8e}hgVOQ!$w)J;dq}tJk^CGB;6g_aMs81raGkwHj8I^^ zV<#P-vJH~33e_Db51U_Ti=UA3xWcvk8Uytn)yz6f2&7mW!LO2)W2yqJ9SosDYc3vt zI-}yfG|TST5+@v)u3@M*O2foHmBx+xo>pn&Cl$jSEMVj#CxgjF=2G?amk)b85LWxW~JHZx9^CTo^Tw=avrG3acp*o9}biJoBG~oOl))1|AL$ zfJJ-J4V&41p{A(SG`HPM>Y=)AyobAl>Xo+I1qi}swtuN7Fo_x(M|3r(#Q|1qKNQre zTT4cTha#&z&Uhky%{TFCUsqF9_+389b6eD{qD2gSsRfqRaUDy>k?R?MNL0OF>ZW9b z;FFcE-Zw0%m|F2zAK&*Hxe0vZq8nKDc1SB>29Yyxku9ixY*oT;SW2MjJ^hkR#jSA) zp|^vM=xs4}{aSm(p_9ujS;#tcg*jTX+s7*qX4kxV(B!ScDe(G>h4zd5^T_}fi=+1` z+SUxfS5{HP!PUyBczX>7*yLrFh)R?$`j(jRd0W8a4`UbB3FGSh2EBIi$=jsjK4oTQv2wQ#>Gy2_4!o63vI$oSdZ_Jd>km4f0AbjAQ% zz4m7kqE6rLmx)h_69rY{ox46$SaG~9b{56l(7tyQAh+GsVmcoBurso1{E~GvG8(3$ z{SA{X^}ze->%t&04nBhwg0`P39O41OaJdnYck9ZkJ?0STK`)rEaQL+CtRfG2`eu}C z7q+8+^kELCvrC9f`GSlm)asrow_{5FM$q<$^kJk zpP8$~msR(7Qu0nzCLJ~QIR#9QDkzu9c`cdW9tBbWjh*;hOkripyG*TtR~-fHc~i=4 zJoE-{-{Bnv<)(X09-a5}VHu%e)eI*@3IP*;j0}!ti#LWzHEVt-Ta5H>X}Oa4_y;1; zKD%Lzjo}iSuJ_x&$n`U)^dBbG+fN|50w}X{*a}WuP9+6dw=96z& z!Z>c`wNFp%JbZzngD9(Y!25YIFqYhcxo=?bdaqT5?^h#F4pW1J1-2v&+o0k$BCs(x z+{L*ZrT04EMSw1W^2*H#bry;7#G%c94TyHJCfJ zF<})Yer>2=l@T9Xg6ANgnZYcaCzla)aD-}lI5eQNGGjR`ATK>x7_I*Ssw)G+v? zRa{tKsPE+ndHZZOYAS7OlECRJ9b{*Z5Xxqsfx{)WkX??F)vNYt=kokt&Lnb z5ve0(c@NY$I)_paec4-`m9T?FEe5 zRq$(Dea+D_`OeIJ zh5aORiZ#$?5ZrtZp?`bvg2D}n5e7knwLK?L=P>#j+F~oxVqCfr@}qWtcsSukF$Gg% zbU+d5WlIb1N!Jt=Idw@SlhzUKkqk5PeRzkDMZ`zN5T>*D1W$WYzw!+XE&JVn-FUpG zWqp}=t8g;?g!iD6U(g!zh{Z7m3@%sWrPfI~G-S>fe^ZlKB#X1*C|f|rOewM1SW{wi zc7C3D^UYlyTU4MH%H=G7-xb8J<%>Yt*yiX;*!QYdu0^jq6w7lhC34E_x1G+y^EXsU zj$IcL7c-jgW3$_}&(qz$9i{w)o5YD3Lfm1mS7wr&gEVgT{mCF%^D=~r@QVlQofM>ZS@1{o!tSkDVE2qnUKBuzp|HYa|)FHQ2BBQ@|_8kxHntg4Ok zvd3M8XgWjscj}&T24=S7FVb580n^={w$Ra}NNA*3e$hz<4U0coApY~jkNVRCC?UlK z5WYN-N4Fgc2R8Bkz;@=x34x?qeD~Ql=4Ou$>czUo@23ZU*=I|U)EH$ueLI$7TX>5n zWs#FJT60EYYkMI0#^$=R-`Z#Ke&9#uy#@qjL&-}nrM+)6_Tn5vPRd!;lRqM>Jd0M-E_FgHC!642d{bA;*1L+WUvKIm5cJKC4R_N2JJLudhe7UkWX4Xl*CxKw?5*!9TN9wwA4s0am##4%5#SxnMl3l zRTK$-FJ9tgb>>@UP|D0x`_EcNWqyy&zv7VhxqPwt9<>_z`n}#W(2K9e*~6>W3%vN#nkWS z8YyE*FPZw#BF1XAzs;S~Tx*Ds_pAgdRxv;f%tp7^EPe7==U)iq#H<)13&^l5trIE; z2n{Re8mID`XF3FYCgz%9N|8Gp-4HKmwW+b{KANlwiKzo2S31ah-)g6HIO`CB`8!^J zcB5GID;N*-*_#cMq8Ag=d6INs2j|wvw4Gg)&IB_pOzQOp7ezRcMU|josuaoqC@x9v zt;^2iGp-f%Q;vwwwQvh{&>u*m9RM+W#WvM39beeD&0Sg2ic z4!d=__diNgKO1V;g_Sz4%W^rR(>OL;5%G$G04Ew~4L*6P4cNryPmYcu_nvjN{us3h zLsiuVH)$rw@@`jDZk!5l9S`9HkAAM;ZvV`WMcN{8?%x=WD(jT{BKCen%XcQE;*)%X z^krG5u>RsBDj~qDM=Ivab_FVbil z-dO1w_OYaE>+6|NUd_ghQ%wK#O$!dGjHH!an|*mMS)V3lzv#|Ml@rcC;!DQ?OTb0c z>QEFXe%=gFZc;6yTZAZ%+kHpjSV_!v6}QYZd9?}^=N(IVG=|H$gz>X~q=HacP(<)c z=#l;s`H}u&uU!NXXR48WV9UP4h4qmB&G;k@biPGy!WUaVD!_^q#@uGVCaAC%KvMCz zMDjYN(@aX5&iov+c%D#5@IsEmg4?D0OXfj(<;xxy4?b6Y+trKXxA#luI~~r3+U`v6 zA2-qg-fW^|`}#_~Bsh(K?RRKhTlv&Hy@x_X;c(|$fFMiQE;jbV7*ejkhIva(e{X;0 zjn?&nfkFGi$>knvfUa0S|7_f8V7SBA+O$Q%U5P>n?=bYeb-M0%T;bhra^Z42Zj3z3 zU3=146#Cv66UlMF_#pE6>b<7DDmvoh1sw6EuFWTm}Lib;YQ zX;^Nk>4nW3kpM#nUE9d3yUQl>_uhH#Ggnp@*OXnHgM9;e1gKTz1E)U&rD&}~O)mrR zt11x^MYdYZM)w+DTHm`x>U-i7TAmW*b-UuW7`6GzqI2T+bd(FjT0zwYL{vT=W%GI& z_(05_?9s4DBdV=Fzk(N>dnP_(RMA_j4v!qQy+(Z;?GG5I7^O>Se_4b)l{d8J#`-@E zwSqa5rlCEv*6jToleEAq5i~b8ATLa1ZfA68G9WiKF*uVE4itYlH8M0HK0XR_baG{3 zZ3=jtjkO0f9NZQ*tVEBV1kpzC%wY6HZ_#^+HW&hzt;DyS!?F(y`R0$-se2e88#+uJw91mq%~9ti9qv#_<<4tc?}I! zF#r%K#18}t60(1>>BG=)=-+NaHbbZz3Wh{T{0BhZ4GKZu`V=7OTbu?G0eIpL2Y`eC zAQ1_Ws00uQ5Cj6n{{=+4NdOce9xz*g20!2l5&=aKvdJS|yxm~-4(Qu${f+He6t z;^Lybf6@W6&QLd)4FmzufS?_q&bK?-K;Qs9qzw#;_Wpmb5}Z;FXtaxjfPkl`CqKj) z#gBBef6T=T@Pwfq0J=~V)Xf8G3-~=SKojB&{cAFQLN|k&xKubxTAMJ(a1watCzkv`q3VE9k@qobK5bImOpUxowC0QK+1I0vz#DoA)R{+$@#zEkBd3|pe z=$|0yxBGSiKVKK53&8Gn2&f;-4to1T=!=4QKmlkscc`E5e+K^BA_Rc|wlEtsz#3`~ zLlFK`{nib&`^&z)d^eaE;3@EydmsSt_vha$^ILk^A`x)!f8c-aS3prwS4&Zo=dX$X z9g}~PLwW&x`2>Xle1c#g00aU70iw4HzyB_y4T1gL2JoL;RfHW9aEt%b?(I4Kt7VVB z8Nm6sI=BG;T}%^sOIs*_^Bca{Ge%m23_C3iUdPnh#h z{Qnb%IK$xHe*yExvfClnb2Z;ZL8bN>mQmqEm7Uu5!zfn~*o?2>V+$^MQo< zfx>_JVJIb-7t~f8hPH9|i!*=u4Ss744nsh-kto>j$K^H)2>hSet-x%YZXXcTEiwNJ zK~T49L;tzP-!}ACPygMABEkk~`&)Q|U=aYs%?;vBczgA?78u|Qx>cwx)awtm0Rn&g z2qgM81#mmFAHWXjM)>=h#e@L@`oCR&ED#V35PK>ia3i2?-N z|HHgRd;Vhz0s#VEf6V{t*v8$>?RKO;M7tg5U-qAO0}Azm+7Ql6B5fpt9czM{&Z}f; zJ^9uKrEvCA&W#262JsOOErhqB_s=l=b&dXbJP6*i`P{6^W(Ny?lK z3T{suAkoj~!B_UVaoUZK z48cKkwGELuRXCZR6)EIvschhxf{xS0Iq*Yko=7>%ZB*MM7^AU za!JC5LZqrS{;v~UOCk~8m`9THkx1TQ%@b9PbjMegKRpbQ7;9`j13e@gywaWC%P3XT*c?!%R~L|WaIwM-_KGYbaCIn}qLdAp&y z$Z}@r>Is;M>kxlNO_}uYiA4IokS8nIBK>6n2`VgceSPaY3EQ*$faA=OcW)+2*lvi^ zw8)q%e|Q>t)&QTp`ITXYZ#i3~*tASrziW3G+(oKQPO!<+r-OEFZE$~V1LR@tv&oX! znGj|f5Ypvw@W=GV6arUQT(1ZVss+ET52`zLUfWtQ^5K7{&9z@+a*UR}^DyVx*pNqz zcrujyj_YavLYKGFQ`hzx(ysPoEVyF`;pXXD5k`FaI$bQ6uo$>okHUf%1F@~wI~ z6CJQn3a)=&tBzp-itZ_$Dt&AQiz4#MeXIo zH0+Uwwn)mCu>e7O-!|B)Jgi@xjVcVuer9R_Szv-gXiH-cp>hvXnB+ZVpxba?U{sGDK#mDVLr*$&l(_R#xDOOgFv#V=}TZbxz^TN0*23kNIk`=0X zFA{&(-o|wA!MIYGT?M_uGkEcq`YV%*HaW*L`|`_>suw>?v`>`Ajw z7vp`DbImsVhRN5i#6OVJ^Pz#CMpv-NPket$ImS0Ytl8Y1?asw2_FQDYMwJ{;5yKOM zs?19z#*&&%K)PY_bEFOUPOsPDlS}N8FRH`(*OLATlI-MWm#;YqG;n?9o%A@vF)!Xn zJjojYSr|C3T5mvuLZ^HfSmzds_b>=9zWS>@YT{A7G6@U-bV&!a8Pr$I*TpgDia zj%BOy`Z?b5JP%6gmE?dQuvkqetI~|RWj@!GES;8VK;C~tnC&cJ?&}R1-I5a7&6RTb z2$|+j!L5e|5rJ{yFH~QR%Y6@^2a6oCe7h=JWHDU?vomvqp3YYKk%zR|mp%Rd-Jc|I zxwdgd1)IxnM{g`>a%X3p)|)%GOC5h8)uz`w+(Y+_%POD~uDonKebKvGb9z{p#qZZ9 z;QP=#|J5X%x}u(dYNUvq`2nkrhvMj%;U~JKE|V;o{+)KL?|yVVY~mMV*9PRkLz=Fy zi#HlJ1fN$r8iPN9EUqi>PLYq>meQF}KjR3BzX&Ro`gv?Zp7lVHOenA#OCX9hML{7tL&=d1A@AsqpNA6=-CCC;#RzVxhxvysUPxjmM_w& z?6Vi#<%7D7;*1?sIwQ)|`FDR-*z|4O{OM3VPvuipbqA;$BI^1$CXJ_U2SqA4k}M7% zM`FD`eXYCH>TWpY#d4Vb*xNbs<768967GrDN8GHv$ON2M=?usC-r1o}7xm3I<4#^G zqoP8Vk=xTRC*D~Ab4*{n(i>u1NSZBul1vWM^QAp3-z+(zOc`tv(8F&GmboeY1 z{W9;JLqm4`lwAFl4Bma3uY$kRuhj5j-}t5pqM{6bWX=J8GGA3 zfVc-x>N$JNC(TvQ+*5yq+aPY3(2Yws#$6cg=}0_I*>8W|KbuIC6opJzUu$DC@y9aN z=)Z0QNDvof*1dW^aJRARdn*PYWN82FQ%=;q%#9`{ZKmcScr*y;tJH?x;xOLI&wSnZ zT@9;4Q3HEQY;<`IeKOe}&iNA~OGk*&$+Vb=ASHY;Z7WB(CTo8fW-0z)h=JWZFC5he zmmTj*7UB+H!IJTE;+4UA=GD47FOVHPGcwkfG{vPgDJ2`yPD5^dY&c;Ubw?s36mIU= zE)3UoqPQgW3UqyynQyjvO$O(g3euu&x|CK*Floht7=77QaSqDZ%BeAfXHF7`KDK$w zeWd_ZEMRy>VE2EsDjQSTgG7YV3@12jn54}>Y@7L0N5(LNGw9?wWCM8ZFb9p5ZLpK? znc%@n-^+akUi#7B4aUnxZhqEmPV%JqViD<--XuZ!RhjroN>7hP#WTl4q?@q68?WYL z9RL)DA4n9n*A%TxbO2po`SN0$7of`6ZaMJ!*SK}1NE?3+btl8M(G(VOX0vsO+UNV} zt4^ht$3e#|VIl7*2(K{F7s~^C>q}O()7NJVmz1cO`XW32m!<7^h#w9%W&JnBxrif0 zaI~p#EDI~%Pd_1!*20GJ4voR4LjTaiJS_Y1Q=5zwosHtU&8Pg!uO#@HY082dYYV&x z=^~s=n~#61m!{d+FeojRT%HtZKPtig&;u_e4Vw>K+UA(;qOpBV&hzzYZAj5|Nsxr( z5k_afwAM!-@cO+oGOb}QlnQm%U7cZ<2Wz;$EY3O_5QFNqOc(_@w$yDtbW#aIjO{Vg zHljiM&EMHb2<7#jzC4&IMbId06C6ff35rg$3zmN|`{;{5bF5bHumA4y!2D8owt9#< zM_GNbnmI@^4&{yALG+{*x(EqeDN~T2?~c zy!fY^#S3{B^aD$8ihmT&`pR};2-BSTL~~`?Bti4~rXboPIB z^EhWIF^W$pOyu;x-LF_BAdZIPHKKImf>TEFkFkRX$pRN>qAV)n{XjN^d8O;E&d@6rP zJP;r+nduud%|%Vf6WZQCVfk?3HJ0^oQDgX9b3A{LWJ5fUKY`O-GVe;CHLZ?8(!n{8 zYT!4J-G%7{pVF|U_L5q`%U*RgfXoY4gLYiy4^NmDGBvPU&!X4w=93grEft-(b9@|h zF1f;7v&S;2qvPLn@6FSA=s|B9Rrr6Sz;1wD^J=~?Sh@Dx8v{#bb6#5E>cG%HFN1~+ zS?QX;nRWs>rjvBJHZ0@O+#Sj4!Zcn^rT0P%c{!TMRwpP8`RX{vH@S@EFX52z zCiMdJg|b0dtv`=l;k$dl+&KLTULqEaUWCaK*%GOP?^I^U5L?Tk*K6}2kJo?PQVCE4 zc~_avDE7^7^88mE2&4R#)A3{i8SEW@vA~3fr(S4}SD7XJ5tMcYwXDQM7G52`&YKvu zR-rKwmy9eMfu?h7yk8Ekb*_Ht)?}9t&DP)PB7PYVPFexTU<+gj*6V+<*#Ry$D(B{| z^Usd0OU^wy+fCT25<5kCZ@1KQ9GRMv$$HiHd74gcInpY>%hXcs3Kfkg64ml}1FDP%*bnps)Nsy@fBR^m%k*~a=tNoQ?Uw!Do97`YS!QZyGFu+8awh_-M^ z8|vzCe}OVjsMQlr6R3ZsrJ9L#Z;{8_tUVIuiNuY%r)L`Ay6<8&QbCiq9~c2ws8~uE zeFGHc)AgKZ1tv;dQ%rBQ-yi+OGUT)07Qsucto}tEAKw%2=V(r4=!^AlH)Q?c+(WX;#lr0%w^zT;NJ73ZtSq;wxsY)G@ zaT}ID;_Mg8J!j!L=UMX>-IPX153?!A2A~R*%NJ85g);9i{{mxMa69&-t88BwM1b%x z5Dc9HDP&ciShZGq^=WbTB{H;-G7i)zor*`37lGpX=cZW;uEdWnFYb)Sjvb}%7jv;* zCf9b-Q*D}hi4|NOA24^0NpWABo$_S;Ii5sCaV^b?9 z_0`YFpYO9t?5sW*O{1R98y+{t7C#~9GmrIUx4c*fJ+v0}^I;DyWf3;Fdw8$+A(*oY zF7@^##B$-KA}Ku}T)8wEcEQ&^y} zjqjxZt+k3|R2;+zD-=I@p&3iQ-Pyk9%15OzeYh3mASJ3dWoDgAuRB0{ch zAdAUtJhPSde&8y6UO>*`qKy+fHY!nu1i{J@F-l6cr_#2#u#ukt#Q#>;XxBFB#yh!c zi@~rQeK;`BTphf<=lbcKCk6FWnh23!O!3J-s^@<~A&xvnJ*x7Mz$Z?A22h?Jd9@N3 z6Xjhjuh{?V;K|qA>0z(Z(aO{(sIxStqQi}!oWt~q<0+3`6mtz5oT0xv-4&Uy{gqCpbeY-u-9df-9FW8K~8(n4%si9bscu9 z`z++YQeDEeqUw*ZJxpY>RcLO;tzSRCng~~ZdbY1)6r^d@sGc?^0 z&&M0ea^&plofQ3a9V1V?>*%p|-WJ3a^PrYOc(>|+WQ=4uvWbQW`fP#@*4aV}w{m|c z4-$x6PryMox<9s@uGPolve3gB;bRCvc=}!Q5`~*;zE`|IERT6yc}8SH6s?N`edp6Y ze!4HzbdIX0cL^B2>}0*Wdo399MOQ_diXV{U5>lAO(#E4n)=rgtxd45veVFG)J$Izq z!{$xBeIauP<1K=(w5p(@V?|H6dZvH9e%!ZVa5B2UWdA8O)n~0;hu{Lmw_jmVS(|3$ zG~5(&UN5oaCx_p#ydB{5A7y#e)%I}cHStOO=PqNjqMk|bC7r=~@aB&a%WD^QU2ywL zy(g0vfYia&@dmf!MB|oq_bHl)+?Yk;^tf*sxm=kPT?wEvUb!OCT~g)XYOQ|>g>F(s zz}lcw^I*SO?SNKDPtlJ10p3+g8QIoy)HsVM>;hz=$*DAwL*a2ky&Nr<=ZX5 z!gTg(RzX#8rF<>*WKH>Spz$)&`z1>e(9FMKs z+69am=u^qw8FKDmqmU)oA#CxmCNjW-pmwNkr;od1knR9eCg`f zi1zNM_5l+1MA4TQ0{1J@X=+kWe-J9hdvTkjQQ)2J6|+vSwRbKQwk}7HugqSq8GqZUarWXu&z8jIkR(NTYW)|YML!k-pJYi}=|>xz zZpLz?X}Mk6?x{qA9ZL^wFBv=EX0NSObmZmgzr$}g!&$betT}%w9%L%YPi7@|qioRT ztMK8<^B)X*^cwFMA$HQz$6Zc{nE+TqpLEx1MQ|n86lK@kc6Ay7PG|YFz8;WV7Pe?I2aW3;0`Q!bu(aM6~j()C7 zyVS!xqPj~F-m`+gdUqmK#=jpCqU&VCU%H2gnJQYB)9$sh^W=^2w22MQ85VpmGjJLX zsQS@&+_g6pnJU;Lp+nR(6|gj(YUFFL&Pah7)wRB;PB4F*S?cF5KbLe4_G4B%-08F? z7nK}qQwuD#@ZQ)9vsW$^ zA*1*q*`yF7PA{;x$7dtb{AUeL(bxTB^PN!tVbM0a%V}yrn0NYE$y0$LhJ>W}MdBEo z%Smem-2stGt`begfZDS(&t>zI`(srQ+z zbG`hILwsJDRe^(AS4^o+l#tw-b+KYo{BFRT_~u-z zopbCyfu2Z^UzrjPi-a?0hyJko7x{F$k!lZ`-U|G)IzgK7(U7{`=)hl2Y1Bn;y4bNz zQ)qt>mEG@sq#sRjz^$agAD5QjuHf2t9!5KOxfns)tOxt=FZL7+3b;ff@ija)det zwzREHXB~>eyq=0qV9jVI(FVW8twqZA(_g+7GlezUMUAu7CU$5UTv4s5js?lD_A@M4 zr<=N*Njbkxr1hTX{N}VTwfqaB_5o8=YL9f$(WP6&rYwbz>)WHtizy+@4=+=)#4&$H zL<`mV&|q8z2NLYNJ$OZY&{um_SF8Cv!p4$~5h{a@h;#C&@`UJ1<9o-3QTIr?u9&Mw zz-6iu@j(mPHD;9KQF3G-=dn!|mUEsh!S`V&pOYHP33ADTk|VoWlT$9}H^dzFSGt*J zXYm7Ef}<=bY(H>6Q_IEf^oQb+xD$W>%4D88?S`}J%}egBlZt)_t%mcx_t?h?Y+~M* zA^E5Y*KcABuO%k=!FAV$k5J=Tyj0{NPD0!2$28A~6c7vDM(@4aJa|T=cXsg`J#v}* zVKLxgVquRv_XJblr16BUJc3T7AE316-|^+78t_)6thzIwrMNms-;YJOJHLPNo^$5K zY%66a7543y!tZ2$HyS*`B>?u=w9GRq?pi|Xl}2-1D>3&1T{E?7^B$%E)>|2=fukY~ zEH?S=ZD9&Ejb|FX>IvvF<#V$8KMoIuWl(BtOo4h~1RMKOVxMoaxC%l7KM-nE6l`mA zV~E5Z%CS)pFSKIxraNTe$IyS=b@noRduZMHY1-nXx3>6uCQc14 zqH~qX3=gL8brHG)HKFQ+>Z|)BKdV3eCN4-~``J&$CsAM!WU>k5`t{tVU3=ucgnBji zQAR4&b61@^Uylb!fHkho$8+jD8LO35u>mosVtiRkcR8or0#Vq&AB%TYD5aXrT*>%Z<{b!Z zMZ9dwlrZl~8MVvBic%J56~ZN98}c>SrH$0p)g7dxnyXH?^D%!{2z8BD;vp6hEJF6TLw?fFo0#(kI(HKJnWu8szav_rHisyX{$k&nnajVr@1#UVNf>ar zPOI5LPnf|QB$t1mrGv?klmJ#ynhfk-_Jl@P{5p`^;UU*NLHQopbAuar$;R34ySwH2r74E6 zcd8P~b(qio4+Kqy^OKqEJQ6ZAIXECMOl59obZ9alGBGeQlMoISe=;&OH8LPRJ_>Vm za%Ev{3V581w*^pKS+p*U2M_MjI0SchcZU#M8mDo03l<|5(bU)$pl)w!1$6QJPY7B8OBWXhe?DercXxLtV>@RidnXGa zItGBdm5U`n4d@JXas!$Hel-kGGPVN%NkF#0{@oc9A{9Wx(#rX7xw^f%i@UKC5C9g~ zTA2bt&R`E$kQvYk08S22msJ2LI{-m{8!P;6zySDXHUL&8)_=qO##Xk*CSZfVDmMm5iK+sO z!43Y?p0lZwm4k~jle3lWuNIkqg#k}l5@aTBZ)XPtxi};Ks!zho31|u)yC?JCCu;+; zcL#a@1I(>JX6C<|FmrWa)&yBOx&mb-{xJcI5P!=ofGz+|7Jn8NZeDf(&=COiFtud< z6<)*B0r;1a^_Ljjfv>lNy#v4;+yv0q${Yy(LiBbvb^`)joLqsv-hV3oix62^0cKXF zE&vmtg%t?#cXY5AX#O__AHI{72SAqv%so~B%dgMBPx@ebnc0JEJ%5}3b-v6}T8grw z%JhGC{I5<-%zxek;LXUv0$^n0WC5`LA{jUM!S}ymRE(|uDdP`cS&+FsfcNie!DITL zirxMp0PR1^K?nG6EG2s|Yk>gT-z3*#;bbud|6%=qruttl|9=es73Kd%^8a0sl&h`n zUuxRF^#32Vv7MEz=RXEu(z?2U7eLV-yau5EZK@6Ydw*#afo4{&cK=%|>tYOE1W}NM z?Z0ERa+b340Gg>-xtLo1&6dCAn!mQp)(Qkvv3Iumb*%sx!AJAIbl}x8wELC=f5c>L8kU*zgCQmlM7(%W`*AfT#n*z1TIJEHv(r@{ul9pv#b0@;Owfu5jeZr zZv@V+{<{Y-u(GiG-4qYF9F5-yT!8k!h!>20TYvI`%Q5+lz$s0fj7@ET;J1jm%WpaR zzw*B~;a>%~e$#&uCpeg?y)Bpp|0Chx_$9IXqqJZ2U^e>$f>Q#2M*z11{7(i}HgIk* zVT_$EfA{;#$I%tMX1~LL$7B8*f(^|7fWMShzmu^4f^NUFvi=hM4#xS*+}_pckLX|n zix58`xU1jQaDd5Y>FHnz1pSx6GXWoe<^;Qfz&rJa9^9+_?_$8t_Wx0Xn{oK91_yHh zzbZlhIbIIdf299CTn=#64&ckp{`YZlfCu4V>+1YRe6YmvU&szl@91g|zIpz8h^*j= z{V`8g@OXa5;QWPvZhy>=6Kw7beslbr7TmS7?Vl82Wd#@aI|2AgW_Gc30{+2&ByguL z?)HB;fMdA+0l`Ce`vZatcmIPhU~i8b4~9PmyKPC-0+{`d49ptqH1a4?d5EacWb$ZHSALIQ zPmVrXfi}=BkYDAfvK?J{P*rjOS4Q8@@2c)qamgb+mQFK9YktrRESjat zG0B+2BZqTgB!+*3aqjVY_UH8sM%Kg&sazaAqVI7udx7`6O}3c3Ij^;Uat$`;PJBxI zcX-6mKQTt9sJ+DwlH_m~yo(D~`xiZ01PVyAP#8Y1GNLgZu%%U5sYQXBdTQK8m%gy> zWG4bbXbAf;cM@t!ny?I=$d$3H+6<#GU252EfW!x1%*EE)ueG|&tv?ej^G?^j0A^8i zERO=3ySyLj9oL42`x$S4-hXbr9cmih?()?x67CZwvT$d8BWbA{xw^uaM*JDJ)MX5+ zQyVCYg~qV#mdNu6YaA-z9dsdfPr&*upM~We4{Q(QDA6frw$DY3Z$-no(wEIy^aWdY z4E^AjU@oN>ldqr8&-3vu*(HtA-_z!#Np?l#tjE%*^49_zW`j$Ana?*XaF`@YJV_Pe zzi}>J3{Vzu$V&I@E>sRh>IHdP-|^-#ooZERwteKxQzhFuj$#};Xb2n>3l8n&y*4}e zc3oB`W`KQYuXT4`;T|qF6tktl9g-9AMJ*t!(^)x1S~Lo(@Me3i2f>8mL_^Gt%&sZ+ zwYG-f{q|UA;iEf$L#eC;6-~jCVxRn>K$y>x{-Q)d4}Nuk2u{S$rU16u4&_@~2;_9M zwHT`Oy%lH*!;YaQt&3*@F+z2X+gu8-O^BX_>9K9Hk*RG;Z`%sJB97i>06*u46lmKx zYO;mxfYi$kLD~zeMO^~*#xX|w&njpM;l7%_@}R~_suSVH5+GJyONn)G#r z0(z{M`GidCZ(bQ9_oT7Sf|bsCwd+_v1wzXN^*VJRDK{j9!!^GnOzu5$C1y=~Nav`6 z2FeIiBk^~vs;K5aWs)sSAu6yz;MVA7rlMbM7x>eWeJ~Gw8w789fF1=8u`Mu1gEd$i zn{=UuslqOQnL`%B$XA0-gTDDZDT*rhx{3*Qskc^KZX80+r4)j?$D14OBUcR~MWEJX z&t&J(+`P;jVZvn;bICBO)PjXOxfJK8SoaI{a7v%5mq2?}f${zE&qzp9Mt+R~86>PM zB|h*eF9L0cc4zfXcZ=!kLzd_3*&!PhhXL>n4b|0uX~IMJM#7ieNk=$HhNIcAx`|&d zc|24EI9TV1F9lsDZe<{rU!(AIrL;8rI?21T9#p&CDcNDOTyIj_-V~zrb)%F`z3_e=FWwOD z&6EFxV@iiNGI6t|cW#m8Qb8?TvK=$gd-VW<(>QYPNZ4zq%r;Zf6K_t-A756!o}UmY z&}Q=>J>YR9Q!tyZ+$OX?^4nq6V*W5FCMZ&Kb$>#}65pkhWAAlGd2%;-GY~-4Tk&;& zY6#nXYkiAN-@deG15j!BBrIz=^4j$vN6hY23J#aAffW^gG06|%PjHYXeusASsa^KbQt7^a-g`$G1Av;$3a#K~ zI%kIsYt>NLNj*rec>LY2SENaM?tKM+UVeq$stFa#QZnqDd!y8&SG_q28wt$jKYKE4 zJE&A7*>dm9=vdW1(api z7(%PZCFDijTsm!EFI*>{M*VTO2z=VgLmCx6R? z`{o2!oQsbkAB^a2y$RrNfT}n19}Pv!akY1>@t{f1ke-GzFZrEv)D<;mS(>dsu2KzYD3K6Waz6@t~$v@3#1 zCPBA2BF{jtm#9p^ToyYdq9@Z2-E5DRZ)+~BqOKLC8ORQz6HK~)9C_-CY$ooX=uH7G zCHbdHKmt5VB8k!3HKacB6fzROoicuUZU?=5cMp6Foo~{J25X#>m1C<13D_7!S%#}E zNzx5BTjz%Xv?QX)woRB*r>sV+Jg!WauJotdOXT;LLj30p{$4}%Q&fodZB-lD9?*j< z$<9IO^Mm*p+N@H49uudt2cI_p7SDEZ(G4D2oSIp!j#v4J24QkdAuMlUw?{z6P6QQ^%=7E^BQ3{)llCOr$p5f2y{63pt8z^;8 z3x~A$LFqEG5R!j$tHA8Jy!+tRH!8dfyvOgNoq59`X^gfj zNKlTQmbLHrls*+44?55M9Qf2kDgtL7jGS&jti2XW&Bo!5QDW%JD+ zf2_=F@{+fIORij)g*iN?-Sb8YLw}9A(8#m&gK7;z_|PXk)x>T>sW+voRvI`L(FX=f zfNL|uJVm46{P*fq8g)vo^4zgi@bqda^T)bQ1!<3iIzRg`PjnoCzU?)OM92kEH;X!9 zD)(22<5G~ClDWs1&mYcb2rZ|OgM$Q5n?og?Mz`~wRJC-BjJiQ znbIGB)5%Ws<yA-f^DuNbqFh;-pdDxTf$- z+WzkvkIzWFsvuV@{0uEncFq&W6Vj}yr_@&kJ9NaSv z^(Hman~x88c^10`lWrN-ig{HIhh@FLViR_Mn{9`OgZh5i{&OL$=Pjgh9vKh*T)rJ* z(n=Vfh5HiOD@6EP?p-Ma9T87;eZPy)EU1)B8NzCXJ_@m~txJ@|HRXv2n|_i9KC5I5R_^MmAc|UX^%Yt1_Uv2*rj+-o~y~(yF*-M4?XywqI3$9pc^- zl;!%*&~?6V%(!bP_`w{_|4JR72HBwHC*O_>j9iVi$agG{vbtbNS{CVH{_$4q6;(&5 zn391{HX1Z7=b32ynF1dj2|TF|3>}7I)Ns7zEA&IuM7c&i%@FcCkA=O=GI|n6Bd2UGUCt#!x zUC+wmx^bjTQpM)GmYFIJ*Jw@OuYJAyJy*qWSek$-vXLa6#N+P}cVx4WvhcGyyTvnE z`0`W-rUjB!&Br7UX@X))qq6#h0qSt9Hvo#unO1a5)KOj4_X?J!I*hx2L4N8^&z{Dd z07VrY>5{ogeiB}oXd-=>k||sr2%M-;5zc`4wT&rS0>s<&I3c8rp5Ue-2^s6KT(oUx zY$xm>kJTi^J*IA<<;nS~s+g(u|r0nuK$= zWlbSO)McoX1YTg<<4<9KfNmfN9?ZZDsURY~ZLOM8_P$Hw3Q;mo&-QJ;iy3;XOjEKv zk8{|hAd?Bj=lO^&W^-Tmjij`rk-~v(a_N#J^oo5Nb4BN=SF@yVwKbo7AFmslnss^` zq79G&W*4Ze#|Fq`zMMrV%e=r3jm3}}-Ze(?AB5G8|L~9dCfDqLmV;UwsJ}{qNV)W? z^z{mjxTSC)XNo|GI^Gj;+sR0E*M&$z1zrY1s&RRJ03%k4sK06C`$JoMZOD2>+8?oS zP7qB+6e~sxlOP>$>lGt*A6qCl;!2}d8d=-yC;!bFvfcW}oS!o)-NVP;pK{?OtCG(I z#~q9h43GjBEsvCcZJ>=ZnoiTU9d7TDD|lQzS1Fx-B&}U0x+0qUnmYE-b9Q<9kv*;H z&t=>b-gX|NYBE$nesRgB+q2@6`H}raIkb0$w$c!&9C%19rS;|6aS{$ksND5nvzJkt zFMR8w*DE+PG)?B69#yR7iQ8f)1PRKd*R}!P=7?CdCslxdlE$~@Ms`8G%C|?G!tHig za`Cq~j5F*ZH^f%k3o;_B9|O%Nf}d=f)tHXbem=R;1Ps_QVbF}JZ+A-?M-udC>@J8Up$tde%+G?Y$zb=$DSTKMqVh55rQ((`8Y=(lskO^%2f)(TL# z;e&*buLB%^{hoQL1+OI~@qKY0q`t_R;+@f=!E}qX{53yk8C<^mz)>5_j;xd8nP@S) zxoFUa4!V_Vc|iBtPS1~ysk7s03>_!5Lt=@a*L<2012Wl=*UNmr5_ov z=)ScYm*x+(T7H}0)txPJeSufs$K#cc#}7g8)sQcLF@8(A<8CpO(5M`&`whw?iqLT& zIL{MCmNx07-5QNkp{P{0)3m|Y$C9LzGR{ll8>Z$&_eb|OooM=wr}B4v<7fN56Zw7V ztY3dL*!nL4I|&CMja+XQnm-mbnN|nKM179*m67b1(`AQ6hD# z#v{>xjHbVgN@nJDyAyQ59vhPoBIkJRS^ZEj4#CCnwH~hC9};=Ui`@0?^Y?hYcc$G4 z`zmD@6y_Y0%mR9Y>Wx}uEBvm+>oO{F7$Zukd7tNm)PYf9ih3~b0s2hdNC;q5Urg0) zl$3kA_I1d)RJhe`q^;jT?=j*{JofyP>hM;7v66{-DE&(Nm-UcLdvb*6r6Ns)cCV>R zi|-a=#yc?|UF)T?r&0uZFyG#Lt~HmIPeR?lX@?rLxPIXfe#@rc{gIKzg>NN~i;~a=nZ9q4bx!t>zmZ!}=SJ;Z z)*-2aCpv&VvtB_Vrk-9BJ&;4DFWU?M+R_G(v5X=3Gf63Dmy*k^R-HgY2R(vf1+P-! z^9#p#(doW$8pH(6_3=&5oxc>WnU=JF!aM{0K8`bXx%6}XrU7$viDP{a%+NKY<%ho4 z<#%`QNXorJBuZRFklAm57^!Jl2a1a#Le_Kw+LlH;itXV-FAKRtFMeCV%@ZvNxjCQD zt*vig`%V>!J4FuS_G=7^4jv$x<2^wo=f!_g@#Tk&B%f)Qzn-BOkJHF*LY2CIx!2n# zc)Br|O@JmQfJWj^LFn}Pt_G0M>kUGYah>IQQSE!0Os2_DWgj%*_n>HwA!WZLRUhRm zwKhRNS)ponk&Ao9EHs>>{BoL3?4-3G*p2U@U)=)NE=2e3EUT+QKfpHQ4w}>c3!3hJ z&ZHDS8iNvbF%70wNu*wll4_TK><^jQv8zeaPGJqc6Ol!!Gu(Zp7o=C}Z@bo5Y6QyZ z+AKG<=ivf7ILuq5B$_N^SC|&-G@$4V)M2L>NkT#HzE2ED;qR21C9x;PA+M@#kaUou z)nI`QUfr|T=j`p%dWemSE+@~=I$NAZvA9xxhG`yM(ZSG~nLbf8Z{r((2Esz5MP6&p zqjAY1>5-;{?5|!6J@O4{89qP_3C$JqzL90|#hGc)Bllj!hCgH1T=wd}7;@c_N;iid zUCIyrsj^W#Oegs++y*pjyxdmqA2)5%a-=>*0ML|o|Dt5T#E5`w(g7kK0 zdlbeNk$6OTXld@)ZSo3#AJxe)sJ+trUBJ5^Ud}$DLB4st3Ul@9n2`m10p_K1cI`#o zqU>j}^XKYFY`uc`ar3%$W=)F;k8Q58h zcY2P*uI!wue8wM@bL(c1C-s3u_)#A^k*Kx)@nbq-@?)B6NWJcV>biht*IPa!n4skq zVN?2Rs?8dN6Q#CQF?CMf_qV}ab&%1endCk5z3Fup2O5X%YdZ!eCE9)Pa4WR6ZzusD z+~LY^59qKXKO}628el1rIaT!Ncohf~yr;%>`phqCCM!;8#2g;zi^ymVfaLPh8?pWI zdh{tWU7myB%~+s+JR|i$x@9I5n-Q@JBKu87j6~F ziO!Dp5M!;>5Qd~;+=71UpjgDWEJ_Rr{R=iK0o9hhZ+?5wmIhlS+lQma)&6+{6w3qN zW`z#!Qz664HQl1f z8)f_aCv9b}QYN$htqKAWvi*h62ciZ9mAL!zNR_MNP5e|YtE2OwZOpKH>h#UpT`0QE zm^lEHBV?O#88Hfz85TrRKj}LpN&c8plED-hrO(q+?bw}HJ7)H`cb0t;i=L3;O)~7N zpl`c~qX9dA45O%)x;Wz0CNkU(YP}z$FnzX>5yFH|H}N*{Xg};nDs|3@19^ z_Ms^m>Rm%}ATl?%yJR1l3}wi z3fO!@SgIG~9diSeBLNiL@6JM4RX+=rbR0bR2TQYTWlHrEApX3buRX@SE-=B3 z01crbiiS5Wd{d&wyGMEFUE0jZ_IYT06>w)xZDZ^LiMnlNhfYVzBn-!yRl9+>?8iuI z`&n&&pA+;wwt16lXU}n$Dtrsq03vCAK1f#uUWW{M5amwD+r@jn0GT3QygQrA&N4OJ zklxo{$zAM8;Fi^8V?PPh7$7PY4Q z;mdGte{KhKj>yoyrlyWGjXDR;0waYUh>Ri%?~3 zz`L!)Tci`LJRHU1T8}{YNffG=AVef&*}~*|_;B^uHOD~_^Kq#uV{D4V0471L&w??3 z;ugGRI~+Jx3CUP$*TodW&_*P|Ws&xC9E^2myGvnO5+?m`YqJ4(C(y-Xynx=Mu;U9K zNjx2AE@(4hO)vf*$?+`lxI4u?Rnq%TIZxhe+Fmpg?Clc*1bCx;F-3T}rWcfNui=e2 zX{N%N1i9%r(v$L^Q=|mLQ`m=vm*3@o4m%D`go{-K2AZM33&4j2orgJaf7pdl4XWg3 zx{?q78Q-G0pI|MC^NGku1N#FLQ&N!3T+^PKNC8YsHwE|HgvuE6P82CKCR>!b{=PC$ ziqH_N$_=$si~>6(Kr6hPZF+PvGlo+u4#wf5#yBKnDGq*3bK-pj9BJSPjnZj)cxt=ey)f-R z_}-zmTK0NLLhxQcBZf{{+4zMz4V9tt!Exw}aQjQwz%)7HW%IER3to zd93xkb4E285ldIxg+>MNAA_!AcoQm+5|+-QqMn2|{HIw+2%^$3Cj-5s;x%;xN=`&m zzt>PwOve?NPld75yu;@S$1I#e-rjC5K(yd4_I*IihoQp=0ct4B){eC+@y5O;BHx91Eqh)psQ zRZ59J+jzg^Ma}%W6F3KI2?qFs|N9$5XXG0*SUzD%)Xjun?0{*^6W)n%RKL~cX|7+! zFp+or`F@Vxyii%q;g!^XxSESw<#NNb-3cyJ+i-sn9s;vOz`%IfP#oWqylHc%m`0^r zvVB!RC}IjVZ9fx4CySiYrauq4$G9{f|-@QvuwJZcQ3Ji%6roAG{5D&G~R z$4y&U(1cV{&sT_!$tNCf1T@zAz5yhQwzn2nqKp>q2?~vHhB$I+VhHCbeJAWx77x^) zRsnkt*Iq$kLiHto9(4(;>Q*tx)0W&<#C?@YevaSGqdzt3rzDZ|FTIhcrafeni(5b#SKpTyBDX1@1@ktJUSwwa2t(PfAh15&A(LdUi(8lcncYh? zLC*Ta{=vBIA?ZQ%mgT3pi4nh;0x_XCIwk4DiQiiaAa}xlRbzQSR(2{j8^ZKf&hK`^jg@7a_^~yy$d4X-gA&7uLB-QbCs$kJEU~eKn z?c;1ZV=BVr5?$(e(QGLsLYY;Nt@5;IyIQl8-1k}%$kSL_^pei9#FgAN2hZCdT(OIb zH0etpBvvecIST@bk8>&NAH0LApHr2!(b~5IOg*FM0#+v<^xM&)F@$X@Z``C0klHHk z^rnyC%&u-hJ4s#%ZE(^jZg)5 zCJ3WT<4O+g2UGpLWENO~PL+#q=i3(ien$o7B2-y_Z~F*at`BqYxR&}YVn;sE0Zx|4 z`uiQd_vM({{^R?>hbnB){Q;GhEY#U#Oi>?@o@|r&lIbUb1qcd2?apw0BPoEZs4AB( zHgzh(-4X;cCGVZ5NPK+XBhRVj6YWjY>-nY^XRiowa5a2CPZi6foZT$j#C=N zSLjy@A(?||9n&Q_%dI@Oaz!m=F!TZ3KuUQE4zoVjm z4`0dt-se9*ra)4eDq!@nC?o9|KS@$2Fu3GRc3c+aS>aVuuB7r_hxitn97Z*(cmx(g zpvcPDn9RFLQ>E?ZrVG*@4^&e`O8dU57<|?wr2F~)r2LBhZ6POUNbSV?g!gB%PI_!O z)(yPybo=w&wG3GD8{xc;tnNvwNyi(1UeDZ~sC176y}2qpIsOGPpCt^5#gz$>KqQ;` zQ0deBdYu$5OhTatz2lyx9{Gsd2S3zOcg^adWG;kKvI2puQ^|bnIYMDFN)}7`^!t@T zHEdRT63!>BJu78y$AVE;=1w~P7j>Z~hn5#6T3^I#a7POo`$Z!H!`Hr(Ipk)4bUNPd z@sp3_N5=aJ5I{rfKtAy?Xj7UxrWd3FZH$GL zwp}||C9Csl)k-3+4dk&FZuEaV!fX!W&%JMk(zW;OG~U4ds(AO-9ap4G`UyEKA39cc zKuc8sLYQ5vOd^}4KYAp?x}ZgWH;WhwN-KaB$X7yrV{yM7q@PS;;bUGd&xX+$Ugurq zliwOsBNY{;r|%Qlb?C4VAA;1aVY5&Q-KlQOr4mV{c@o4&HpRi@I=<3>;*~kh752qs z1Me{Y`KC<6Bh~{nDcIPkqhxWz6t45LrS8U0i=qksjq&7Bk~;9odpN_gn~)k?j10;- z;>$~9@D7Zjz~BOm4m5&KA>om!cJT9QSNu3ns+~_8TC@%7rSO&SYpXEK7Q_L^SM*k) zvN9XeTKffs1K3!m-$}@So+qjTzVVIvbYB!mYQ8*Mtl98j#p~A^$gbMdH%kK^5cAF# zV#+KwkxLu{ACR403o|QCKicGC2z&K+KCM<7H=$XpBH4q8F(FU3h&~NqOiN58+uTsR zzqC-(E@v|`^nwMYI}myqE2+=#WU4pw^!qnfMnN4wc_w-Jkc}6AU0uP*-q1I4w;_9# zW>qG@xy6jmZpDu7S%#ZIRR}&hUwc@$y-xM~=rzDkYwBo1I5{{qfGEQiDzoyTE>i)| zJd$1kGhHkRbBR0i>FqU5jalJ-V9*6;$0_L;#jTN(mP2&WFp6?0 zrzjaSCoaD~K*@-IpRCIib1w;m$`moNIQFR(k#IBE$TjbjZqb!T+x?Vvig}#8gC1UhmPqV?aWj4l|TwzjP&V`{gA9TWhSGXe)@DKNvJh(Y+DGG$;ori&OYShjNcUU}{q(hZ=XyCxoG}za@!#o_W6%%t}UiF8y(wsI&)`H^0GU@=0>B_a9jf!EPSMUX8y@)eQY2M##2k?sWz`)+KvnY zFYvBKgmQ$@UV9XAKmdp~*bYyc@S}*5z+X)^_`y-$m@G=s`L@K}!?Q26CVukz>yp5? zND{n=l?QsCS0@|npPD}jjzWah=tYWY+SjJMewrbF&Q~OIbdeeOpq9Guv2?>}+5_Wd zQE&u-700}Co$o&Wn6M&Ii`#K?5x{||YpRe{heKN#Kc70k$}ck!=KbwrQqkTE6TVX- z(C_BX(x07m-E&o4P5D;kQDp+d39koW@~l(p-{JtW*-(<{#`$(8%f_I>40O(AGNzW8 z7mV|NDp_^X5iPMc&}<#8ulO2mKFw+~9pT(O^l?B~qrG>RDsjqiV0_Xy9o8teB!TAK zKe}Y|jAi%9ws{3&Al*`jxh;7?et;MjMAkWF_tQ{omhT`|9*bcQ)e#}K3)PG&Jq>w2 z53PTl@(A%~-vQ-keJeg(b`oewHyhRNR-!t8?xIjSql-G6*@F#5`R{5sHOJdLPc=gVkD=rj$533&9wWA@SB8D3WJLSrl&$2!_86HcjDJO5g z6U^?v5vbjSt%7Pw&ZQ>Q80(4@6}>@&VPoyLqWTfc)L0@CT=qpg-@8xBQMOtcq2`u< zR*6e_?Ay(wzWRrK8nFak)8&;`RE!;>L!G?rYu%$bR{DuNeiuGyY5ruAQK~%x{%6s5 zsbxX5%ROmnUylzy&6=!9FQF52rOY)`GBKI%ddwQTBbC21jKhl@CpnC>*lw+z3UgJg zgvX)a-(~_F%CV150w1zgyf*#ab=(YpZC+?g@qR>ojHsvVeU2sNMPh@ndvkn0i?G_7 zOD01|24Ic7?*0uL$g~+yW&4&GUHJvik*Ag5UBMqM*ZkjvU`O$Bm@BL1U}HaZoF0L$P^WgHOF|BHe5EE`PdXu;LBX_*c}P6_u~y=^+Qs# z$lc*AV@Dcq?+ZRkbqKvq0?dKOFTb{Zk0N=bqn$U|75qt zSzGc2J%cS%qQ+fD>p%pufDqkR>%e_IbK?l4Wm1^}Dc+NMe`V{SS4Y8ry=S7k(kWyu z)zn;d`XmohAJE=iq3grh;I%QU5p;F!YQwdjLXA=>$HW)uvyVt4*{oDrz_d*E1o&T*~S_93M^6T8GI_^tUPvEe%x}v8Xud z$VWwGn07#I%xLElhTN2KSJ#%;=40N zmP~ofSLZI;9D{RpTa@+(6inSKeo_uX@E~`YEg;pq7$wtk+cAT4K0k1BGB*J_@gy%1 z-MLxd!f?0sNGIWc;VUqUAj#GT!%w#51Tks!E6y7>%B|`2mK6oFNK*aZTTAltuus47 z-d)yo4|*{YhE9hV7YAK?2c_ztkM+*a|PZZ z_(4iLix3=uUqNJ(7HqMU18Urzz`8LR0x2{aoY^yfZe&)_)o0nqN?ZOA=d0|H!QhvH+S%(@VBOBM^M-DBrReb zz8^Jz<-*8g{7B~!H~MNY>}_uA+19Lb>V$z*Rk4O-l-#4SuO|PDuy*9A$sO?^eRVWq zuzJ3f6m@#sG2rTcK}gkp_N!r`EC+X!eSAxJ&!sWhI)XOg)ECj-H%70Wv^l=8ykcqo z>CTbZl^jJXOs^3xb%VoYX82(5e$U`j;$#Vbqd7`?8Eh|TeFIWJ#SvmlcZ>YSze=$x z>Xpi<3D3iLoH`V@Hi5Bd*;t-dD_XpS9_%RIIy%N5AkCnFXdGt|NjBAWe8_qi?zu6a96x}{4*^pZYoo2@q2m1kIFFV@#cEyYvuA3IhaxSZBjFsns1&4{)@@Zc0;{Qj6czFT$#Lw3>3W7`LK^ zMEc1Y`YB@7#ys zpKUV|%+*|8Y0OI1>3u|FJ3@!zi7|qaS{2-xwEc#9RJONK^U?ml4qb zveXC!yhP&mejQb$1)*?%uW{ez3>Op0z~~vnU7cI{=iLjxXmxG0_c>?b=m;ka#Uo_+ zT@Xvb1L+Z@r?^dA=LS%wyCj9BCuI>68l!Xh#DoUZeZAJZx;Ue6m{6DUu8K&=yu4lZ zMA%27QtnaoT=0t>uE`E~Dgb=%OoYqPrg@XHtcS}_wt+FikkVX#%Ohh_a#s-fk;f$ELlTu7wgkv1dqFUwOz=hIJ_bqA8IYdFt#PqG4}jZ zIDuPtb^?_`!00wKN=}8kPzHX_Jrvhg6wsHwyCrz4-T4T$syZh|o$o|`fRM*FdefHQ zF>!57hO|zZ;9TgAPn?{KLNL@HwRi8a!*TR^TQEu~_*%n%L-N9});-{;+syvzyVx`Ru9?GS@j^2xE+Amcs$J6X#QMmZnFIO7+_37$R znc4k*18=5(>~j&7_w7yFQC5rSk1Cnomn#IZd=}K~)sAAAemmn#=ctm?abj{1l5_Dk zp^cP=#%G)VR2*@cVHfSDc9mvI4q(E zEnK=`nl2zc>2pSHFF$sn&(Vh_ zm0oYfp&_V)=Jxlsi(YR$b;2{ONoNI`K%7O8#a+M`RrreMMj6C!JVYWofv)V7seIb4 z@E?(X1L={on zQ>;eYJgz-bXW##fUm^bq(+Qb7^d|kjPhSsz(feEE&|LYp_@0yc#NqI)FB2wB=NmD_ zQ9&!BzF<1HXMfW0K&XKXwDzrH#NhSC%cjJ~N=2HltdfKHqo;Bnz;vmMVJ@WiSfl|- z2}OeO1Z+eNS^Ew8_QZeI@u?$7iI7RCZs?@BN2YLFL#nG_VijV1gthy$RW2cjrKGh9aeZ3`O zwEW=>h{1N*W0cKfCZ{>I)VWdHtb6O_C<;+;L@HHbEFD!}wkyp9*U!~yvb_(d5!88% zo@ZWJesG_VT=*jHA+BYGvXadFW2ei1xrdrbK^mSz3X>wQ16z58j)fb2IA5E{mg>Ry@?{K`*5BStCDfS&Fdb*I@<|BZ}5AcaC z0o7j3KUZchVsTgRt1txBxi0#guwbM|UYt~$L;MmMJ^jKwlVb~?EIT+3W!IX2Xzfq; zf=+D4Z?X#mN1awRk)D@N5sg)s?JMU1ouXAnG7-QZmK;NPQTLp5EJbxt^GEn!{I;}D z@QzpP6QAGN^!F(XNScg)qFc#+#%OCDx_4$^2P%vu>u zBHtX6H}kjzHSyT#@Fx@1Sy3&2$}Dd{atknEBd*{v23$~9zm+p!T@P!(sMUoEpZGp{ zC5?#G`z}UzVOFPp;x#1mq+rI^jE{Cl9@&De1lN$}A=m+`yC`(?Ee*si<}s;GRo`+R z$Ey4~5XMQ)DKdtV#FdNd>ilX#hRatHmXamEig1cr1#uxzp)h|Pq&nJvA>(X~6T+Rv zu23OTax%kCH%NS4rBh6$L6A^#Gf}pbVj9yiK0@k@PTD+>#m^8Dj8ut{&%&(W;g@*h zE6G4{w_u$bd5E4Ve?Dhhipm~Uet>W)86eLD6i~eiPC__K(j(E1)FE@5jWWB{cEwl9 zCZ5a{uT}Utdi!o|ccmGBp0wQRC??ILxH>ixF6S%yFio|rkV9>S1AFuce57G^qmsY+ zU152+l2v0XV?xMJa|Cs33MMb}y-A0x3XJw-icU5)fEpja94Ip@Z9IIn9{UX0y=(DO z^^SdC6$P@|yc-fP@fLco{Bt_Tti~zphVb$Fx@4SpadQPu$R`hf*T#HScwdNeqs?o@ zPb6tlMioR7HA~+HanqVxW^GRBUXi3W7}n^zF~@-zkdA__NGd#?ChPge>QJ|LOqkR@ zFopPxhE`XZ(4sJR`L}<+=;mx*x30VBaC}tKh5laGX}wC|*l}*&=7`NCFMyGRYK`V8 zCN)6=p`iJ_^QTyUy(s1#<5zZjrLZRSncf=(gw^1kc5D3TP7hVblmV#w6r!NeFI+Qy z3xT=B`Dd=&b|o!_Xl#fX8zPBJN`Wvue(2G6($H7URyh+yBx|y8bY{DEyA`%5i3-ZI zkyTPp3T#bJx>O+^G9i=~MkxF_n+GT`G^TAEz9h@#nSQN*NNzq|GfNh(sp`gf?~!hQo4K$haMy2nMjrUq_mJ03^6rfnBa>c^o2EwTBS3>@7#8d`eXcL z?_RAxl1fH@V}ABa`8KD)$@pH}d@yvUo~W?2%|u8(2+fk18#HK7I{kuYAUtT-r&$7RvE;9_HgG zW{k9~pcXQ@MU6N0CH?+loN>84#ET~j+(gs%dWnd$_Ne2^uA+)1G7c|(5S*~4e5D_N z*K*EFQhhUI6p3`aR66yFZde9=J{2&XqmnDzF)^m*5T7r3Q$dkFS;IAGWoOw{>zHSg z-Y;=~d-#F)w)m2Hx^G*lv)uGa^YpQ*8fh5}ALCly=K4P^sVRCqT=l|R)0|xgS-*^& zQJJPF)Z0~0qDkMLb2Ae#tc64g&aI2dgNVc)3bPMvd^Ki>M#(ky7ZgU(ye4SouJ3B*Eq|xLZ zYYmV_Nvez_^2W!3L`Y)2Oly~!n|~~_rIpA?hNF6&8X-XV6E4qXTmIc5MWX`O%=!F( z*o==`D>?VB4<>&J%)vj}B4e_xooxFX>q?3>M zPQFcilnI78o|hM;8W0Ig-JJ8NCYPK#5H?CTcNn2t;jiH;>ZzD>f1G+6BCYm8qUvHN zgynn-1oWz(W7a-;TQJeuN>m=Q0)wDwewTK8=swDV9TlJzT*0#83>s1Ip-hw=G;rdKdN zKAyJ)sDHi|A)4=uqy@H|L^bK={QOO-Ji96*A4Z>rnqw3( z-jzL?tg|`{HKv-LV`jgZ368+>+rXX44o@J|%4(S*%us7&_2o(5^5WK_{>U$CY=hu0 ziMc72eE@YqM*U6V7QNG1*5LE5H}7~W3ql(raJMPQU$_GwQryO<-oH_-9rD^ul<3=*xc63s=A@njHGC#7j znWeqOm$8SI(vouubGB)pSh)7?sg2ezYWVWB=t#wwGC1^ts`Weyk-~o-l83V9uVdes zYn5@K;=|R*S~?QJh0q&+%4ncbylufcB9Y&r=3*7Q(|~xsf!X@X$qjh!T(}Q~(RV9^ znw~VVICKn~UZl90rl$Uu1J+JyCBs424Ch&SQhWQZi)J7RCYDPLX|c$`FbFTF7Otv0JTd4(ohHUYN~03$y1DJs`G9@X z4j6f2In`lq^x&sn>NQkV1%x&NA2?I1x)=)QM2fL4+Y`dtSKSc!{Fs0oI#GQZEZDfw znHQjjw{j|KH+es{x##_>uw#v!=gX^t{fJEe`xopP9p=LO<>6A~x(-c2{P~2(_T3{$NcGJ9h5Lk299h2xZOY~{}*nH?&FzbXllcbYhv8K z5zV&O`8(g@MuSE5?DU@ih+dVx;7Zq)#tYymahg1TKsiM+0Hb(CW#KoF*up~&7|8u* z-To?$W7a`=&+wHzCPvhUgKOVjuG3rZLexNCF#Hw`OU-2(miJ8)UcnGcXn3#{#a>wI zwBFcRfga>Dc*`NXuqIdcZHB|()&9}D6wf0KF9rj6Nq#1Q!3#`*N+i(z2mS@9xfB3) z_@ySgND#dl^o-|f{P$mq_{IM49b7Fb3Oo^4oKX3yD(Z#rc6u?fR3y&S2IgK9gp7;H z%0xym_SI}PcknZ2iy6sLd^NDC4ZKYGKX?c)tx&{*gmngY(V;t@#L0_h2HdV0+1~Hb zKnY*+72np@;|d+_M(9|3Y$oEi9Bly7_rV7ucQ6iyUcaY|88b=57B{U})`EK-aS56g zd7mGbcTcGH^?7T{?N-brm9fRW(_Bqj>&@W^MoN72RI7pjwrGzftt&k0XiDzKsQ|Q& zVICP_JuecBBgJ!qzh^uecQqi&r3NVVWE@?GH> zkx?GhrXmQdiv7wy!$vNTG8dp$8P?LQ-~xO)UoNRZrhH;vxi2t?q52i^>&a^RO)-%` zwY3$l8NKAEp{P^gOCL^t6gU|Z^{Fbj#Qx8^4lX}(#6(RV z0)1i$cEV@j)zV4w3=K;hd+D8sA$6~tw3NI*hr=`see1>^%_L?}wE*CRSMTc^U*^AK z?*%hy%W_roBfpM zfBh7+VIWHaocP2X+lzD#qhvt#-^Y0l9Exu`o$>dw2R^~qvhvBrYx`l+n?sG}tkPY5 zj2KQ~L^dDkr#0x7O4$JfiUk2S96p;92>erB8oZxe1z8dzPR|X(pHxad^yjd%2}CIY z=+0C>JQ63pRNEk=OldIZF<|r1OaVdBPQ|K8e5jZ#e81?T?EfOMO=4Op=yeEVo0A-s zNlf7>)`v)bz0xp(e*MnFT&9D04Rn2>XzlgbcZTVPb;a6xhJpcg{+*w}d{ay&xj<~# zY)sI{!g>ZiTIicT)De=k_fU;-D2UMXhYZg$T7WY4ht5x>(I~}%rSl=_eaU;0vmOjS zgWIf?U7@xD_-7EqIa$3LV$snA?m`W(O^^eCL+@I90Y4@2zSCp=wEYqAr;cq=mr(*yuqc)d-gPYk~N*JqR(-An#^50n@fxcgKh2R}J9K6DD>g1)ZxPkQUJ z)_jV*I+9)h4YDh+34&qga}##_jlWgpw8+9_3Sam5ma5RsgS2^IjNw!?9A<)rjuEZ4 zSXUNI3#*D6=40oPpP#5&s|B*4AIe8N=1l_dsX%3WEF-{8sAt7<%Pb4nq?1D8^=F3U zB}m%BL4Z#NIHf)gcWHyr18s*`MX6+)dnonRVhrj-(aqYt-m!5$NxkFj+fd%uGEG@;n9T+Vq zio+rh`R_cMI?Wnw4n)#{!?Gk37V(~-R9CKSWDtNgee|S@)KPY8!p`JR)DWD6@5x&^ z2XjXO?3qnP=;T->2}_N4V_ypQ<|n>-<;Su?eH#gH_3%W}vY|CXhy973WLn1_{yiSw z3YOg2qFZDOi_ZkPY1yDrSE^c~eETEM2metWe?C~quuN3g2$xO=o5^Mk=P6rJ?glSB z2M@3cCAMpbWbFL(tAeCh6p2PRJ_D+<-IcDjLExn8Qo8?(BugOKYI$NA)T6C&7IBOz z?A`UbBfWj!8#RLvzn?P?s$=NIeID7fas_yoX9?+Fv8uP7S#k3u$gH>9x0;k0e{HM+ zA?&e5MRoQ3f^pqq!6mwEEdLvkyVw`p8w}9MTl8K4Q&cvwN~U4VNeF*Z?r@p3;QpL0 zug8uusTg?osxT3kw%K$(HpY%M0e%dU;#FOUu@77ec4@{=m7ZR2I(_|9u=9o;-w$JX zK$stu>FL5JOYRcDs8i8+=K@4*VUzMMna)XcQN)hT$31KTJa4`) zn@T<;Cxo*sK#@Kx3mmLvFE;XP=?o)SZNJh?i3x|ZpIM{rG#2(~`WGTS+Z!$pr>%vhyiqcnV9wlaRm2O%)|hS`ghCWlHIh&;qIbN3{BpL z?NvWXAaK9^Zoe)~Ri@E!_Ugb&0TV424fRaUZ5l6%wm{i|W0KB=wn#4@E@?))LDaL0 zAKUt%^DC#{UddTBVkl8$pFZSuWV1N)Pyf)1k{#Du(~{Y&2OPcNllEMVJHYEd2uf+o zK2|7$v*P0{w~yzlQnc-GVIB3DF&gEhOez@gCmRZN(q`eMZlT0@4qchs@s|cy z=8VkeOquG>)?(XeY96vi6@bKBViTsW>79lucgNrZqQ9*~OzRbHZ9WXu!x;4WLc4g; zW+n~_uCPG0oVC#~;|cp}BgnU(VStNlTa(K9aojqwNRk`8QUjMCA=rRXl&@xqr;r`p zaWNlt%0R)U053n)R1^uDcKGSC-u}wA>Ej}<=DwH$<7_lb;Q7(n7@+Epp+O>vd^7(o zKdy>h(osN5_N@0&Tx?&+R^D=Tq zv_^EtySMSj_u5}Ex?3yd_Unn|0qZUSyDx~pBYz70XuBQVC38&3$tQ+Zm{pMpErtoX zq~-X^rY$m#ozw0wg6?ehj~Agy2vLX&l(Ag9<~3$xnqN!F+5m5;5)g-*UL3~QUwdfR zB_#2WDdyQ6(?P&GR=?L;kadTiFS(9r~;iKT|{nJBn3H878 zQ1>a29EhfWA<~b=XTiyL&IdadPcB?#!IJT%D1m6RY5{Wm4Rj{y`+{&ljxXtFAG@tf z>BETVh4@H^jbZz(XlbQwBgyaQ*wTZOFpV~wZR)xI*)%QA0gYO8lj=-#H$Niw zjJ|)T0A6+Am-|*zeV^zm(Y6q}tn+gXbYjI1b;oG&XZ@g9*Ywe*CApyZ$DDDn#ryMV znBmy}0suB!{i(gON~M&C%@RBp7r=_EQ=n;BEXS1MmGpo=tf@{7AJfHdif8V@;v*_X zTUL{FWM%(}4f(1Wn}2h|@9Okg;%!Z)ky49uq7wA&$Zv*kPD3oJZdDMh@Bc7CEn(ku z+y{9*b<88 zhpxPJ<={dc1pWZUepgaqDkq`Mt*)6VRRa8q->l(70G@X8>E2XSXN!*I_j2421Bs^b zZxv1QKmrlg20}H8R*wX${E4O-{7qTcyCMcUB$)k)6-PZ8@2#gRMdg=(IS5I&4#pQj z7^E^M&I<2@HG$sM3FTV+{%OQD7N$6PrW7W6DbRtB2i#!Vy#Ji4`??5F*{?Mnv4ErK zF>OLt3!o6SZ1%uD_NaH!H2JEmwbD|D34|!XloTo>vVN%IEHm6dxjUeSE8Q)7`Wn7F zVrQ%1qQpC`d?fBGvWrVu8PP1iyaR)@X+t53g8P(>j3lE=q}IFxDNqRejC07eMwOS#6(!vmy`8PyvSy1_8 zHnG+)Z1|Vrygw1?8$zw{ksC)Z#SbTPf(^BMp<70#=3QqIzvs%8R6(XY_+k0Mus$CD zAJN7k{u2=tV-ZugdcSh^39lT@$aKis^;l>dTYE3-`+@Cx3j}0MEJK)V1wgh)i-Eq= zG#ne}`N3iY?v+w+Of|+`Vd&VOKmTOdeg0y4x?1_TjYa(PZ-~xe&t;1L&b{#gm#06Bt&pya|dI)n1H2KX6q3xy6fsMXQ=O$Mn8&zSo1Xe$Fxs=jx7 z6fIysj+^~dr;SN5JQA2e50I?SJr2xxT$Rpl zuQoOO#a~Klq44<>ElB&)QQ@2fv&x(FSJ_<}B`@-HuUO?855p}OD~Ab|rZHfPBkVR0 zKVg?FmcHahiFdRxq(fls9~6^e6CzpClMF>n4jck4PFzn6>x{)Qb+!~^j8L% z1nhEPxDga2Z{2Yc8*LKAen2Le^DC+jcrs2B%ziV2I+`NWl=!iP}k| z&37f^lON)oajO1XH1=>X07)?1a0g!5EA9YgMUYLj%qL!-8bKqrvrHnks^;3X4EN~3;rw$^)ENyarP^uWUWjy4+zPU) zj)ckLJ5lD^- zl~2&p?LLWZfnfj4)Uu*V-(B}q53-G&FE3CxB8{_etkJNs1bF5&4?SNBH=-A@_dU** zhxqqNGHL$XkQKuBoFj5u8oW3@#W$gpW78SuVZ2k`dC=f^0p|+}^6#8x*sVMoszGTS zEtyn!1K5n}pF0D|(fUVHp52~hAL`^l+_nw<L7tnk!2U>C81|e%L;Y*B23wu=BXpzPdfwaGa-Gl@Dja{dbI=iz-5B$AE6;# zn!zP4q~xF$X!4*S@~G$b&s7E2yxLq){5UuG3I7_0RX)GhC7!K4$2AGvWu)`8`CMr3 z0W`NKb7e*VACjIqK#g{AUl~$7W-8i21RpGg6IRUXk5I}x=bGI(jT0Bgs%JC07jA^e zb(C_*;$SSs11zoZ!o@QLaSFPl1Ju<`WQxnn%R+@&zx_?e?4V_@tB@kyg65QIAL~ww zpV3BhTd#^`>vSiJ(>U|-eD7zn9=rvGfQA;ucC$T(Jom;YiI+Z#`{3RO<^5@TVB``; z3?ZQjP#{v2k8LIJuT(Jexk4mUO${9g3qsEmRS%+$BLC>Z1<*#{HGc8|7SO5YcNFv= zk!DWCN7)2e1PSGEK@X=GBhYOENh5k6nu&h+86oe{wP(42`Row8xGPtqt_)0NK=O7- zV^=&Mg5iJDf-s8*Oxo5=XX{Se8md>YeYK@pMsYOeFLJRI6PgY@yhG3H{Nmq}$$u>9 zLy@Wk*hd|#>IW^;2Y3vpa1dvb{2oYRPwCQ13B`s< z_Gm*}0Fd!9Vxq%+WK;G(y!6LGBV52TETqftC9#319xSK{^#@$q*i8cl0160|+#;@B z3iXj7Z89v1*IDUXr1FtkaMSAZ&mT?bgsctCi14$8hYk{#J6)$YcOc-4cC{nUQz5wh zv>>sRquO&LA*H3=4RX^0mh&%ay|CG+w-($QH3t3gA>c8Qvd|n1=cVpVUIL{WU%PZP zdAh$ZFW04c+4gNDa{fPY;t!C6|8T;og_(p8Lm2ic7#%m*Uuom(UMdGvC1U8aY=?lU zP#7g*=OqFLsT9H%nBiUCmQRRf&epe*L_XEGnVXCTH#SrIp@8{YZ^D2f2~u|%fT>ZK z**IAKM?uWN&cXeEM0FcF*~~@_iBbTsJp^XAO!KXsx0jfG7y| zCvAWC@HYbTl=oE;AOeCy+XDu9zXznH!{twSALK#2DZ{{#`=!T=NhNdtk3 zAh9CZ17df_@>c}vqa+)lq=Nthc?%Gl?~Q=cVD<+Y`>*RfcLZEUyobceXXY6k)k?dx z101n&dMgQpn}**FOQGi`7E5qm6TL3+;=y^XPq0@$V4nD|3E5 z`CineKnLKp{0aXz(QBeIL_Pz~e~@7QF0Ns3pFgGhxwL!& z0{--9(O_#rSNRTI07=Pyq|V-zvY$?oZlDvPq^~!iK7(2Szg8ZaS(N`^*RTBVwvj$J zsEQUV`HUd>?<5sv*c|}m&FL`;q)j};A4otzfY`sTj;QZ9*U?32PSEo!td?dA0T}6< zR&R;>JG)_&5Wemk8_BIt(Abh#X(9w@?T7w}Qb?Ex>v`lAkn(At`kOle5Pvra`Ps#$ zZXY!4y|w`${}A$yVZ%KB3<^=N;zwkF$b(s7?ET8KhkmhlWB`zK$~qqbI%@GmOKf8U z*MA~UPQ0f;eZDXeTvY-9F!1gMi!z`roIVARFE*jjrb7r#3gR zbvpF;*o99euZK?}mO#Ad<3BS&J5l4ox0AUgnJDu+vuJ3riHk4{tj&%sX()a1?g(MuiR;k9dsA zd%W#4MgitAHC0{X_&8HYT-2(!wa66+l*J^Ee~ia)WeG}16erZI-9(M!QTb9C6=h9| zXxtFYwTA03^uL*PxR!F*==OFjYRL&*6hGHDDPFyT_qt5Bs*d z=r&`^IZd&*SezE7OR|I1efi13cmcWju0AMEYXQV8*F(x7K0Zq{v&@M>QgTZPbhSrK zDev!filhg`LIr!0P!|H`JEPaJdwWx)K>sPTCSH^oSuk_ebjI-?9K63cA!%DaFoFBE zEIyPNH!&Vy^}9$(3ZN!gETngH)@3eL(RlpC4uy;Ufzm4N@jq)ZQXG>_gP)t69bB@! zRR&;iCL-%)8ObrB5YaFZX)(>MNlY$vSkquo;Bv{zNnN;TD!g9!CeLkRCiK%MSds+v znNO;Wx}&+gqK02`+@8PqjyA|OIr5(zk2b5$-m*B?F)SOYi3%tLb6k__-;SlvfZ@Z= z)}Bmm<3MP}r|^3x*kitu{%pQz9scQwumSiMVbjqxds7%LUL5OmC^Y7KY)s{pfBz_~ zG}$sHk5oEO87pW0F|GeQGH0Y|suF0J`89#$nUw#IBvp7=1-{yRTdlXa?(QS-2zx)O zBg~M(8>21BAV`xlK@D_+TF(#~0b`?X4bc$(VRRsg15SnHgW9eLlwk#Tk{kB;U%YmW zec!gfXn9u!?IxXdxJfK=$$+{OFZXq^=3mS5{6hu&r#~Z8WKgo0pT`-L&)b-F0sYg6 z4#vEm`TK~p)5We`iE>kqvVMAVEYfQX@>q^DF%*3Ygn_Ts@6-i zD`&rZ{$hzfz-N<6D;&8%z<9lo-d<3vqgLQK-^0o-`)Cc4x@InadSRl5GCFxTbD@E{ z^ckU!@9Ag}BZ}GC6&>%c3<_XwTGjRtN{GA$1dF5ODiT>cxQ;mzHGw-?Vg%09HzcV?(rLG7#FO9|-CIT&Cjq`4Aq z6QXXf8azGeEtg9oQ7KBMv+$(*hhchGu0K>mk0*3pt%HKRP%%xgA*2M3mh;UwD2L_7 zsfyiuMx!-*N`8J`zKyvXPA!W99)@U+q7%}irG@KcY25kvqropK>uLApR`pQ2Q;FNG zK3HpJFs|u;F0OpBw*(ka)DkTd*!>gN<#$y?FYW1|L(OUrCB^Uwbf`TqOf^!a?B^x| zNF5fYivC0!{Ne|F`59Jw96Fe}LKX9_I|flZktjTHaq!{pJx@Ditse@EB0oXznD>@I%X~+5gRhCcJB)B7vMnBdPhDb>0B3w z82s{v+zDVSnLA4esFsM((yzF6B0=M_ITT37QsycPoY_<(cbm%rT)egu#)>09&N8;*jwfJ5$<}BU*O>{wQfwdmpr+Zdu@us$JD)wXM*t( zljw)o$N)Bb1JaXi^G&BhmVb;SXL<#`qg1|~1ZOgKfHyzerDcD_&5VdTuAZlRoGo~@ zufXOp({i1mj9#Yw-i>Lt6>X1}^TBs!rN5O?cD(tz07LI|^;EfjL~8ZOc)vH#C=v}P zb2}jR&)oRK1WwFwhuYu?_&r6WyLZE)mkybKv;bp-y(YPPNR)!J1@W~)DJ=Dr9LbCJ zohi1J%N946+D%Sc=yF_|+p!~QQ|8O;yB9(aVJwA=*29PO4yf`%&^oU{KTREXq%?#( zh|lt}0<1XSX8C^Ae_-6t!U&vEeGMRK2-?`hRWi>FnzJSlY9&?oC02U1O0{j`w`FXv zuK{8M9Tya;b}&=(aDiQ06l}2P11<$zIQl|F$I#?%HaQJt-|oh-x3RR{|%XiJ_@bkp%C94QN=a@9xq&zQSfI@9BxFwjAp5q_Q#68 zUlPqZ+qp%3Dg9?`8KU|pWsubSGSCk25umZ9sDH|#N*N4)R5;Y)>fhy2mX#dvK>f&_ z(0A6-WPM)DDFf!q8+j?b!S&Z=?b~++HxqaasU9m_KwcCDz8%*=)nQShn$bj)Gd%7< z_w1;*G*%`f9@=C+)f?3y$AL96iNN-%NRLS5Ifm$YO&tHAD%q&4814pLit!V#9iW;} z81iuVa5)?`K3LdQQSURED^(XkKvsFcFz5Yj>=f14+w~1c;?L~N&R18D3k6Y700k6X z+W3nnmTVR3=47@0IftkvXj!YS*9_$0xum1RR>C}Zx2K#43X_HTh(SHzTTaJ9$-!UU z$!@YV$KXs=>z!l6kvy*fDHQ_Y36Ni<+j4!$=2gwK0s=`hryAShUwWoP%qG&UeSdg6U zwuIN5V&$RUdOA?R0=(V>Tx{xonBgvUqjygVaybcsq`3qVWc(7WTjW&O2NFaAzXl4|p}|>rM$r z>L0(fD`lKn8SvE=QvfBntU%dKvvFS6<3Ho7#z4qS_f1r9A{oV^7&z82jz+2{TOGQqsy`>u;{?KH_F54_^yeWW9N8xg(PQbO_ZI~cI_LmJk_l2 zgN7O5oP>N*mm+o1dm*yuUv|f+#HtE$Fy7)5@;^d}e*34nC4h6;JBf=uE}N^WVD1za zgh`K%eXiDB!bQTG_AL zWDRh=U=bZmny&e&7j9j@EyLOc$%R`EO|i+;;^6|C96N^=^A3c5G=?O_>U*T!MGi<* z<*wLnrHc>>LIBLu&!mNsB>6~3>0o2Z5^IyK@+qA?lzL>}h!$Un%V?MSS=!~_@jcuBDO4iHv@3ey>AYOj*f;*?mcQl@gA{k zR+SypM7J2?EVCG#S=>HE_uf52Cq>ijrlZidXSM#MaR4q&kGdF2-EkBR=5UJmu9Y(| z`kOkk6Un7-LT}?QdIsOM&Z-D*Cl5#&m{+sI@Q-{NED_NCc%|p-Qa>MPX(5NFRT71Q zc<)e)z@~Mp7NHqyT)2B#(Y<%ping_^r-e5@B=(D6Nn56ItWREh(AkEH;qW`2+Pj1> zTG?w?SOJ~3?J_eJ+^cD%!_B15M^E0~wyqmo+o^IIa<$~+Wr7flM>4k?6Hxx^5%gd* zWsA`6rxvGkY20kzY8Id6jXh|m5tExey0b$#j;`lL700B`UE>-g`4l&?U}5d^#ES?? zT8tb=xkat*b;jzAxyHLE+Wb=#)F!o=#@5{v)BwA#((?7tRZT*fJD0Jb;&QVm5x?t1 ze+=!!&~%;d(ty}bdz26z$xV~%Vg-FT%Gbw>2av(EXr5yG&{Ur2>kHKV{j6ks))GCW zzsi<|I* z)&Y0LY<5kRaGxz6p>UU484Bhq$WHs+hRQVFsWk<4E=FSX*G_?l{Mqv|C5;nRWa|W5 zoP1=M0lqyh`gv77Wrs??a+UpE;3}?5R-7zK1g~rU1Lm$HH#aYO5$jJ&YnOSvD{+5z zCn9|wt*Y=jFKOjge!Sf4BLW?FAo-|a$pGtf2ks5DVA&*F%fa9|kVv;2SsqolZn@xP zjJTgCRx>p)QjBCn$<{fVKA5Z}D3ql49%)z-SrMiU#Ifi!uT1ZDs^!p@AaOGt6>Tm8 zLBfB?{7>~8afby)+Vh83D*u^`TPB`udUK8k!t>7u)C6QmQQMDaIK)m9;d(~bm;+M4 zvd4sRv{pMnu&fu44W&1p&$B7bF{9o|n{b5ByoteisObiz$dEtUI~(HKI=&BIOBWrV z4yJFeq75#FYX#0qi(frmV(|?Ci2!xR?P`pLnarvoDw8o4*rbgS3Bkj!yc%9ym?9&* z?CPwPE!dBX7t?2=A=rGg`W~hKWJfEH+EU&jqk z+s^WoczX6{7+K#|Jw9XJpNnTgFtNgZRb6|{4VB-a#4kYgdpae-;nA8Hy&J(JHx^sw zmb4S-I#DE^*qvbD>}weWxhrdU)bYi{nbtsowTU5jwUFExs2D*VXZA6K!2nA}ia(M( zs1HLu(X|3SmF7F*+{qDh2@XC_*sm$<9^QFDwHYq)b&^}Z#Pg18sMG$Zd!8Ki;!+~n zPoA1@6y;hg#$L}-pHNc|{n-UQ54I%A>1(<{6{>xBv}alIo>JSh+8W!x#`~GmsO}+m zTS-(RzbYwxnZU?@ax&i+UI4bZR*2k8=Ke;UrEEXphSFrPa!*r5YLZqkb^tdGHA@}2 z4#f11wD4;CGJaqJ5|^V?cMirM&2oA=^dl3WV^v+vod^LlkAF46B&p$DiUV~| z&w(oq;Sd8Wj_bAoO8#6TFoKuJ@XxDHmSmOE8T9Q`r3DV#^(z=0c7PPys_@&qVd*O8 zOXnS^3U5(^h{p}ggYhWaa{e+Sx%t6*`Ndg#LN5|sso5SAW)o_JGd@i91PQ)0JclJ> zlx?nZv#IlD#rP;c0$%2}B4;cB1%r8cW}aRS$z6A*=uM80Z#Zukeo(omylc3_t9ef{ z2glLM2ma2WTuBc5CBP71_s2Okt_}-f1T*S zX^v9s!-kE*Ypw+jb$lEMI6%RHr`+#=6C=4n_Lb2d0!dL10l=0GO+=bO1870#QV&jj z`eaVw@DbpZ%Nm^|Bw(h@T@H5}lZ@l+R@9&E2}eS6BQfZd_Z-6WFHHCXi>aKj9=M&V z9+|$((|;dL;nc=eiR4gbicr)ZM|7euoi{s{d68Z@tzDV&(O=0#H;jBt zxr63h1BM@{eSbylrO9ab{qoA8atlO(%%0WyQfE%bf5H!iyyzJV*8u|Mg|tb2jW z-wsQ0S;AIYdysX+u?@Y4#m8HfOORL2T3bES8_?Cw8;=@aLtdu7@M8M*ZZ8gm5*G*u zIi3^iisZH~TW7mXr^ieTs(ns2v9rEII+rYJ-KRNJ42I9K*Ane*DcqI^oRfx=Pr{mB z0R8{`BLg3jh5tS2h&`tS2ZNcG{jJVvHOD{daeqW;@{x_o*) z28uXhhFPN;4GD^pluJhtnNl7iD1##60(|LEGV?if4|46|arUEhJrW0`ma46{UP#0~ zPc~f^j1g>e32piIQdA@ztcs~8pEtsWhou*SzxBrX_dm-^5F2o27CNYkn(Zh>GN9m zcJTVw{vF%drg6pAk}&@S2H+$)A;)%MmpBsUU{|Q%&jSRjW1O%M@GboQedY35?T+Dq zv@D@F&TSnaeb`CzCSSoSbsm&*>3L*ZSXXU$@oPB48QQ7+V zC2Pd;Vw6#~?39MRoyXWA+irF>cl!6yQO0C6mHt0;q)aB>oO6x-9jTNkY#W(=OI|a0 zwlaO_f~`a3cAr*JXF!|Ena#!NS^b0omD=tw)2lq=l?Sn^45cEv#m6{O(99HPNG8@< znd{PdVI$bW&)Aoh0o~BzJEVA8?eSzAr}@~?o4u3ZsD2zS(?9%#@O4Ru^csJJ%GBeb zYioTkh9$epQ{#iJur%%%L8FI)m*q#owm>R6MkdNt2vd{ESwJPq9vf@DvV@%qABxth z+-*;tLpPsOw+hYe(*`x?H7oFIANzAj1aO})Mfd!Sfnepa@w}|@um28zX3RHe49#F; z(!xwmeomf6Iw!5)jJ;`uex9p+6Ec$%*N`@+_(@y#Jips=j6Io-g_fVvAxR|HtS9Bg zCsyN|S2C|@l)9ScKuRHGq?o`+o&!kF{kJH`|bVW^4E8 zRg=L{89}6$39?MO$5Xl)6-`x|*Fhx*)VSlp`XT1d zemXuu8%@$p#@#W~d;L1{9Hvn+&a%SAjzghD6NgU@T6Y_daCUrhO~kO1x7PgtnPPWY z7RiI(Jns(okHZEGjQYLkbotoK*gjsKhvL$rWT@lEt`9mNX5BU$R;?RTC%TVGGk(2a zKhHWep9ba8QfStK9vaK0^CI>$iIX6OZI}uH`H7}dl*43F-IvtzxteLFY z`l;4<#|N8}h2k>OSf+>KPKA^JOzb67Ox~;(RBAHh0Y*2S4{0^m=E}(C%_Z73#R>jh9+|Ki3tKyjQoO5DZ6^%ZI!e4SSwc zywpH4)HnAdK6%q%$*~>4508wcfZF~0i>B;G+L#PdZ_2wHVGF{zN}P(;l-+4G@QXAA%HMRrj&bYs2dfvQmkq_j z_Qa0n>hg}OS_f^d-X%{TpNsEnfAcm-P3>fi_nNBf61WpdwsCpCQ#-a8T7o5lep$KX zcrHmppDfh|auXJNH9FE{pJ*9TQinb>s!<-t)@w8}IFj!`Fc4oGmiF9#1-o zXpA7@a6UW^`Qs}9Ik0>-xP_ICu&yG)o1>9qLr_4kWNFed1xImyRw1=-#F$e??D)bU z_n)*yLr*Q$Tnp9)*gSxkL=u_G!4Gnr*)OwEzJeN3WAV8bY_xzzFwTlRdmND{f;v9r zV*kj=9dL*qs))Ca^EejQg@ML&$ClsMh0pqkiN*IjCT|#k8&Yogjw7s6>Bktepi&Sf zbL+kRB{Ac>dh&?rXY_@Q(z8awpEHZ;t*1b*=rx`6wG2#J%ek|X<1fUEnvUJ;r5@XD zpij6?)g)`}bVE-I5z@lop)M=to+siYJ3WSf4UkovQ0WV|S?ro|m(`mMf|2QmsERvQ zg~^AkC+8txX`fCPe@5i9vtezfOg??@e30^uXB)F_C2heF6DykDSK#il0&E*9-4o9J zwbS=fr<&y+!U1=rj+$HGBMHx*S86mYv*q6X?}@t1VQ5GXcU_)Gr7LA!Nr|$1PD7n z5bOOHfvV$rOZmUHemK_KD9xS-hR1bcQp55TUKMF7z^pBwbH!C>88}a{8g#YYn*~_?QZ<|s?Y)$E0(3M26+>J-EP3K{!g`5&15k;%vgs`TX+3I#?Pr+ z$loL=6i+qO&zfEld#v9&WGYx3wsWK17SrwI4lQk4J7ItO3nPrZgP6~~&Phajhm|$; zwi4VqT7rSH`y$VtKdC(Y&ytdC2Os>?S3kX*D6*3 z8dNjZq_8;s%|Gk*26}nP(|dWH;*+VAil#tc3Wo@XyPoZ#~V5 z__nTADtK{0?EycT8~Dc{h`q0Q6!f=htIfP;5I(#XD%C_R$s;!^VVPtfK@&Zo(qzm} zKlT~_Od45!mel}^_g5sU5gE?Gz>*0d(T*8dR=P;OdTf?ee zs@ydYBrEX!%klZ-*E#@q@k2H-LaARFWId4{zv)F!G}a(?AyqVg!ge3sS@@1dcL`MY zt~^+94R{}J3&IL|FgBqt%wta&4UA?cH|Q>|UUo6%X9#tQ*_}=LP0$}OcHz{4B~En-0hdbN|=v<4U+{ z>e>B_g6n>L%`1RWa~ObN3~3kh+{S(c!_533CctNqpH#beHCs|~?*Q(Zg{AE*jOISU zx$o~B>ACvn#J5O^N(uO{mf8E4wELbKL;vDlq-oK1(`-)QpC6GSpb2JE5Vr)&y6cJ!p>90Hm zJ!|`Y5{8kRg4LdY|0=!o1JY9KJ1wSpkM-M5xN_sM(hzIgZ5SuLO_1!WZh3JrDSe{~ z90|sgj-FA~-*2(o{2Par{x5DA-=fP@J%lUVm>x}a&#M~-_hrD6KgzaW7j^5Q#25;$ z_a)USYB6HS=k3%Cx*6J&en-80QFa8R-NS!spPSs_d3e&#Uq0HSqHbRNxF+~q&r#2Mr_p~Ees&LJMQ z@EftxPgVxOmmRjU)jv>SlmPA5yyjfTU(DdUdmWh60VrUU#C|Jk6m~A=|2dCjW@7#C zKJvZ~1Hi__^}puhm?m(gEFBE`XmEE*%|n!}?d|RA000qf5l^XoyO!s1DW|I^kxMF-l1-GZ@g+qR8PI<{@w zdONn$QO8Edb~?6g+jizVbJna`|2pTc>Y{F|_Ooll9=;BWRz%PEVuL`B3`E-5 z7#oW=3vYtXF_F-$K%KxTLH7}eFiqpy|C$2Pk3htMxc{s{nJ__ON&f@DP?xr}a6``w z27`k&r5PE6dj%UKfe)ORxk3HP0bki?4rLlZIzkKy0+|N0 ztVJAI++Q7>U&Mld6tILop{oSt*c7P-a4SE}d!b%@c|aVHu7L3O_4jxYqh;ajKrSv6 zZ0@{D=9NVvBWMpOP!0fdfyYRQg$rb6@d;TxuL1gCmG}e_f*-sp7x9aM5Jo9s2?`{a z|D!_~8J}ha@#xcdJ)5O%VY!0r!bo@3PSJn;2=OrLjnQP1}-ARg_H$Q z%-p+!f0iG7iGOT}=k?$ZAR0YyK+&MsLHm4(KR<)`1cI=XQPa$P=SF@1IN8_$(XB;9 zFhZ<{?kM=Cerv!nd&Umv2545Gjm943gdISZiF<(DiCkO@cxU&g&-m9|%?Vn@n$oJG zr?czS@2Zr55&O%ROr{vJ?Tx)z7^;{VEGo=&|H%rM&zZ&CHMHD zCaLS|2;_bnz7Oo>S_?11@+b&o;+wP`7h5=O@;?0iJL3vy|M;%^h^P71EckYmgv*(l z0?snN*;2~B- z^G*O@qYUJm-T4dUGxDqK*ZdQ40)8*-8}tFB)7m%q9Vids7ig|{;5TR}NY>Q%uRaik zwC`TaFqif(a3SiT5Bxj9b)lZjZzW;Npf7MZ5FX?2u<63x5O49X`~Z*VFZ8eFGCP6% znPcdEMK*>Wmt$i(A7NVDRDcAe!_F0pWi`9CfT>)S|MVZ?E=rDzV@A2OxSnJ zxUi^U;i%If+(5Pz`FXF}Zk*llC!@0P8*vL)fkbn$P0Kd4fELxc+;wvy@P~{joq;#i z;iOce&}cb%4c^NQnFYpO%r5j=#hAwF8KZBBj;!_eO7+3|*ba_o1BrLLT0cVFVFrqPSB}Ns(r)E9IK0MID#IdK%fJ6Et{drNm7V7M;02U zSsQH`UgnNE<9Y16ZYG|MXh+2f5+esJAeMchA{<6}lykcEAEvfp?Ch*d@yTprkbA9b z=K7YkD=Iv8Xo0Js{giCof2P(es~&`H=5q~(AaY3Lr4O8svSFUP{I7XFm4hSFa>yMX z{Lnp2a1UShL;fAWc1ig%@sx0jL7)k3ORtK2Fn)naw36S@wdEu#%JB#MwtoW$EOu)T zi8oO+c5ut}sysHna6|V4f7TdY$g|`#!X=>Iea)+95@e3}mI?Bsp+kj&c2l0Rt7c&l z2iDM#xg#VInp!fZE?}rPN$xo&EiPO3cbg*#Nk^Hdf_e53SvJo-%^1 zOz=d99N3IA;GAbbwLBtnzv63*S8WPLbwmD{H}5c}c-j)rETLXP|-O*e%SAm$qnw&4|Ur;MP z!e}Qi6qL#ys!~caK)c9FOUbL6pr4`)%P=$ZXxopQDK79n zlcL!*w&x?2`r>ntB%%f=Oi~uG-sZJ??kHtsTU}<0i^@GI`^KwS@i~4Z`&Y8npGJL5 zHN~eBHOr8M&LL3kVQIv7f&a}YR}%a$^ogxEHc4w^8CA9f*0k5`t>x));}Y3}hsFZ> zltwSyDrmd>7hf`#*Tgl^f;7SH$q#G2&SkH)(=~mm{67z%bv>oP<4sRxeo=9z;;Sa! zZ|%?S{qtibxo0Y?>NRbonfBd8-g-mphwfUBGmV$@@IcfGWp#^VnoJ}5pJ@kj?=m|@ zN%hM_#>}(dPjK;%9+wZkP^%nJpns~Lkhm1BeP{hK$yM8IIWscUyV^YLywXQNpO$QF zYksk3(5E%s;A7tdareY_!&$P2*OM`)kOrCEaEod2`S@0ms>}-l#zUEZj}!i5CMq}I zL~J|;+iBhRhsV`4#&~`+Dd7c7CD#QJ%n#n|VYdo;J1nKId>F;5Q()}Y1EGDs#QEFvXAQx4&~L2FXk_(^ zes9FG6vNdt)tlmEZxNofq=75)@jt89N00~oOE*MHoKZ=)1(pDf&$`CFoS1m`-i;q) z-#eKEkep|?`ibzM<&Q+c@T#@?B)|269e9sKvfSctu6qYDs?O1pUyocOWV$cJS>08C z{NC?oBIFT2I{T+5) zXD^eP1thI?%#$u8fy(M#$PxAk^J_mvu_>jqCwn+m1eYAGUKII25r6XA%sMdqo=P%dB$MYCg_vRs*45R*g-t>B zbH)=U1L5EFR34~8L(|{O`(QJ;T%djOl+){;Ki{U8zDGZ)R#QR*)hj!%R6Yo@ct(Ax zb^Xf3WZQb-a6SuRMkh4eUQ3W3bM`p~z~$Vx?3aGtgwqY9hX5m?0quPc|J=)*Z;Dqv z*l-pJD^O$9hFWJ`alp=s4N$Aa;=;v&P->QCBfK@A6Z-9l+>Gr>i`@$7iEghnyGj>R ziw{xg4wYGMh-36zM)s@rAA4Mq(ZY;%_f^^my&KkLKSn?V&!N69^xow3{O+ItA4ry! zI+$*YP50Y26R6LMf)`o`E|$B*qo?wnXgSxMCZ!Rz^G4Jqzf_;W;ptfC#h2}|=9_;f z4zTzcbqv8X4R8}ddD-e$(VjS6@R8R_0}{dZt2T@lkXzSlhxOL(9r7vAS<5``CooO0 zT>2_Mf3X%M6lR`_fJ9f{gk|Xgu^D7=4+)vId8R2wwap+joT&e)5cYNk3ue3M!xpT?PM&sPAqpX>Rumm>i1zJDpin zqN+@bo@$W<8&<1amk*;byW}-NwI)ayWs|nJmHACejep%O7|65wM7Uuvtv)RO`BLc$Qy zraw0)cxWi7ml|tmEjDijSPvrUyBNrs3EFyw1KIMKE#h@6PmCofVUa~t@Q%X4OnWv} zL0ImkOH0Q&FKqTG?bjoYv(zy!qT<7OqL7w7Iw%s2x9p=$IlE@AcjSS$BJIa0c0wsz|{By>RhT9+jWuMr0A@`f;fXS4; zX)pC7aSAgV>n@-8je=k*woZ@zj+TPw!=~cIPa3&_C-VWXVk;>m{=Ea?-7X2~w#rdV z5|fbzSkWSSTm&1LzL5yr#SP!UP#CfFNQF2vFs3t?o_Ai@D2R(kIwLO=Z>?X}Kau0f z{P4SySLQPNf@aKs>FrVo`%{D>E%(|)VZOPrE**jj75Av&xg+YxDO_cw_Z^-$lJBGN zCZcg#1x5u>`;R|RkyO|H>NW3SlOR55NZo~M8s*x^qvmcm@(V@ydWG)askj)71~|Iy zcjIA^D^<&t$mAnUHue0Mr|30fv}vIzXt3KV8*f7{FC$X`1JVI|_thM;BC;Nb>Xtt) zWbqVX8$PLW9rf_UH~8 z37Yfpc(;arz9aQ_3~7SEzNq8Z^S2p(sw6Y=7@Hzc_IB)&^PddqG_OnypafhsR*-2 zZxa(9n-B8!hDF=CzCDT|X6UAD0G74PkS2-{2GV5@Tcx=mG|@n1E&4_Wcf0z>C}`;n zp<)lyN$%7^6%_wWaX1ZA`bjL;hR==%6}Z^(z^4F6RP=_*lrgL$tpr>R@CwFg$EV%< zyuN<@Z-s_J_9%M_lxvur%R-}V;b}8ePG&lB3321t1Dzvff6ZSm4R3% z`13G#{{0coTT!Rq`li+oKBhD45qZ3c`9^0AU%v|j10W$Rs1aC*@nIYd?$!Nz9+X$V z+yf#-bc=Vz1cvaz>`6KPUL%^MBM42!F(jf#Y&zx3RqMf+428t za92@6api4p=o7L9V(NDKO+MzhE74;3xb=UAVLA0$T`)3$Okq4?*EOv$w&k_I*iXff zL=NAi*v^kHtF}(g6L)&QEIDD5wcGPnDFTN&w%VE z3MqPj<-5B_6G63;Y^(;zso*tof7Qr3uaa8-E#a&#+6OIFk6-iS!X=SC4#m2b+qsFH z2WdC*+EJ}}YyZZ6(u+P_yTZ)xms9l5DdcF_5HMJ-eF7wz(D&bsXfK|x2shSIhSF;= zg#4>Gy9$wyxYTZyLQcB`=841V7QmTC{JLkReapkvuo+>E0(qAU%3cIT5iXN$irm*E z_RF67_sWgA@li(A#fo44$s_A;6T{=-y@aH|0Cc|7A&j}c|FUjy^%6S#Dj|@>(&E;j z8EIgWQlC6+;lVA71{Vb-TuyggWZzg>(EB^Zu?IOu_8Hp zv*gOhb6uqeY6p>9Qo5VtbHeE7PrrDHez24VYlgU#%wky)G7(~waj?C297km(-hLXn z+8k8>&~{<1QKbb+s-rG-Cg6%9gDbH0qne_oB*h z{a<)|?)#lQ2GTl*^2?$exve9U;U)c?jge)9)0@5^JoMv-0MVaVU4pDIXiPSS3mna% z!0QiU?uUdfUeQo+5Nxdk>hecotpgs4;p5$-P<|KN%NMt5Z=ozoIRL+@InFrWXI^<% z>+B`5Ff+!xzSYs;1^f!8x~@jao3PnkajD_CDT3?f;K!S)UxIdslBMFCk}B>IyN_pb z8txdC%uN51Yf$uSfa0p zV6odu)L^9q0VfQ$GLWC-wHRGS>6M(Mz%BE;?7m{~2hfnDqUea8!y6yk{wiv)*yoXv zU-#$fIN5)zkX{A8K|UFEo2QCrjS~V#9kPWgEiLY@n&C zH`X&dW#-3EP;c$G8F-c*P6%W*2>i0dZU+~5jf<&DuD80eXdtP2J1!=9Pg@j6pbRF= zodOp(;-{albb$~Ku0LjXcb6;4kv5%FZxHD6h+sTn@oI~U+lM`|&&>WNmrVWlRa z#z>n0mLc$2UvBlz&Rk@)jmBZ^x@liuq1<#LF zf?fmNojy871bAZx@4%|=GNnBiz$jDCP}tFc$qSsAeMmIU4x1ct*h!KzxH6pA(yc1b z)ILNobr@4YdSg-A8y6XS)yfZvB=UNJcZ!>|7wTEiFj6hL)Mhh&Devgir|!%UAu-1h z$vR5Z?cwyWq{#M*$9~(OI_$A%$G-KkhY5lj7;SCM0q01d`u50o2HpSh<22G4#mc|K zmQRNNtB~|V;NiS9?0EU=@nJJY&*MP4v;70g?yUTOpM8#v^o@E^LYw_(;UFm1& zx_LGwy=0W_iO5gGV#s3-1zNINaff+NyYxef(U*o@`rJiO$52lm&RwgJt!; z0@cZ3QdaW;y)v@Rj>gkr1`^*}RW*k7=HGbOr-1C|+tRNGviV(lI8s_eL;FqBY1Gb! z#-HRpr2=XFk_Ne<<5snF@_tR>mKSPK_ICXRJSl3;Q_^>RZR8C86C^7$OP=l-hLF_d z#&5mWhw0~DZ&2bbRhy!o>P_y{ImMwTk}&EceVgHFv#0V?j7xurjt_`)KX&6KQ$F#l zZ~)MD2Sryy*7MzHwq)Cw<%@9?$`JYh`B-o#&AfdN4r8)Gc!@3i>XilA0-mbVU*fc< z{OXOKNl&m{(s-j+j&W=WFFR+UPTFs1k6ZDDkL$he`!%VSXD7`H6>%}q1pK#{hA7o1 z1>J~x7>Ag?9ex~h6doy{Gm9-E=@IfFt$_X>*H?4lVOmn0B>mdE@uh+ngrkDqoPrscd~ON&Gkha=riR75$ii6#MSX2-29k5@5HLXeJ?Wd;~$nx>qA0dza_ zF~th?@3y?j4DRv{tnVq2N0Toa&FNLIwjvAtNNhix4xqbFJRzd$NC>?932eYw%=w*{>CB)i3@zIxgHbK5okNtLo+nTb^;=Zf#*< zeer{#st2L65h}7OJsQckQxHuiXiM5AqBG)X>^UdwxB@9ZC>OKhwcI_G#Z9UKIrRND zD#~$U(cl6YDj%t|$Qm*_H@WC62jJqJdVCK+M+=otE&?@_aGMQq8g4FY$PxZtY3t?* z8EXGTk$Z9j`*g2=AXy)JG^?M+)7c zDvHw&-6#C6JdCaU!Y|GjJwcokKHfeLPnAr9YY=;rmry-{c6yKrGq?_w4d~nK(I!Q! zgAT}yEbCo=Ec!d_a;gn!Ef>~%Y)LBZ91Uh>cBL4h04|>n-;UP`xEcv0K-ZN{SgI6{bdWN*Bru`xWGt#anuuihSuFaY7I}x@@X}#we_xP#yZyA{> z*FNql*Xk+9Zo0mxX39rXJ0MBq1L2c_zx-di1%q2eXn)7<(~~HS;#4-HdtUOb1?F&y zCgHuyJa`*2*Yr=8*ZfjRWL39sj>B$TDUB4GNj-(?sbpJB&|)0dYKixMY8%W4)(2f0 zq?HwayM3cnLG^T2xHc*B54u&)r4Sgf+#89vuQ6%e%7l>c=uDO8&j1|woHSgarkaV~ zNuo()KY=)*@wFo#O3qo9(w2&RZW`~OXqxqYcyM-_DdQGC6cS!V9Rss9_;ppr;6q_7eG#yPfuhl#I@iKcz%>2_~=6KV7fv+_E;u5Y_ zuMJ~oiC`;_n;-qNRZgcbl7GJR7oo>wQD5LB#jVH>^`hE%HUQ3>BJ~cQWqUlJnO|{V<53*wvX2D;Vgm zg{}c58rk6WyWe-o)TMslv=cNl!nIXxQkYz+file}XXG$djV{gom|Weg$ZLH}^aJ#X z>Pss;PU9P1+@_c{iUk8cVOGxY2|Xpp8(gtBYN{53546+EhOT!@>m(v z0Xal8{!|@1?D~NLF3c-`?)kbGkqioL;D|kY`gyRDb&!UFS@>NNJe+v^z0 zB~#zHU(*A&R8cqn2c@$R+Mm5-3xbC;@i(YtkKk?b!r}tqCU1z1Wm$ZbCAQ-5+?+MR zsnXZ*Y+wML74~lN&57jQrLe43t~v^PQ56=-Y zWwktQ-8Ciw5v|aIzxcq6m(904<{0Goc^m!n$=0vQc7nOIDphsVYG6Sbuj4FPx^vN>1c6Sj@s5{YwZT(EemN8fh1FRr48Ncmu4dZ3n& zC{0DXU*(ytkWb{rmUQP>o$`SxdZ4)6nVSW*+#EV!`yE{+N7OL-Fw2kq;dhQd}f)*&Y77o2`Bh;YfG=7%1~Oz zw(E#*%`D*b`$w1(X#<^xN~p3*q;gF85*YkH!`&h6##=wHXv;5A?llzE{M7Hzm;qDf zLFg%j19{gmUrpFe?ofCgqzopQkPt#hV}KcB*J3-yaAXI@gCotjQ+Cx^NT`S~a(nkP zsVIW+o+*UBDtJ-SF>$NXwxS_Uxw*8=Jvdq6|5Nw(1F3g@Qmc_R ziE$N+FEiNQ(nC30`aJ>lcblbwo5IG)fCZZ@14c!Zkl*0h#%6b zme>PD+6jllEMpkkqjtvA!NEj&D{YCL25d@_WPP`6HLLE+kloc)iy>(k;GZujk7t2K zq>#om4R=u8TcZvv0-Gk80HG8j`y6jT>UmC=oW74V)xzvcR`=rcm@mR?xfA6UHNLhE z72g}ky2lfBRlaOFVj%vd*H#{cEaVrY&2^p%c>5E&6QliCQAY=_*`AXggWX}!LC(wH zyCe;f{8&iCpAr#DCVxq%y9T7{Cu_=$N;G6yXgsC?iW%vwphe*86lw*u|{6jA{E!z{m z4aeTBlPombBGN8R5W~#+WfulG>6~^?!y#!z>Nm~~_Qz5m zO@!_Bxni8Jwg|jV`0r|x&r&7jG!aG?S`-xaH%K+rT7>MZDYgDbqe-|Od9spJ>=sEj>snO9y z<{JsDj*(a0YMXmca`E?}tq@XE^LJmkC_>L4*3 zpkLpYeNpBey?H-h3WC>PHQuz6NZ(wn;AEHZu>VSFXhhX@)i!IKg4+ zJr?QKvK*Tlc{m_fG(X^rRV?Bcuc=wH!|q@8upjT4%|^}iq=xB@1F(9Iv7#ccH)Rpm zEhzMWCyZ$P?!-sk868D{KhwQA%X>zrvGNf9r@nsmhX_cqeX}UssqDS`fAMH{FV=O} z0sUNLe9SKyx_ruzU2R&(sf<6pxYXz!C%WIfpL*!p|1HxJ2mM7jLfbw2S~wx)p*joM8T}AP?vT1g#!!M zJKZneu-SQ zmangaMU4&@yqgu{5dn4Z$P2RJv*E%aA(fxs(E3R>k%@Wqn&DISik?*_|O&sV!w&^am`-y-`8PQXCHfbGSdkpYJ(r* z2L^6MOVSZtTvjuIDx<2wMQBQzLl)H)kS_Y@S0ZmV#`*Zw#_S4h9f2rUVYf{NsF#0d zJvL1SRWn5}^3F2~;8C>mEi?*CwfU& ztq=`8UivbLsan$UYN~JcOzdaAV2^86QAnAODYRmHd61>>CM)nP=;4YcfRRTAaJI>P zi+hN68SvF=aMXJi#mXJgJ&F?cJ%qPEUoa)1v+~!TcW!0FggoSUI|SRW3ztPibwjiN z{i$DdAFD9HX(}=-VyQkA#j(^#*_`fXn$GPh)MSNE5u!GgX7=~?23I10LDTADV$+Z; zcROkM61+M3L+V@EZizT)&5ktzbjXClO50>VmCw~HWyv+9Gtu(?^MsX>tud)l;)5!x zzTp>Hk#GZgJ*Nej^l%iu8=}1G=qztL7%ENVs4JODWVS%Fq!Up^Ro>wQr{*c>(yqhA z8(2c7#yxe2$OWUoG=|$_ilEjAb)%2dra+4w+|aKJcZPr22qQ;#*snYRaPCGcnay>5 zWLv!&Uo3d5F=E@e%12_nQR2rO%*VlfFHgV1N8%kLO5YAhL6w!G~W)Ze}j zc*-YDCJ}jl6#1IbKK|%~*%jbs`?+C#M5l%SrXkGPl(OK-K%r~c$uAIbTP4-X?4mW- zY_zQ0`K{p2&WK9>Vz@M(GwoFFDx0ijJxG+>*pCR&ritT4A1gRx^j`6Yazlx0ggk!X`2c;1Wq-15 z{?CIrLUI}eqZhET3LTeViA+D5HeI9tT9udB^t9}BZgXlHBjxKq`jQ(REW5_5m`oM6 zBs=1WsCvCzUhPf!fhO_-9!uK$0|!(V*&F&t*((dKdm`ldqla_#!{SA&N#6=6mw|>N z5hHAS92tv;M|*Dvj7ju+zm<(MA_k`N;Hh;mHv82r7bDX0&#QOkg?@s@#nlFf`T}KET3CZ0VklmAp+* zQA|n>s!wODX(P`oCCiiNX4~NamdO#Vi*4Q{vOo5XGBY@sbpLWqFS2Wmc9`@aKeD5c zbEgjGzlhZ1D`;eDGwjn2K#KuC}IUga^k8B{?)|_@Qd!OGtO7> zp3mQMp|8RRo))dVy=k%9G=kE-E%DEsUNYo4;}D)Nb50mBf1JxAjt3xUj<17Dc1&CO z4rMiGgDKGOZ9)$jur;Z{7Ly^B!4^gn^+^BLD-G|_v~-W-v2Vn-BfYd&UwU-bzj(J_ zJ|cE|a5}gud5O)h6k?aBo&op+vu6Bx>VS`zvK%AJO_K?#sN0Xj_2k%KxxST$Z@=Bul{2aZ_rYMi54NP5|Y`ob(+w!pi@fO97qUk=T2OPs?uz9msIVfTufE; z-B#ts{f%FJrNYdj0AIOtrgX*vsAWyo4&np6frURB2VQ26bUfYzVY6vc^Iggd%-8gq zl0IS7@e-2N4>?`F;9u3OM4sEH?YNaQYpj#NaJ~Q!sl>vhjkP@GUJBiQh_$8UGstM} z0=u)F`S_fPo4>}|VZN6H`UDPNmR&WEv;F&B zWH&dzejs&qK)?nRcI7G=PXzrN$!N8|B5_c#5djC#Fjgl% z$Y~rwHHi0?lQL?)fy7jf31C=H<6)#LQ(TP7WrSvB^;FkdV#jt+WtfR@#9s{{B6%Qh z7cJ@jpnNv{b0jhVFQ!5>f<@KiE8&EU#KP(aOC^~v0Iq^?f{#=C)C_Zreh*{AIm0UH6i1b6D?M25oK)Lid4fAe!px6g$9C+yy{OKTt z|GwX|-=mMN8=<~KjV&U723T$H9YOEO$tMeF!zU?`5t8UIYv*Joqd2B8uIxB2h`4Xe)Ym$9&|@WC#4FEtywwo?>=)Is9gFRN_z-nkhaKwW~L;Wes=9B z|3!@JjH3)^?qKHX=3)+JY@cR)0m|G`x&TIopQiE(DuMBT8VWf%(u5(v@Y4og|8o?w z^RoXB#q=WHXx#qLN)M z3hCc8GUWJEk!H8Ii|Z|9Q#ou|pZiGR=iArU-JgLGF-B&!q^qB%C6s#^Xn43#)0G!# ztLLt5Oh@oTD}TK`xBYo-GR!|VPxQ}y>pkX{S-TfR~sjTFV{r!@?ENKuV<$I2=d?-sLc-ciicD%-ix?HvPu>+O;F+!6L$zcqTpz$uk8gAbw@ zSrpw}upkKJtA{xg@kGwvjwcV4R9y47gQFd-mxOp)!iSNJ>eVe##Dne!16^-niNjhP z9J(cH0Fm+@06IjHhW}DS!V=)kntpnOxe-m$!tZG6^wOR$k}%u?MqMb;F%YI4PUMLR zqW^?78Tv(xpQC`csG~bXnb)mPVnb~Gc4gBAa3#j|yI})4w?ls)j}1*O zbFnx;8)D?%Ps-w_uD1wdDl=fxNXuA+kdQ+(5txj_0%RnN!yqt7BV=k5TZiLk`4gAJ zG813y+#AEsAt|-d6MYaJAID2lFYPOwhflES^L9@bNbfX?%!__l8cn7`);+7m5M5q&dj3rho5F`z)VM%!6^c2~Y}WLv7f6T(8#dYjd_PC{%(aUil9 z{-S9NsLQO{_1rJ3-x8sBGbZhVOhmdZeYT*$N}Hu7&~Q9j;LdFbQ94B^fe?#!{gfik z_v%;|H{p&uNZBNL6z`46%N)CZGorLw9Hc=^g{idvF&%uW{O7~--F<&o1Qb>$l0+J2 zPUStT0NhVwyix#&2#b`!TJ$IRgUUyewE^z{6tgidIG$RCBJ+*>p}-2GnMDu&jR&iN zr~J=EP*5xPbx+;NF`LB`-c~b98K2#tmvLl5lB|+}?LHOhR!lUNVrwZ_7yAUZ_(T&b zDL*!tV7Hm)9sNX6hEo)9;;#^n4Y^9%S*Ji_*$7tMPQRu9D?&(K3OtgwRWpqM*y3(unmiF?6sN zi!SEA#6r371MD@*tl22Rnqnb+2P0x$sq1)sCg9DbUsJKLTu*$4pT1N`aC8YJN}8QC zS(cXBRHzMi!-Xzhg*RH&dt*_&bQ?n#plL_rz&)zi6Ru8=^t&eee7+UogqKVQ`)}$? z2b#VR=DJpHm-w+)>g3#f21qQ@&mUiAb|OKQMT`>iXCXV4a3d1qQbA09vj4;ELt%nu zWJE8qwGPz$2gPXLxe1Et2Bi|;*a*hzU~4px(k=D~ZVux_&c8y6XIw!|tEr$2gk}9j z2uNg`h+yN{(+I+N``mx+Gas{3Rvyrqo1*R4BkOcCD?(^A5;H2Qae0yi4sj5E3F-?QF{TIgHb9 z9{ziOsJDg-igOfaC{v&oRJXURn{}guJ@RuZwLNn}rqc6Jfgy!Hc~{7=sxP){X0?9p zD${QrYw@PQCmz-ne1+^Uhh!J5=kM<^d_0B+q*-+yiSWl9$zE48)TjHg8i%|1OE++h z@u7Gh)l$6IcE5UJK$ZweEgd8Lj`*t3hR~=28oNYjWxho55-Z8mtn<{vZTxVGeDrg_ z-6giaelWGCbK&amfA805;k2ntAJnT$Th0Apn#ho;Ej}x=N0{n$X7jif=I(UJ?_;PC z8^NP_JrGgG*V&)AEsPqzDnmQvRRWSc)bBzBos<(${Ent%fZuHc;XmE6Hn2)qZVec{ zX%BOru3*XvNwd;vxkOo(Tq2qzO4;7i0zwz951h^x&y;^5-Aj*JfRx+kYyE zQRE^r`^3@h)nN4_zjkOpLRnG%wtTVhz+G;%uU+yYg4UJs*NQjul0bztQL zq+J0207Q36Kxk<*E0GdjTJ!k>iMEuYjB#V0uP3Z@faZK_3=vewXs^yF$2WsCBAHXq^e82X!7{G;v>iHZru zeZIO#UpmD4j2X{gC6ri2O$2p%L}XOlqF~`MpI_)FfLxMa&5yGr#S)N|%FQy3tO}gj zhl4Dki-nhnn|PzNH#GFT$f^jy|JTH3msB50k!qg=2cC+!!1&(2(we?(PV#;%;`F{S zt=YxvMZYekU%?XS@EBxX!tk0Ns_NAU-00 zODfME5RIx0xP{8x45R&{2*zM$!a6e0@2yk0jnbaBSR!4yV0DrLMY%uOcRneB@tGvf zX<{aFGfh&GkR|q8%^?>G@5F6+3?g3x`e`BDbbM5mo(kGW!8a}{X6(hef%#@`xu=H+^^6kojg z^&ze7@P`BjB@turSt`0LO5(wRwC~lXiAOMvDk(_U*u1eFRK>Y?j)tAL1y17pB&v$b z0hd~%uKwJYdjl-Fp<17r5~y5{s@B`~6ijT9=O+7I>q9bHdzyMToR;m?J-VaT3yX$<>+Rc#9fUObmhd2X>@;lW{NS6;Uc}OwqYgP zwjpQFyF@6FmlX1e@I#5sPiKqGge%IRy7~XW=IJy7p=m$+Tok zRz@S@CLE#`j33;}53~v`X{3ZVli{wNowj*V=Z}*Gq8tYNA>LQcRNtyo`I}dGR>txL z$k&Ip&T%8DJ39IbH#|RjFwv&d1yRBgZWE>uNR0kF+T@u^`d3#)!S<+F zlneSWT{#xyHK6DsY5uj_HWQ31*ODj_UYHJfpcAnoZJc1qgxyQaQ6wE6K64rUC>E}( zl4ScIGSc1rP77@kCrITDJ-9`Yclx7sg+DF3p$r6wL)*etd{2#oTpljZu1@8#q_iuN zR%YO5`?^DEGgI0RHsP_>C%G%`CN|u6p&&P$bG8vvKHZys5a#x;zy&|io4p2njpbw3LcPDc*5PO;~$}okEBUo;D$#% z=l|cNWo-YyR*oh%|GAo5qJzNBLDLdj!RT5ZuEB~~(ta&~A*24d#6xs2F81U+NbIz6QgC5_lZ5%F1c|PInJJrvF)s(Z1q+WU zI|~W^RqG}xwY8AmsEMZ3kNvGPN fj6OgWjqeCVOuj^ef(U!TTqjF|iKShWfn)wZkuCy` From 83d0b9d3ff14773e26e4fe470ac26aad9e562a24 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 10 May 2020 13:40:13 -0400 Subject: [PATCH 019/199] Inlined derivatives and fixed one issue with Jacobians around image center --- gtsam/geometry/Cal3Fisheye.cpp | 138 +++++++++++++-------------------- gtsam/geometry/Cal3Fisheye.h | 16 ++-- 2 files changed, 60 insertions(+), 94 deletions(-) diff --git a/gtsam/geometry/Cal3Fisheye.cpp b/gtsam/geometry/Cal3Fisheye.cpp index c6b43004e..f7794fafb 100644 --- a/gtsam/geometry/Cal3Fisheye.cpp +++ b/gtsam/geometry/Cal3Fisheye.cpp @@ -24,7 +24,7 @@ namespace gtsam { /* ************************************************************************* */ -Cal3Fisheye::Cal3Fisheye(const Vector& v) +Cal3Fisheye::Cal3Fisheye(const Vector9& v) : fx_(v[0]), fy_(v[1]), s_(v[2]), @@ -50,76 +50,73 @@ Matrix3 Cal3Fisheye::K() const { } /* ************************************************************************* */ -static Matrix29 D2dcalibration(const double xd, const double yd, - const double xi, const double yi, - const double t3, const double t5, - const double t7, const double t9, const double r, - Matrix2& DK) { - // order: fx, fy, s, u0, v0 - Matrix25 DR1; - DR1 << xd, 0.0, yd, 1.0, 0.0, 0.0, yd, 0.0, 0.0, 1.0; - - // order: k1, k2, k3, k4 - Matrix24 DR2; - DR2 << t3 * xi, t5 * xi, t7 * xi, t9 * xi, t3 * yi, t5 * yi, t7 * yi, t9 * yi; - DR2 /= r; - Matrix29 D; - D << DR1, DK * DR2; - return D; -} - -/* ************************************************************************* */ -static Matrix2 D2dintrinsic(const double xi, const double yi, const double r, - const double td, const double t, const double tt, - const double t4, const double t6, const double t8, - const double k1, const double k2, const double k3, - const double k4, const Matrix2& DK) { - const double dr_dxi = xi / sqrt(xi * xi + yi * yi); - const double dr_dyi = yi / sqrt(xi * xi + yi * yi); - const double dt_dr = 1 / (1 + r * r); - const double dtd_dt = - 1 + 3 * k1 * tt + 5 * k2 * t4 + 7 * k3 * t6 + 9 * k4 * t8; - const double dtd_dxi = dtd_dt * dt_dr * dr_dxi; - const double dtd_dyi = dtd_dt * dt_dr * dr_dyi; - - const double rinv = 1 / r; - const double rrinv = 1 / (r * r); - const double dxd_dxi = - dtd_dxi * xi * rinv + td * rinv + td * xi * (-rrinv) * dr_dxi; - const double dxd_dyi = dtd_dyi * xi * rinv - td * xi * rrinv * dr_dyi; - const double dyd_dxi = dtd_dxi * yi * rinv - td * yi * rrinv * dr_dxi; - const double dyd_dyi = - dtd_dyi * yi * rinv + td * rinv + td * yi * (-rrinv) * dr_dyi; - - Matrix2 DR; - DR << dxd_dxi, dxd_dyi, dyd_dxi, dyd_dyi; - - return DK * DR; +double Cal3Fisheye::Scaling(double r) { + static constexpr double threshold = 1e-8; + if (r > threshold || r < -threshold) { + return atan(r) / r; + } else { + // Taylor expansion close to 0 + double r2 = r * r, r4 = r2 * r2; + return 1.0 - r2 / 3 + r4 / 5; + } } /* ************************************************************************* */ Point2 Cal3Fisheye::uncalibrate(const Point2& p, OptionalJacobian<2, 9> H1, OptionalJacobian<2, 2> H2) const { const double xi = p.x(), yi = p.y(); - const double r = sqrt(xi * xi + yi * yi); + const double r2 = xi * xi + yi * yi, r = sqrt(r2); const double t = atan(r); - const double tt = t * t, t4 = tt * tt, t6 = tt * t4, t8 = t4 * t4; - const double td = t * (1 + k1_ * tt + k2_ * t4 + k3_ * t6 + k4_ * t8); - const double td_o_r = r > 1e-8 ? td / r : 1; - const double xd = td_o_r * xi, yd = td_o_r * yi; + const double t2 = t * t, t4 = t2 * t2, t6 = t2 * t4, t8 = t4 * t4; + Vector5 K, T; + K << 1, k1_, k2_, k3_, k4_; + T << 1, t2, t4, t6, t8; + const double scaling = Scaling(r); + const double s = scaling * K.dot(T); + const double xd = s * xi, yd = s * yi; Point2 uv(fx_ * xd + s_ * yd + u0_, fy_ * yd + v0_); Matrix2 DK; if (H1 || H2) DK << fx_, s_, 0.0, fy_; // Derivative for calibration parameters (2 by 9) - if (H1) - *H1 = D2dcalibration(xd, yd, xi, yi, t * tt, t * t4, t * t6, t * t8, r, DK); + if (H1) { + Matrix25 DR1; + // order: fx, fy, s, u0, v0 + DR1 << xd, 0.0, yd, 1.0, 0.0, 0.0, yd, 0.0, 0.0, 1.0; + + // order: k1, k2, k3, k4 + Matrix24 DR2; + auto T4 = T.tail<4>().transpose(); + DR2 << xi * T4, yi * T4; + *H1 << DR1, DK * scaling * DR2; + } // Derivative for points in intrinsic coords (2 by 2) - if (H2) - *H2 = - D2dintrinsic(xi, yi, r, td, t, tt, t4, t6, t8, k1_, k2_, k3_, k4_, DK); + if (H2) { + const double dtd_dt = + 1 + 3 * k1_ * t2 + 5 * k2_ * t4 + 7 * k3_ * t6 + 9 * k4_ * t8; + const double dt_dr = 1 / (1 + r2); + const double rinv = 1 / r; + const double dr_dxi = xi * rinv; + const double dr_dyi = yi * rinv; + const double dtd_dxi = dtd_dt * dt_dr * dr_dxi; + const double dtd_dyi = dtd_dt * dt_dr * dr_dyi; + + const double td = t * K.dot(T); + const double rrinv = 1 / r2; + const double dxd_dxi = + dtd_dxi * dr_dxi + td * rinv - td * xi * rrinv * dr_dxi; + const double dxd_dyi = dtd_dyi * dr_dxi - td * xi * rrinv * dr_dyi; + const double dyd_dxi = dtd_dxi * dr_dyi - td * yi * rrinv * dr_dxi; + const double dyd_dyi = + dtd_dyi * dr_dyi + td * rinv - td * yi * rrinv * dr_dyi; + + Matrix2 DR; + DR << dxd_dxi, dxd_dyi, dyd_dxi, dyd_dyi; + + *H2 = DK * DR; + } return uv; } @@ -157,39 +154,10 @@ Point2 Cal3Fisheye::calibrate(const Point2& uv, const double tol) const { return pi; } -/* ************************************************************************* */ -Matrix2 Cal3Fisheye::D2d_intrinsic(const Point2& p) const { - const double xi = p.x(), yi = p.y(); - const double r = sqrt(xi * xi + yi * yi); - const double t = atan(r); - const double tt = t * t, t4 = tt * tt, t6 = t4 * tt, t8 = t4 * t4; - const double td = t * (1 + k1_ * tt + k2_ * t4 + k3_ * t6 + k4_ * t8); - - Matrix2 DK; - DK << fx_, s_, 0.0, fy_; - - return D2dintrinsic(xi, yi, r, td, t, tt, t4, t6, t8, k1_, k2_, k3_, k4_, DK); -} - -/* ************************************************************************* */ -Matrix29 Cal3Fisheye::D2d_calibration(const Point2& p) const { - const double xi = p.x(), yi = p.y(); - const double r = sqrt(xi * xi + yi * yi); - const double t = atan(r); - const double tt = t * t, t4 = tt * tt, t6 = tt * t4, t8 = t4 * t4; - const double td = t * (1 + k1_ * tt + k2_ * t4 + k3_ * t6 + k4_ * t8); - const double xd = td / r * xi, yd = td / r * yi; - - Matrix2 DK; - DK << fx_, s_, 0.0, fy_; - return D2dcalibration(xd, yd, xi, yi, t * tt, t * t4, t * t6, t * t8, r, DK); -} - /* ************************************************************************* */ void Cal3Fisheye::print(const std::string& s_) const { gtsam::print((Matrix)K(), s_ + ".K"); gtsam::print(Vector(k()), s_ + ".k"); - ; } /* ************************************************************************* */ diff --git a/gtsam/geometry/Cal3Fisheye.h b/gtsam/geometry/Cal3Fisheye.h index 5fb196047..e24fe074f 100644 --- a/gtsam/geometry/Cal3Fisheye.h +++ b/gtsam/geometry/Cal3Fisheye.h @@ -20,6 +20,8 @@ #include +#include + namespace gtsam { /** @@ -43,7 +45,7 @@ namespace gtsam { * [u; v; 1] = K*[x_d; y_d; 1] */ class GTSAM_EXPORT Cal3Fisheye { - protected: + private: double fx_, fy_, s_, u0_, v0_; // focal length, skew and principal point double k1_, k2_, k3_, k4_; // fisheye distortion coefficients @@ -78,7 +80,7 @@ class GTSAM_EXPORT Cal3Fisheye { /// @name Advanced Constructors /// @{ - Cal3Fisheye(const Vector& v); + explicit Cal3Fisheye(const Vector9& v); /// @} /// @name Standard Interface @@ -120,6 +122,9 @@ class GTSAM_EXPORT Cal3Fisheye { /// Return all parameters as a vector Vector9 vector() const; + /// Helper function that calculates atan(r)/r + static double Scaling(double r); + /** * @brief convert intrinsic coordinates [x_i; y_i] to (distorted) image * coordinates [u; v] @@ -136,13 +141,6 @@ class GTSAM_EXPORT Cal3Fisheye { /// y_i] Point2 calibrate(const Point2& p, const double tol = 1e-5) const; - /// Derivative of uncalibrate wrpt intrinsic coordinates [x_i; y_i] - Matrix2 D2d_intrinsic(const Point2& p) const; - - /// Derivative of uncalibrate wrpt the calibration parameters - /// [fx, fy, s, u0, v0, k1, k2, k3, k4] - Matrix29 D2d_calibration(const Point2& p) const; - /// @} /// @name Testable /// @{ From 4f07aeb8595b9d21b8ce1ce7726e14703be065c0 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 10 May 2020 13:40:37 -0400 Subject: [PATCH 020/199] Re-ordered and cleaned up tests, added derivative tests for image center --- gtsam/geometry/tests/testCal3DFisheye.cpp | 129 ++++++++++------------ 1 file changed, 56 insertions(+), 73 deletions(-) diff --git a/gtsam/geometry/tests/testCal3DFisheye.cpp b/gtsam/geometry/tests/testCal3DFisheye.cpp index 9203b5438..9317fb737 100644 --- a/gtsam/geometry/tests/testCal3DFisheye.cpp +++ b/gtsam/geometry/tests/testCal3DFisheye.cpp @@ -10,17 +10,18 @@ * -------------------------------------------------------------------------- */ /** - * @file testCal3Fisheye.cpp + * @file testCal3DFisheye.cpp * @brief Unit tests for fisheye calibration class * @author ghaggin */ -#include #include #include #include #include +#include + using namespace gtsam; GTSAM_CONCEPT_TESTABLE_INST(Cal3Fisheye) @@ -30,12 +31,27 @@ static const double fx = 250, fy = 260, s = 0.1, u0 = 320, v0 = 240; static Cal3Fisheye K(fx, fy, s, u0, v0, -0.013721808247486035, 0.020727425669427896, -0.012786476702685545, 0.0025242267320687625); -static Point2 p(2, 3); +static Point2 kTestPoint2(2, 3); + +/* ************************************************************************* */ +TEST(Cal3Fisheye, assert_equal) { CHECK(assert_equal(K, K, 1e-5)); } + +/* ************************************************************************* */ +TEST(Cal3Fisheye, retract) { + Cal3Fisheye expected(K.fx() + 1, K.fy() + 2, K.skew() + 3, K.px() + 4, + K.py() + 5, K.k1() + 6, K.k2() + 7, K.k3() + 8, + K.k4() + 9); + Vector d(9); + d << 1, 2, 3, 4, 5, 6, 7, 8, 9; + Cal3Fisheye actual = K.retract(d); + CHECK(assert_equal(expected, actual, 1e-7)); + CHECK(assert_equal(d, K.localCoordinates(actual), 1e-7)); +} /* ************************************************************************* */ TEST(Cal3Fisheye, uncalibrate1) { // Calculate the solution - const double xi = p.x(), yi = p.y(); + const double xi = kTestPoint2.x(), yi = kTestPoint2.y(); const double r = sqrt(xi * xi + yi * yi); const double t = atan(r); const double tt = t * t, t4 = tt * tt, t6 = tt * t4, t8 = t4 * t4; @@ -46,32 +62,42 @@ TEST(Cal3Fisheye, uncalibrate1) { Point2 uv_sol(v[0] / v[2], v[1] / v[2]); - Point2 uv = K.uncalibrate(p); + Point2 uv = K.uncalibrate(kTestPoint2); CHECK(assert_equal(uv, uv_sol)); } /* ************************************************************************* */ -/** - * Check that a point at (0,0) projects to the - * image center. - */ -TEST(Cal3Fisheye, uncalibrate2) { - Point2 pz(0, 0); - auto uv = K.uncalibrate(pz); - CHECK(assert_equal(uv, Point2(u0, v0))); +// For numerical derivatives +Point2 f(const Cal3Fisheye& k, const Point2& pt) { return k.uncalibrate(pt); } + +/* ************************************************************************* */ +TEST(Cal3Fisheye, Derivatives) { + Matrix H1, H2; + K.uncalibrate(kTestPoint2, H1, H2); + CHECK(assert_equal(numericalDerivative21(f, K, kTestPoint2, 1e-7), H1, 1e-5)); + CHECK(assert_equal(numericalDerivative22(f, K, kTestPoint2, 1e-7), H2, 1e-5)); } /* ************************************************************************* */ -/** - * This test uses cv2::fisheye::projectPoints to test that uncalibrate - * properly projects a point into the image plane. One notable difference - * between opencv and the Cal3Fisheye::uncalibrate function is the skew - * parameter. The equivalence is alpha = s/fx. - * - * - * Python script to project points with fisheye model in OpenCv - * (script run with OpenCv version 4.2.0 and Numpy version 1.18.2) - */ +// Check that a point at (0,0) projects to the image center. +TEST(Cal3Fisheye, uncalibrate2) { + Point2 pz(0, 0); + Matrix H1, H2; + auto uv = K.uncalibrate(pz, H1, H2); + CHECK(assert_equal(uv, Point2(u0, v0))); + CHECK(assert_equal(numericalDerivative21(f, K, pz, 1e-7), H1, 1e-5)); + // TODO(frank): the second jacobian is all NaN for the image center! + // CHECK(assert_equal(numericalDerivative22(f, K, pz, 1e-7), H2, 1e-5)); +} + +/* ************************************************************************* */ +// This test uses cv2::fisheye::projectPoints to test that uncalibrate +// properly projects a point into the image plane. One notable difference +// between opencv and the Cal3Fisheye::uncalibrate function is the skew +// parameter. The equivalence is alpha = s/fx. +// +// Python script to project points with fisheye model in OpenCv +// (script run with OpenCv version 4.2.0 and Numpy version 1.18.2) // clang-format off /* =========================================================== @@ -94,6 +120,7 @@ tvec = np.float64([[0.,0.,0.]]); imagePoints, jacobian = cv2.fisheye.projectPoints(objpts, rvec, tvec, cameraMatrix, distCoeffs, alpha=alpha) np.set_printoptions(precision=14) print(imagePoints) + =========================================================== * Script output: [[[457.82638130304935 408.18905848512986]]] */ @@ -134,21 +161,18 @@ TEST(Cal3Fisheye, calibrate1) { } /* ************************************************************************* */ -/** - * Check that calibrate returns (0,0) for the image center - */ +// Check that calibrate returns (0,0) for the image center TEST(Cal3Fisheye, calibrate2) { Point2 uv(u0, v0); auto xi_hat = K.calibrate(uv); CHECK(assert_equal(xi_hat, Point2(0, 0))) } -/** - * Run calibrate on OpenCv test from uncalibrate3 - * (script shown above) - * 3d point: (23, 27, 31) - * 2d point in image plane: (457.82638130304935, 408.18905848512986) - */ +/* ************************************************************************* */ +// Run calibrate on OpenCv test from uncalibrate3 +// (script shown above) +// 3d point: (23, 27, 31) +// 2d point in image plane: (457.82638130304935, 408.18905848512986) TEST(Cal3Fisheye, calibrate3) { Point3 p3(23, 27, 31); Point2 xi(p3.x() / p3.z(), p3.y() / p3.z()); @@ -157,47 +181,6 @@ TEST(Cal3Fisheye, calibrate3) { CHECK(assert_equal(xi_hat, xi)); } -/* ************************************************************************* */ -// For numerical derivatives -Point2 uncalibrate_(const Cal3Fisheye& k, const Point2& pt) { - return k.uncalibrate(pt); -} - -/* ************************************************************************* */ -TEST(Cal3Fisheye, Duncalibrate1) { - Matrix computed; - K.uncalibrate(p, computed, boost::none); - Matrix numerical = numericalDerivative21(uncalibrate_, K, p, 1e-7); - CHECK(assert_equal(numerical, computed, 1e-5)); - Matrix separate = K.D2d_calibration(p); - CHECK(assert_equal(numerical, separate, 1e-5)); -} - -/* ************************************************************************* */ -TEST(Cal3Fisheye, Duncalibrate2) { - Matrix computed; - K.uncalibrate(p, boost::none, computed); - Matrix numerical = numericalDerivative22(uncalibrate_, K, p, 1e-7); - CHECK(assert_equal(numerical, computed, 1e-5)); - Matrix separate = K.D2d_intrinsic(p); - CHECK(assert_equal(numerical, separate, 1e-5)); -} - -/* ************************************************************************* */ -TEST(Cal3Fisheye, assert_equal) { CHECK(assert_equal(K, K, 1e-5)); } - -/* ************************************************************************* */ -TEST(Cal3Fisheye, retract) { - Cal3Fisheye expected(K.fx() + 1, K.fy() + 2, K.skew() + 3, K.px() + 4, - K.py() + 5, K.k1() + 6, K.k2() + 7, K.k3() + 8, - K.k4() + 9); - Vector d(9); - d << 1, 2, 3, 4, 5, 6, 7, 8, 9; - Cal3Fisheye actual = K.retract(d); - CHECK(assert_equal(expected, actual, 1e-7)); - CHECK(assert_equal(d, K.localCoordinates(actual), 1e-7)); -} - /* ************************************************************************* */ int main() { TestResult tr; From 5abe293cdf48bc47c76938ed71512cd296abec4d Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 7 Mar 2020 20:57:08 -0500 Subject: [PATCH 021/199] Setup and simulateMeasurements --- tests/testTranslationRecovery.cpp | 126 ++++++++++++++++++++++++++++++ 1 file changed, 126 insertions(+) create mode 100644 tests/testTranslationRecovery.cpp diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp new file mode 100644 index 000000000..45c882cc9 --- /dev/null +++ b/tests/testTranslationRecovery.cpp @@ -0,0 +1,126 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testTranslationRecovery.cpp + * @author Frank Dellaert + * @date March 2020 + * @brief test recovering translations when rotations are given. + */ + +#include +// #include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +class TranslationFactor {}; + +// Set up an optimization problem for the unknown translations Ti in the world +// coordinate frame, given the known camera attitudes wRi with respect to the +// world frame, and a set of (noisy) translation directions of type Unit3, +// aZb. The measurement equation is +// aZb = Unit3(aRw * (Tb - Ta)) (1) +// i.e., aZb is the normalized translation of B's origin in the camera frame A. +// It is clear that we cannot recover the scale, nor the absolute position, so +// the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing +// the translations Ta and Tb associated with the first measurement aZb, +// clamping them to their initial values as given to this method. If no initial +// values are given, we use the origin for Tb and set Tb to make (1) come +// through, i.e., +// Tb = s * wRa * Point3(aZb) (2) +// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two +// versions are supplied below corresponding to whether we have initial values +// or not. Because the latter one is called from the first one, this is prime. + +void recoverTranslations(const double scale = 1.0) { + // graph.emplace_shared(m.second, unit2, m.first, + // P(j)); +} + +using KeyPair = pair; + +/** + * @brief Simulate translation direction measurements + * + * @param poses SE(3) ground truth poses stored as Values + * @param edges pairs (a,b) for which a measurement aZb will be generated. + */ +vector simulateMeasurements(const Values& poses, + const vector& edges) { + vector measurements; + for (auto edge : edges) { + Key a, b; + std::tie(a, b) = edge; + Pose3 wTa = poses.at(a), wTb = poses.at(b); + Point3 Ta = wTa.translation(), Tb = wTb.translation(); + auto aRw = wTa.rotation().inverse(); + Unit3 aZb = Unit3(aRw * (Tb - Ta)); + measurements.push_back(aZb); + } + return measurements; +} + +/* ************************************************************************* */ +// We read the BAL file, which has 3 cameras in it, with poses. We then assume +// the rotations are correct, but translations have to be estimated from +// translation directions only. Since we have 3 cameras, A, B, and C, we can at +// most create three relative measurements, let's call them aZb, aZc, and bZc. +// These will be of type Unit3. We then call `recoverTranslations` which sets up +// an optimization problem for the three unknown translations. +TEST(TranslationRecovery, BAL) { + string filename = findExampleDataFile("dubrovnik-3-7-pre"); + SfM_data db; + bool success = readBAL(filename, db); + if (!success) throw runtime_error("Could not access file!"); + + SharedNoiseModel unit2 = noiseModel::Unit::Create(2); + NonlinearFactorGraph graph; + + size_t i = 0; + Values poses; + for (auto camera : db.cameras) { + GTSAM_PRINT(camera); + poses.insert(i++, camera.pose()); + } + Pose3 wTa = poses.at(0), wTb = poses.at(1), + wTc = poses.at(2); + Point3 Ta = wTa.translation(), Tb = wTb.translation(), Tc = wTc.translation(); + auto measurements = simulateMeasurements(poses, {{0, 1}, {0, 2}, {1, 2}}); + auto aRw = wTa.rotation().inverse(); + Unit3 aZb = measurements[0]; + EXPECT(assert_equal(Unit3(aRw * (Tb - Ta)), aZb)); + Unit3 aZc = measurements[1]; + EXPECT(assert_equal(Unit3(aRw * (Tc - Ta)), aZc)); + // Values initial = initialCamerasAndPointsEstimate(db); + + // LevenbergMarquardtOptimizer lm(graph, initial); + + // Values actual = lm.optimize(); + // double actualError = graph.error(actual); + // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 146f411a99df7d82648f0c1ebbeb27833f11f041 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 01:45:04 -0500 Subject: [PATCH 022/199] Built TranslationFactor class and partially completed TranslationRecovery class --- tests/testTranslationRecovery.cpp | 323 +++++++++++++++++++++++------- 1 file changed, 246 insertions(+), 77 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 45c882cc9..330a507e5 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -1,3 +1,211 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file TranslationFactor.h + * @author Frank Dellaert + * @date March 2020 + * @brief Binary factor for a relative translation direction measurement. + */ + +#include +#include +#include +#include + +namespace gtsam { + +/** + * Binary factor for a relative translation direction measurement + * w_aZb. The measurement equation is + * w_aZb = Unit3(Tb - Ta) + * i.e., w_aZb is the translation direction from frame A to B, in world + * coordinates. Although Unit3 instances live on a manifold, following + * Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the + * ambient world coordinate frame: + * normalized(Tb - Ta) - w_aZb.point3() + * + * @addtogroup SAM + */ +class TranslationFactor : public NoiseModelFactor2 { + private: + typedef NoiseModelFactor2 Base; + Point3 measured_w_aZb_; + + public: + /// default constructor + TranslationFactor() {} + + TranslationFactor(Key a, Key b, const Unit3& w_aZb, + const SharedNoiseModel& noiseModel) + : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {} + + /** + * @brief Caclulate error norm(p1-p2) - measured + * + * @param Ta translation for key a + * @param Tb translation for key b + * @param H1 optional jacobian in Ta + * @param H2 optional jacobian in Tb + * @return * Vector + */ + Vector evaluateError( + const Point3& Ta, const Point3& Tb, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const override { + const Point3 dir = Tb - Ta; + Matrix33 H_predicted_dir; + const Point3 predicted = + dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); + if (H1) *H1 = H_predicted_dir; + if (H2) *H2 = -H_predicted_dir; + return predicted - measured_w_aZb_; + } + + private: + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "Base", boost::serialization::base_object(*this)); + } +}; // \ TranslationFactor +} // namespace gtsam + +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file TranslationRecovery.h + * @author Frank Dellaert + * @date March 2020 + * @brief test recovering translations when rotations are given. + */ + +// #include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace gtsam { + +// Set up an optimization problem for the unknown translations Ti in the world +// coordinate frame, given the known camera attitudes wRi with respect to the +// world frame, and a set of (noisy) translation directions of type Unit3, +// w_aZb. The measurement equation is +// w_aZb = Unit3(Tb - Ta) (1) +// i.e., w_aZb is the translation direction from frame A to B, in world +// coordinates. Although Unit3 instances live on a manifold, following +// Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the +// ambient world coordinate frame. +// +// It is clear that we cannot recover the scale, nor the absolute position, +// so the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing +// the translations Ta and Tb associated with the first measurement w_aZb, +// clamping them to their initial values as given to this method. If no initial +// values are given, we use the origin for Tb and set Tb to make (1) come +// through, i.e., +// Tb = s * wRa * Point3(w_aZb) (2) +// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two +// versions are supplied below corresponding to whether we have initial values +// or not. Because the latter one is called from the first one, this is prime. + +class TranslationRecovery { + public: + using KeyPair = std::pair; + using TranslationEdges = std::map; + + private: + TranslationEdges relativeTranslations_; + + public: + /** + * @brief Construct a new Translation Recovery object + * + * @param relativeTranslations the relative translations, in world coordinate + * frames, indexed in a map by a pair of Pose keys. + */ + TranslationRecovery(const TranslationEdges& relativeTranslations) + : relativeTranslations_(relativeTranslations) {} + + /** + * @brief Build the factor graph to do the optimization. + * + * @return NonlinearFactorGraph + */ + NonlinearFactorGraph buildGraph() const { + auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + NonlinearFactorGraph graph; + for (auto edge : relativeTranslations_) { + Key a, b; + std::tie(a, b) = edge.first; + const Unit3 w_aZb = edge.second; + graph.emplace_shared(a, b, w_aZb, noiseModel); + } + return graph; + } + + /** + * @brief Build and optimize factor graph. + * + * @param scale scale for first relative translation which fixes gauge. + * @return Values + */ + Values run(const double scale = 1.0) const { + const auto graph = buildGraph(); + // Values initial = randomTranslations(); + + // LevenbergMarquardtOptimizer lm(graph, initial); + + Values result; // = lm.optimize(); + + return result; + } + + /** + * @brief Simulate translation direction measurements + * + * @param poses SE(3) ground truth poses stored as Values + * @param edges pairs (a,b) for which a measurement w_aZb will be generated. + */ + static TranslationEdges SimulateMeasurements( + const Values& poses, const std::vector& edges) { + TranslationEdges relativeTranslations; + for (auto edge : edges) { + Key a, b; + std::tie(a, b) = edge; + const Pose3 wTa = poses.at(a), wTb = poses.at(b); + const Point3 Ta = wTa.translation(), Tb = wTb.translation(); + const Unit3 w_aZb(Tb - Ta); + relativeTranslations[edge] = w_aZb; + } + return relativeTranslations; + } +}; +} // namespace gtsam + /* ---------------------------------------------------------------------------- * GTSAM Copyright 2010, Georgia Tech Research Corporation, @@ -16,100 +224,61 @@ * @brief test recovering translations when rotations are given. */ -#include -// #include -#include -#include -#include -#include -#include -#include -#include - #include +#include using namespace std; using namespace gtsam; -class TranslationFactor {}; - -// Set up an optimization problem for the unknown translations Ti in the world -// coordinate frame, given the known camera attitudes wRi with respect to the -// world frame, and a set of (noisy) translation directions of type Unit3, -// aZb. The measurement equation is -// aZb = Unit3(aRw * (Tb - Ta)) (1) -// i.e., aZb is the normalized translation of B's origin in the camera frame A. -// It is clear that we cannot recover the scale, nor the absolute position, so -// the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing -// the translations Ta and Tb associated with the first measurement aZb, -// clamping them to their initial values as given to this method. If no initial -// values are given, we use the origin for Tb and set Tb to make (1) come -// through, i.e., -// Tb = s * wRa * Point3(aZb) (2) -// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two -// versions are supplied below corresponding to whether we have initial values -// or not. Because the latter one is called from the first one, this is prime. - -void recoverTranslations(const double scale = 1.0) { - // graph.emplace_shared(m.second, unit2, m.first, - // P(j)); -} - -using KeyPair = pair; - -/** - * @brief Simulate translation direction measurements - * - * @param poses SE(3) ground truth poses stored as Values - * @param edges pairs (a,b) for which a measurement aZb will be generated. - */ -vector simulateMeasurements(const Values& poses, - const vector& edges) { - vector measurements; - for (auto edge : edges) { - Key a, b; - std::tie(a, b) = edge; - Pose3 wTa = poses.at(a), wTb = poses.at(b); - Point3 Ta = wTa.translation(), Tb = wTb.translation(); - auto aRw = wTa.rotation().inverse(); - Unit3 aZb = Unit3(aRw * (Tb - Ta)); - measurements.push_back(aZb); - } - return measurements; -} - /* ************************************************************************* */ // We read the BAL file, which has 3 cameras in it, with poses. We then assume // the rotations are correct, but translations have to be estimated from // translation directions only. Since we have 3 cameras, A, B, and C, we can at -// most create three relative measurements, let's call them aZb, aZc, and bZc. -// These will be of type Unit3. We then call `recoverTranslations` which sets up -// an optimization problem for the three unknown translations. +// most create three relative measurements, let's call them w_aZb, w_aZc, and +// bZc. These will be of type Unit3. We then call `recoverTranslations` which +// sets up an optimization problem for the three unknown translations. TEST(TranslationRecovery, BAL) { - string filename = findExampleDataFile("dubrovnik-3-7-pre"); + const string filename = findExampleDataFile("dubrovnik-3-7-pre"); SfM_data db; bool success = readBAL(filename, db); if (!success) throw runtime_error("Could not access file!"); - SharedNoiseModel unit2 = noiseModel::Unit::Create(2); - NonlinearFactorGraph graph; - - size_t i = 0; + // Get camera poses, as Values + size_t j = 0; Values poses; for (auto camera : db.cameras) { - GTSAM_PRINT(camera); - poses.insert(i++, camera.pose()); + poses.insert(j++, camera.pose()); } - Pose3 wTa = poses.at(0), wTb = poses.at(1), - wTc = poses.at(2); - Point3 Ta = wTa.translation(), Tb = wTb.translation(), Tc = wTc.translation(); - auto measurements = simulateMeasurements(poses, {{0, 1}, {0, 2}, {1, 2}}); - auto aRw = wTa.rotation().inverse(); - Unit3 aZb = measurements[0]; - EXPECT(assert_equal(Unit3(aRw * (Tb - Ta)), aZb)); - Unit3 aZc = measurements[1]; - EXPECT(assert_equal(Unit3(aRw * (Tc - Ta)), aZc)); - // Values initial = initialCamerasAndPointsEstimate(db); + + // Simulate measurements + const auto relativeTranslations = TranslationRecovery::SimulateMeasurements( + poses, {{0, 1}, {0, 2}, {1, 2}}); + + // Check + const Pose3 wTa = poses.at(0), wTb = poses.at(1), + wTc = poses.at(2); + const Point3 Ta = wTa.translation(), Tb = wTb.translation(), + Tc = wTc.translation(); + const Rot3 aRw = wTa.rotation().inverse(); + const Unit3 w_aZb = relativeTranslations.at({0, 1}); + EXPECT(assert_equal(Unit3(Tb - Ta), w_aZb)); + const Unit3 w_aZc = relativeTranslations.at({0, 2}); + EXPECT(assert_equal(Unit3(Tc - Ta), w_aZc)); + + TranslationRecovery algorithm(relativeTranslations); + const auto graph = algorithm.buildGraph(); + EXPECT_LONGS_EQUAL(3, graph.size()); + + // Translation recovery, version 1 + const auto result = algorithm.run(2); + + // Check result + // Pose3 expected0(wTa.rotation(), Point3(0, 0, 0)); + // EXPECT(assert_equal(expected0, result.at(0))); + // Pose3 expected1(wTb.rotation(), 2 * w_aZb.point3()); + // EXPECT(assert_equal(expected1, result.at(1))); + + // Values initial = randomTranslations(); // LevenbergMarquardtOptimizer lm(graph, initial); From d8f3ca46a4966f0c13250caa929de74fb441966f Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 01:58:22 -0500 Subject: [PATCH 023/199] Added initalizeRandomly --- tests/testTranslationRecovery.cpp | 29 ++++++++++++++++++++++++++--- 1 file changed, 26 insertions(+), 3 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 330a507e5..f513184e3 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -167,6 +167,29 @@ class TranslationRecovery { return graph; } + /** + * @brief Create random initial translations. + * + * @return Values + */ + Values initalizeRandomly() const { + Values initial; + auto insert = [&initial](Key j) { + if (!initial.exists(j)) { + initial.insert(j, Vector3::Random()); + } + }; + + // Loop over measurements and add a random translation + for (auto edge : relativeTranslations_) { + Key a, b; + std::tie(a, b) = edge.first; + insert(a); + insert(b); + } + return initial; + } + /** * @brief Build and optimize factor graph. * @@ -175,11 +198,11 @@ class TranslationRecovery { */ Values run(const double scale = 1.0) const { const auto graph = buildGraph(); - // Values initial = randomTranslations(); + const Values initial = initalizeRandomly(); - // LevenbergMarquardtOptimizer lm(graph, initial); + LevenbergMarquardtOptimizer lm(graph, initial); - Values result; // = lm.optimize(); + Values result = lm.optimize(); return result; } From 652302f5ad6d868c6c339bb4e76ae6b4f9c9ea22 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 03:05:38 -0400 Subject: [PATCH 024/199] Running optimization --- tests/testTranslationRecovery.cpp | 21 ++++++++------------- 1 file changed, 8 insertions(+), 13 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index f513184e3..bd8a81f20 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -200,8 +200,9 @@ class TranslationRecovery { const auto graph = buildGraph(); const Values initial = initalizeRandomly(); - LevenbergMarquardtOptimizer lm(graph, initial); - + LevenbergMarquardtParams params; + params.setVerbosityLM("Summary"); + LevenbergMarquardtOptimizer lm(graph, initial, params); Values result = lm.optimize(); return result; @@ -296,18 +297,12 @@ TEST(TranslationRecovery, BAL) { const auto result = algorithm.run(2); // Check result - // Pose3 expected0(wTa.rotation(), Point3(0, 0, 0)); - // EXPECT(assert_equal(expected0, result.at(0))); - // Pose3 expected1(wTb.rotation(), 2 * w_aZb.point3()); - // EXPECT(assert_equal(expected1, result.at(1))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); + EXPECT(assert_equal(Point3(2 * w_aZb.point3()), result.at(1))); + EXPECT(assert_equal(Point3(0, 0, 0), result.at(2))); - // Values initial = randomTranslations(); - - // LevenbergMarquardtOptimizer lm(graph, initial); - - // Values actual = lm.optimize(); - // double actualError = graph.error(actual); - // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); + // TODO(frank): how to get stats back + // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); } /* ************************************************************************* */ From 83a0f515875b666a9cdae1e4af1668d6ec737fc8 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 03:15:38 -0400 Subject: [PATCH 025/199] Moved TranslationFactor prototype into sfm directory --- gtsam/sfm/TranslationFactor.h | 83 ++++++++++++++++++++++++++++++ tests/testTranslationRecovery.cpp | 84 +------------------------------ 2 files changed, 84 insertions(+), 83 deletions(-) create mode 100644 gtsam/sfm/TranslationFactor.h diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h new file mode 100644 index 000000000..626214dcc --- /dev/null +++ b/gtsam/sfm/TranslationFactor.h @@ -0,0 +1,83 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +#pragma once + +/** + * @file TranslationFactor.h + * @author Frank Dellaert + * @date March 2020 + * @brief Binary factor for a relative translation direction measurement. + */ + +#include +#include +#include +#include + +namespace gtsam { + +/** + * Binary factor for a relative translation direction measurement + * w_aZb. The measurement equation is + * w_aZb = Unit3(Tb - Ta) + * i.e., w_aZb is the translation direction from frame A to B, in world + * coordinates. Although Unit3 instances live on a manifold, following + * Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the + * ambient world coordinate frame: + * normalized(Tb - Ta) - w_aZb.point3() + * + * @addtogroup SAM + */ +class TranslationFactor : public NoiseModelFactor2 { + private: + typedef NoiseModelFactor2 Base; + Point3 measured_w_aZb_; + + public: + /// default constructor + TranslationFactor() {} + + TranslationFactor(Key a, Key b, const Unit3& w_aZb, + const SharedNoiseModel& noiseModel) + : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {} + + /** + * @brief Caclulate error norm(p1-p2) - measured + * + * @param Ta translation for key a + * @param Tb translation for key b + * @param H1 optional jacobian in Ta + * @param H2 optional jacobian in Tb + * @return * Vector + */ + Vector evaluateError( + const Point3& Ta, const Point3& Tb, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const override { + const Point3 dir = Tb - Ta; + Matrix33 H_predicted_dir; + const Point3 predicted = + dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); + if (H1) *H1 = H_predicted_dir; + if (H2) *H2 = -H_predicted_dir; + return predicted - measured_w_aZb_; + } + + private: + friend class boost::serialization::access; + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "Base", boost::serialization::base_object(*this)); + } +}; // \ TranslationFactor +} // namespace gtsam diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index bd8a81f20..8742820f4 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -1,85 +1,3 @@ -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file TranslationFactor.h - * @author Frank Dellaert - * @date March 2020 - * @brief Binary factor for a relative translation direction measurement. - */ - -#include -#include -#include -#include - -namespace gtsam { - -/** - * Binary factor for a relative translation direction measurement - * w_aZb. The measurement equation is - * w_aZb = Unit3(Tb - Ta) - * i.e., w_aZb is the translation direction from frame A to B, in world - * coordinates. Although Unit3 instances live on a manifold, following - * Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the - * ambient world coordinate frame: - * normalized(Tb - Ta) - w_aZb.point3() - * - * @addtogroup SAM - */ -class TranslationFactor : public NoiseModelFactor2 { - private: - typedef NoiseModelFactor2 Base; - Point3 measured_w_aZb_; - - public: - /// default constructor - TranslationFactor() {} - - TranslationFactor(Key a, Key b, const Unit3& w_aZb, - const SharedNoiseModel& noiseModel) - : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {} - - /** - * @brief Caclulate error norm(p1-p2) - measured - * - * @param Ta translation for key a - * @param Tb translation for key b - * @param H1 optional jacobian in Ta - * @param H2 optional jacobian in Tb - * @return * Vector - */ - Vector evaluateError( - const Point3& Ta, const Point3& Tb, - boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const override { - const Point3 dir = Tb - Ta; - Matrix33 H_predicted_dir; - const Point3 predicted = - dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); - if (H1) *H1 = H_predicted_dir; - if (H2) *H2 = -H_predicted_dir; - return predicted - measured_w_aZb_; - } - - private: - friend class boost::serialization::access; - template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& boost::serialization::make_nvp( - "Base", boost::serialization::base_object(*this)); - } -}; // \ TranslationFactor -} // namespace gtsam - /* ---------------------------------------------------------------------------- * GTSAM Copyright 2010, Georgia Tech Research Corporation, @@ -98,7 +16,7 @@ class TranslationFactor : public NoiseModelFactor2 { * @brief test recovering translations when rotations are given. */ -// #include +#include #include #include #include From 656f4ad57725110f5f24d2ae51b1648f84773fa8 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 03:26:41 -0400 Subject: [PATCH 026/199] unit test, incl Jacobians --- gtsam/sfm/TranslationFactor.h | 6 +- gtsam/sfm/tests/testTranslationFactor.cpp | 90 +++++++++++++++++++++++ 2 files changed, 93 insertions(+), 3 deletions(-) create mode 100644 gtsam/sfm/tests/testTranslationFactor.cpp diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index 626214dcc..bf65b9bc8 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -35,7 +35,7 @@ namespace gtsam { * ambient world coordinate frame: * normalized(Tb - Ta) - w_aZb.point3() * - * @addtogroup SAM + * @addtogroup SFM */ class TranslationFactor : public NoiseModelFactor2 { private: @@ -67,8 +67,8 @@ class TranslationFactor : public NoiseModelFactor2 { Matrix33 H_predicted_dir; const Point3 predicted = dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); - if (H1) *H1 = H_predicted_dir; - if (H2) *H2 = -H_predicted_dir; + if (H1) *H1 = -H_predicted_dir; + if (H2) *H2 = H_predicted_dir; return predicted - measured_w_aZb_; } diff --git a/gtsam/sfm/tests/testTranslationFactor.cpp b/gtsam/sfm/tests/testTranslationFactor.cpp new file mode 100644 index 000000000..54928d684 --- /dev/null +++ b/gtsam/sfm/tests/testTranslationFactor.cpp @@ -0,0 +1,90 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file testTranslationFactor.cpp + * @brief Unit tests for TranslationFactor Class + * @author Frank dellaert + * @date March 2020 + */ + +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +// Create a noise model for the chordal error +static SharedNoiseModel model(noiseModel::Isotropic::Sigma(3, 0.05)); + +// Keys are deliberately *not* in sorted order to test that case. +static const Key kKey1(2), kKey2(1); +static const Unit3 kMeasured(1, 0, 0); + +/* ************************************************************************* */ +TEST(TranslationFactor, Constructor) { + TranslationFactor factor(kKey1, kKey2, kMeasured, model); +} + +/* ************************************************************************* */ +TEST(TranslationFactor, Error) { + // Create a factor + TranslationFactor factor(kKey1, kKey2, kMeasured, model); + + // Set the linearization + Point3 T1(1, 0, 0), T2(2, 0, 0); + + // Use the factor to calculate the error + Vector actualError(factor.evaluateError(T1, T2)); + + // Verify we get the expected error + Vector expected = (Vector3() << 0, 0, 0).finished(); + EXPECT(assert_equal(expected, actualError, 1e-9)); +} + +/* ************************************************************************* */ +Vector factorError(const Point3& T1, const Point3& T2, + const TranslationFactor& factor) { + return factor.evaluateError(T1, T2); +} + +TEST(TranslationFactor, Jacobian) { + // Create a factor + TranslationFactor factor(kKey1, kKey2, kMeasured, model); + + // Set the linearization + Point3 T1(1, 0, 0), T2(2, 0, 0); + + // Use the factor to calculate the Jacobians + Matrix H1Actual, H2Actual; + factor.evaluateError(T1, T2, H1Actual, H2Actual); + + // Use numerical derivatives to calculate the Jacobians + Matrix H1Expected, H2Expected; + H1Expected = numericalDerivative11( + boost::bind(&factorError, _1, T2, factor), T1); + H2Expected = numericalDerivative11( + boost::bind(&factorError, T1, _1, factor), T2); + + // Verify the Jacobians are correct + EXPECT(assert_equal(H1Expected, H1Actual, 1e-9)); + EXPECT(assert_equal(H2Expected, H2Actual, 1e-9)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 7910f00c2c6524a27aef5b513c18dd929d9625ca Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 03:50:45 -0400 Subject: [PATCH 027/199] Optimization works! --- tests/testTranslationRecovery.cpp | 49 +++++++++++++++++++++++-------- 1 file changed, 37 insertions(+), 12 deletions(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 8742820f4..94ee14c28 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -16,7 +16,6 @@ * @brief test recovering translations when rotations are given. */ -#include #include #include #include @@ -26,6 +25,8 @@ #include #include #include +#include +#include namespace gtsam { @@ -57,6 +58,7 @@ class TranslationRecovery { private: TranslationEdges relativeTranslations_; + LevenbergMarquardtParams params_; public: /** @@ -66,7 +68,9 @@ class TranslationRecovery { * frames, indexed in a map by a pair of Pose keys. */ TranslationRecovery(const TranslationEdges& relativeTranslations) - : relativeTranslations_(relativeTranslations) {} + : relativeTranslations_(relativeTranslations) { + params_.setVerbosityLM("Summary"); + } /** * @brief Build the factor graph to do the optimization. @@ -76,15 +80,35 @@ class TranslationRecovery { NonlinearFactorGraph buildGraph() const { auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); NonlinearFactorGraph graph; + + // Add all relative translation edges for (auto edge : relativeTranslations_) { Key a, b; std::tie(a, b) = edge.first; const Unit3 w_aZb = edge.second; graph.emplace_shared(a, b, w_aZb, noiseModel); } + return graph; } + /** + * @brief Add priors on ednpoints of first measurement edge. + * + * @param scale scale for first relative translation which fixes gauge. + * @param graph factor graph to which prior is added. + */ + void addPrior(const double scale, NonlinearFactorGraph* graph) const { + auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + auto edge = relativeTranslations_.begin(); + Key a, b; + std::tie(a, b) = edge->first; + const Unit3 w_aZb = edge->second; + graph->emplace_shared >(a, Point3(0, 0, 0), noiseModel); + graph->emplace_shared >(b, scale * w_aZb.point3(), + noiseModel); + } + /** * @brief Create random initial translations. * @@ -115,14 +139,11 @@ class TranslationRecovery { * @return Values */ Values run(const double scale = 1.0) const { - const auto graph = buildGraph(); + auto graph = buildGraph(); + addPrior(scale, &graph); const Values initial = initalizeRandomly(); - - LevenbergMarquardtParams params; - params.setVerbosityLM("Summary"); - LevenbergMarquardtOptimizer lm(graph, initial, params); + LevenbergMarquardtOptimizer lm(graph, initial, params_); Values result = lm.optimize(); - return result; } @@ -212,14 +233,18 @@ TEST(TranslationRecovery, BAL) { EXPECT_LONGS_EQUAL(3, graph.size()); // Translation recovery, version 1 - const auto result = algorithm.run(2); + const double scale = 2.0; + const auto result = algorithm.run(scale); - // Check result + // Check result for first two translations, determined by prior EXPECT(assert_equal(Point3(0, 0, 0), result.at(0))); EXPECT(assert_equal(Point3(2 * w_aZb.point3()), result.at(1))); - EXPECT(assert_equal(Point3(0, 0, 0), result.at(2))); - // TODO(frank): how to get stats back + // Check that the third translations is correct + Point3 expected = (Tc - Ta) * (scale / (Tb - Ta).norm()); + EXPECT(assert_equal(expected, result.at(2), 1e-4)); + + // TODO(frank): how to get stats back? // EXPECT_DOUBLES_EQUAL(0.0199833, actualError, 1e-5); } From f4b2b8bde0590c0c431f9eaba87ba9f1d73e98a0 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 04:04:21 -0400 Subject: [PATCH 028/199] copyright 2020 --- gtsam/sfm/TranslationFactor.h | 2 +- gtsam/sfm/tests/testTranslationFactor.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index bf65b9bc8..584b1fa69 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) diff --git a/gtsam/sfm/tests/testTranslationFactor.cpp b/gtsam/sfm/tests/testTranslationFactor.cpp index 54928d684..da284bfd6 100644 --- a/gtsam/sfm/tests/testTranslationFactor.cpp +++ b/gtsam/sfm/tests/testTranslationFactor.cpp @@ -1,6 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) From 98b8d6b4f3f272ee952271329163a269344eccd4 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 8 Mar 2020 04:04:49 -0400 Subject: [PATCH 029/199] Move to its own compilation unit --- gtsam/sfm/TranslationRecovery.cpp | 103 ++++++++++++++++++ gtsam/sfm/TranslationRecovery.h | 108 ++++++++++++++++++ tests/testTranslationRecovery.cpp | 175 +----------------------------- 3 files changed, 214 insertions(+), 172 deletions(-) create mode 100644 gtsam/sfm/TranslationRecovery.cpp create mode 100644 gtsam/sfm/TranslationRecovery.h diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp new file mode 100644 index 000000000..a0f3eb6b6 --- /dev/null +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -0,0 +1,103 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file TranslationRecovery.h + * @author Frank Dellaert + * @date March 2020 + * @brief test recovering translations when rotations are given. + */ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace gtsam; +using namespace std; + +NonlinearFactorGraph TranslationRecovery::buildGraph() const { + auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + NonlinearFactorGraph graph; + + // Add all relative translation edges + for (auto edge : relativeTranslations_) { + Key a, b; + tie(a, b) = edge.first; + const Unit3 w_aZb = edge.second; + graph.emplace_shared(a, b, w_aZb, noiseModel); + } + + return graph; +} + +void TranslationRecovery::addPrior(const double scale, + NonlinearFactorGraph* graph) const { + auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); + auto edge = relativeTranslations_.begin(); + Key a, b; + tie(a, b) = edge->first; + const Unit3 w_aZb = edge->second; + graph->emplace_shared >(a, Point3(0, 0, 0), noiseModel); + graph->emplace_shared >(b, scale * w_aZb.point3(), + noiseModel); +} + +Values TranslationRecovery::initalizeRandomly() const { + // Create a lambda expression that checks whether value exists and randomly + // initializes if not. + Values initial; + auto insert = [&initial](Key j) { + if (!initial.exists(j)) { + initial.insert(j, Vector3::Random()); + } + }; + + // Loop over measurements and add a random translation + for (auto edge : relativeTranslations_) { + Key a, b; + tie(a, b) = edge.first; + insert(a); + insert(b); + } + return initial; +} + +Values TranslationRecovery::run(const double scale) const { + auto graph = buildGraph(); + addPrior(scale, &graph); + const Values initial = initalizeRandomly(); + LevenbergMarquardtOptimizer lm(graph, initial, params_); + Values result = lm.optimize(); + return result; +} + +TranslationRecovery::TranslationEdges TranslationRecovery::SimulateMeasurements( + const Values& poses, const vector& edges) { + TranslationEdges relativeTranslations; + for (auto edge : edges) { + Key a, b; + tie(a, b) = edge; + const Pose3 wTa = poses.at(a), wTb = poses.at(b); + const Point3 Ta = wTa.translation(), Tb = wTb.translation(); + const Unit3 w_aZb(Tb - Ta); + relativeTranslations[edge] = w_aZb; + } + return relativeTranslations; +} diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h new file mode 100644 index 000000000..5eea251cf --- /dev/null +++ b/gtsam/sfm/TranslationRecovery.h @@ -0,0 +1,108 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file TranslationRecovery.h + * @author Frank Dellaert + * @date March 2020 + * @brief test recovering translations when rotations are given. + */ + +#include +#include +#include + +#include +#include + +namespace gtsam { + +// Set up an optimization problem for the unknown translations Ti in the world +// coordinate frame, given the known camera attitudes wRi with respect to the +// world frame, and a set of (noisy) translation directions of type Unit3, +// w_aZb. The measurement equation is +// w_aZb = Unit3(Tb - Ta) (1) +// i.e., w_aZb is the translation direction from frame A to B, in world +// coordinates. Although Unit3 instances live on a manifold, following +// Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the +// ambient world coordinate frame. +// +// It is clear that we cannot recover the scale, nor the absolute position, +// so the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing +// the translations Ta and Tb associated with the first measurement w_aZb, +// clamping them to their initial values as given to this method. If no initial +// values are given, we use the origin for Tb and set Tb to make (1) come +// through, i.e., +// Tb = s * wRa * Point3(w_aZb) (2) +// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two +// versions are supplied below corresponding to whether we have initial values +// or not. +class TranslationRecovery { + public: + using KeyPair = std::pair; + using TranslationEdges = std::map; + + private: + TranslationEdges relativeTranslations_; + LevenbergMarquardtParams params_; + + public: + /** + * @brief Construct a new Translation Recovery object + * + * @param relativeTranslations the relative translations, in world coordinate + * frames, indexed in a map by a pair of Pose keys. + */ + TranslationRecovery(const TranslationEdges& relativeTranslations) + : relativeTranslations_(relativeTranslations) { + params_.setVerbosityLM("Summary"); + } + + /** + * @brief Build the factor graph to do the optimization. + * + * @return NonlinearFactorGraph + */ + NonlinearFactorGraph buildGraph() const; + + /** + * @brief Add priors on ednpoints of first measurement edge. + * + * @param scale scale for first relative translation which fixes gauge. + * @param graph factor graph to which prior is added. + */ + void addPrior(const double scale, NonlinearFactorGraph* graph) const; + + /** + * @brief Create random initial translations. + * + * @return Values + */ + Values initalizeRandomly() const; + + /** + * @brief Build and optimize factor graph. + * + * @param scale scale for first relative translation which fixes gauge. + * @return Values + */ + Values run(const double scale = 1.0) const; + + /** + * @brief Simulate translation direction measurements + * + * @param poses SE(3) ground truth poses stored as Values + * @param edges pairs (a,b) for which a measurement w_aZb will be generated. + */ + static TranslationEdges SimulateMeasurements( + const Values& poses, const std::vector& edges); +}; +} // namespace gtsam diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 94ee14c28..774a999e4 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -1,177 +1,6 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, - * Atlanta, Georgia 30332-0415 - * All Rights Reserved - * Authors: Frank Dellaert, et al. (see THANKS for the full author list) - - * See LICENSE for the license information - - * -------------------------------------------------------------------------- */ - -/** - * @file TranslationRecovery.h - * @author Frank Dellaert - * @date March 2020 - * @brief test recovering translations when rotations are given. - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -namespace gtsam { - -// Set up an optimization problem for the unknown translations Ti in the world -// coordinate frame, given the known camera attitudes wRi with respect to the -// world frame, and a set of (noisy) translation directions of type Unit3, -// w_aZb. The measurement equation is -// w_aZb = Unit3(Tb - Ta) (1) -// i.e., w_aZb is the translation direction from frame A to B, in world -// coordinates. Although Unit3 instances live on a manifold, following -// Wilson14eccv_1DSfM.pdf error we compute the *chordal distance* in the -// ambient world coordinate frame. -// -// It is clear that we cannot recover the scale, nor the absolute position, -// so the gauge freedom in this case is 3 + 1 = 4. We fix these by taking fixing -// the translations Ta and Tb associated with the first measurement w_aZb, -// clamping them to their initial values as given to this method. If no initial -// values are given, we use the origin for Tb and set Tb to make (1) come -// through, i.e., -// Tb = s * wRa * Point3(w_aZb) (2) -// where s is an arbitrary scale that can be supplied, default 1.0. Hence, two -// versions are supplied below corresponding to whether we have initial values -// or not. Because the latter one is called from the first one, this is prime. - -class TranslationRecovery { - public: - using KeyPair = std::pair; - using TranslationEdges = std::map; - - private: - TranslationEdges relativeTranslations_; - LevenbergMarquardtParams params_; - - public: - /** - * @brief Construct a new Translation Recovery object - * - * @param relativeTranslations the relative translations, in world coordinate - * frames, indexed in a map by a pair of Pose keys. - */ - TranslationRecovery(const TranslationEdges& relativeTranslations) - : relativeTranslations_(relativeTranslations) { - params_.setVerbosityLM("Summary"); - } - - /** - * @brief Build the factor graph to do the optimization. - * - * @return NonlinearFactorGraph - */ - NonlinearFactorGraph buildGraph() const { - auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); - NonlinearFactorGraph graph; - - // Add all relative translation edges - for (auto edge : relativeTranslations_) { - Key a, b; - std::tie(a, b) = edge.first; - const Unit3 w_aZb = edge.second; - graph.emplace_shared(a, b, w_aZb, noiseModel); - } - - return graph; - } - - /** - * @brief Add priors on ednpoints of first measurement edge. - * - * @param scale scale for first relative translation which fixes gauge. - * @param graph factor graph to which prior is added. - */ - void addPrior(const double scale, NonlinearFactorGraph* graph) const { - auto noiseModel = noiseModel::Isotropic::Sigma(3, 0.01); - auto edge = relativeTranslations_.begin(); - Key a, b; - std::tie(a, b) = edge->first; - const Unit3 w_aZb = edge->second; - graph->emplace_shared >(a, Point3(0, 0, 0), noiseModel); - graph->emplace_shared >(b, scale * w_aZb.point3(), - noiseModel); - } - - /** - * @brief Create random initial translations. - * - * @return Values - */ - Values initalizeRandomly() const { - Values initial; - auto insert = [&initial](Key j) { - if (!initial.exists(j)) { - initial.insert(j, Vector3::Random()); - } - }; - - // Loop over measurements and add a random translation - for (auto edge : relativeTranslations_) { - Key a, b; - std::tie(a, b) = edge.first; - insert(a); - insert(b); - } - return initial; - } - - /** - * @brief Build and optimize factor graph. - * - * @param scale scale for first relative translation which fixes gauge. - * @return Values - */ - Values run(const double scale = 1.0) const { - auto graph = buildGraph(); - addPrior(scale, &graph); - const Values initial = initalizeRandomly(); - LevenbergMarquardtOptimizer lm(graph, initial, params_); - Values result = lm.optimize(); - return result; - } - - /** - * @brief Simulate translation direction measurements - * - * @param poses SE(3) ground truth poses stored as Values - * @param edges pairs (a,b) for which a measurement w_aZb will be generated. - */ - static TranslationEdges SimulateMeasurements( - const Values& poses, const std::vector& edges) { - TranslationEdges relativeTranslations; - for (auto edge : edges) { - Key a, b; - std::tie(a, b) = edge; - const Pose3 wTa = poses.at(a), wTb = poses.at(b); - const Point3 Ta = wTa.translation(), Tb = wTb.translation(); - const Unit3 w_aZb(Tb - Ta); - relativeTranslations[edge] = w_aZb; - } - return relativeTranslations; - } -}; -} // namespace gtsam - -/* ---------------------------------------------------------------------------- - - * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved * Authors: Frank Dellaert, et al. (see THANKS for the full author list) @@ -187,6 +16,8 @@ class TranslationRecovery { * @brief test recovering translations when rotations are given. */ +#include + #include #include From 3a1653dd231d7983cd357761d4a785f6db5cd844 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Sun, 17 May 2020 15:44:11 -0400 Subject: [PATCH 030/199] Include corrupting noise param to parse3DFactors --- gtsam/slam/dataset.cpp | 17 +++++++++++++++-- gtsam/slam/dataset.h | 3 ++- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 052bb3343..83636eb1d 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -541,10 +541,18 @@ std::map parse3DPoses(const string& filename) { } /* ************************************************************************* */ -BetweenFactorPose3s parse3DFactors(const string& filename) { +BetweenFactorPose3s parse3DFactors(const string& filename, + const noiseModel::Diagonal::shared_ptr& corruptingNoise) { ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); + // If asked, create a sampler with random number generator + Sampler sampler; + if (corruptingNoise) { + sampler = Sampler(corruptingNoise); + } + + std::vector::shared_ptr> factors; while (!is.eof()) { char buf[LINESIZE]; @@ -585,8 +593,13 @@ BetweenFactorPose3s parse3DFactors(const string& filename) { mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); + auto R12 = Rot3::Quaternion(qw, qx, qy, qz); + if (corruptingNoise) { + R12 = R12.retract(sampler.sample()); + } + factors.emplace_back(new BetweenFactor( - id1, id2, Pose3(Rot3::Quaternion(qw, qx, qy, qz), {x, y, z}), model)); + id1, id2, Pose3(R12, {x, y, z}), model)); } } return factors; diff --git a/gtsam/slam/dataset.h b/gtsam/slam/dataset.h index 3ab199bab..032799429 100644 --- a/gtsam/slam/dataset.h +++ b/gtsam/slam/dataset.h @@ -159,7 +159,8 @@ GTSAM_EXPORT void writeG2o(const NonlinearFactorGraph& graph, /// Parse edges in 3D TORO graph file into a set of BetweenFactors. using BetweenFactorPose3s = std::vector::shared_ptr>; -GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename); +GTSAM_EXPORT BetweenFactorPose3s parse3DFactors(const std::string& filename, + const noiseModel::Diagonal::shared_ptr& corruptingNoise=nullptr); /// Parse vertices in 3D TORO graph file into a map of Pose3s. GTSAM_EXPORT std::map parse3DPoses(const std::string& filename); From 9fc090165524f094ba93393440ecbc9dbdc8c483 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 18 May 2020 08:30:00 +0200 Subject: [PATCH 031/199] more precise use of setZero() and add comments --- gtsam/base/SymmetricBlockMatrix.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/gtsam/base/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index 1ec9a5ad3..c2996109f 100644 --- a/gtsam/base/SymmetricBlockMatrix.h +++ b/gtsam/base/SymmetricBlockMatrix.h @@ -71,6 +71,7 @@ namespace gtsam { } /// Construct from a container of the sizes of each block. + /// Uninitialized blocks are filled with zeros. template SymmetricBlockMatrix(const CONTAINER& dimensions, bool appendOneDimension = false) : blockStart_(0) @@ -81,6 +82,7 @@ namespace gtsam { } /// Construct from iterator over the sizes of each vertical block. + /// Uninitialized blocks are filled with zeros. template SymmetricBlockMatrix(ITERATOR firstBlockDim, ITERATOR lastBlockDim, bool appendOneDimension = false) : blockStart_(0) @@ -95,7 +97,7 @@ namespace gtsam { SymmetricBlockMatrix(const CONTAINER& dimensions, const Matrix& matrix, bool appendOneDimension = false) : blockStart_(0) { - matrix_.setZero(matrix.rows(), matrix.cols()); + matrix_.resize(matrix.rows(), matrix.cols()); matrix_.triangularView() = matrix.triangularView(); fillOffsets(dimensions.begin(), dimensions.end(), appendOneDimension); if(matrix_.rows() != matrix_.cols()) From 537155dd05a0e21d095212084227438447514992 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Thu, 28 May 2020 04:36:35 -0400 Subject: [PATCH 032/199] Sampler initialized with noise argument --- gtsam/slam/dataset.cpp | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 83636eb1d..0ed958869 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -546,13 +546,6 @@ BetweenFactorPose3s parse3DFactors(const string& filename, ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); - // If asked, create a sampler with random number generator - Sampler sampler; - if (corruptingNoise) { - sampler = Sampler(corruptingNoise); - } - - std::vector::shared_ptr> factors; while (!is.eof()) { char buf[LINESIZE]; @@ -595,6 +588,7 @@ BetweenFactorPose3s parse3DFactors(const string& filename, SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); auto R12 = Rot3::Quaternion(qw, qx, qy, qz); if (corruptingNoise) { + Sampler sampler(corruptingNoise); R12 = R12.retract(sampler.sample()); } From 5556db54200d19e453b87b7ba2eea1da106f3b78 Mon Sep 17 00:00:00 2001 From: Binit Shah Date: Sat, 30 May 2020 17:35:22 -0400 Subject: [PATCH 033/199] Using optional sampler outside loop --- gtsam/slam/dataset.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 0ed958869..66e8fc4c0 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include #include @@ -546,6 +547,11 @@ BetweenFactorPose3s parse3DFactors(const string& filename, ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); + boost::optional sampler; + if (corruptingNoise) { + sampler = Sampler(corruptingNoise); + } + std::vector::shared_ptr> factors; while (!is.eof()) { char buf[LINESIZE]; @@ -587,9 +593,8 @@ BetweenFactorPose3s parse3DFactors(const string& filename, SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); auto R12 = Rot3::Quaternion(qw, qx, qy, qz); - if (corruptingNoise) { - Sampler sampler(corruptingNoise); - R12 = R12.retract(sampler.sample()); + if (sampler) { + R12 = R12.retract(sampler->sample()); } factors.emplace_back(new BetweenFactor( From 1db0f441bcd91878e562c9ad61c1a958be082cf0 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 31 May 2020 21:52:13 -0400 Subject: [PATCH 034/199] Added FunctorizedFactor and corresponding tests --- gtsam/linear/NoiseModel.cpp | 1 + gtsam/nonlinear/FunctorizedFactor.h | 123 +++++++++++++++++ .../nonlinear/tests/testFunctorizedFactor.cpp | 127 ++++++++++++++++++ 3 files changed, 251 insertions(+) create mode 100644 gtsam/nonlinear/FunctorizedFactor.h create mode 100644 gtsam/nonlinear/tests/testFunctorizedFactor.cpp diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index d7fd2d1ea..72ca054b4 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -619,6 +619,7 @@ void Isotropic::WhitenInPlace(Eigen::Block H) const { // Unit /* ************************************************************************* */ void Unit::print(const std::string& name) const { + //TODO(Varun): Do we need that space at the end? cout << name << "unit (" << dim_ << ") " << endl; } diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h new file mode 100644 index 000000000..b990ac04f --- /dev/null +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -0,0 +1,123 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file FunctorizedFactor.h + * @author Varun Agrawal + **/ + +#pragma once + +#include +#include + +#include + +namespace gtsam { + +/** + * Factor which evaluates functor and uses the result to compute + * error on provided measurement. + * The provided FUNCTOR should provide two definitions: `argument_type` which + * corresponds to the type of input it accepts and `return_type` which indicates + * the type of the return value. This factor uses those type values to construct + * the functor. + * + * Template parameters are + * @param FUNCTOR: A class which operates as a functor. + */ +template +class GTSAM_EXPORT FunctorizedFactor + : public NoiseModelFactor1 { +private: + using T = typename FUNCTOR::argument_type; + using Base = NoiseModelFactor1; + + typename FUNCTOR::return_type + measured_; ///< value that is compared with functor return value + SharedNoiseModel noiseModel_; ///< noise model + FUNCTOR func_; ///< functor instance + +public: + /** default constructor - only use for serialization */ + FunctorizedFactor() {} + + /** Construct with given x and the parameters of the basis + * + * @param Args: Variadic template parameter for functor arguments. + * + * @param key: Factor key + * @param z: Measurement object of type FUNCTOR::return_type + * @param model: Noise model + * @param args: Variable number of arguments used to instantiate functor + */ + template + FunctorizedFactor(Key key, const typename FUNCTOR::return_type &z, + const SharedNoiseModel &model, Args &&... args) + : Base(model, key), measured_(z), noiseModel_(model), + func_(std::forward(args)...) {} + + virtual ~FunctorizedFactor() {} + + /// @return a deep copy of this factor + virtual NonlinearFactor::shared_ptr clone() const { + return boost::static_pointer_cast( + NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); + } + + Vector evaluateError(const T ¶ms, + boost::optional H = boost::none) const { + typename FUNCTOR::return_type x = func_(params, H); + Vector error = traits::Local(measured_, x); + return error; + } + + /// @name Testable + /// @{ + GTSAM_EXPORT friend std::ostream & + operator<<(std::ostream &os, const FunctorizedFactor &f) { + os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); + return os; + } + void print(const std::string &s = "", + const KeyFormatter &keyFormatter = DefaultKeyFormatter) const { + Base::print(s, keyFormatter); + std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor(" + << keyFormatter(this->key()) << ")" << std::endl; + traits::Print(measured_, " measurement: "); + std::cout << *this << std::endl; + } + + virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) + const { + const FunctorizedFactor *e = + dynamic_cast*>(&other); + const bool base = Base::equals(*e, tol); + return e != nullptr && base; + } + /// @} + +private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE &ar, const unsigned int /*version*/) { + ar &boost::serialization::make_nvp( + "NoiseModelFactor1", boost::serialization::base_object(*this)); + ar &BOOST_SERIALIZATION_NVP(measured_); + ar &BOOST_SERIALIZATION_NVP(func_); + } +}; + +// TODO(Varun): Include or kill? +// template <> struct traits : public Testable {}; + +} // namespace gtsam diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp new file mode 100644 index 000000000..7536aadc5 --- /dev/null +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -0,0 +1,127 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------1------------------------------------------- + */ + +/** + * @file testFunctorizedFactor.cpp + * @date May 31, 2020 + * @author Varun Agrawal + * @brief unit tests for FunctorizedFactor class + */ + +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +Key keyX = Symbol('X', 0); +auto model = noiseModel::Isotropic::Sigma(3, 1); + +/// Functor that takes a matrix and multiplies every element by m +class MultiplyFunctor { + double m_; ///< simple multiplier + +public: + using argument_type = Matrix; + using return_type = Matrix; + + MultiplyFunctor(double m) : m_(m) {} + + Matrix operator()(const Matrix &X, + OptionalJacobian<-1, -1> H = boost::none) const { + return m_ * X; + } +}; + +TEST(FunctorizedFactor, Identity) { + + Matrix X = Matrix::Identity(3, 3); + + double multiplier = 1.0; + + FunctorizedFactor factor(keyX, X, model, multiplier); + + Values values; + values.insert(keyX, X); + + Matrix error = factor.evaluateError(X); + + EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); +} + +TEST(FunctorizedFactor, Multiply2) { + Matrix X = Matrix::Identity(3, 3); + + double multiplier = 2.0; + + FunctorizedFactor factor(keyX, X, model, multiplier); + + Values values; + values.insert(keyX, X); + + Matrix error = factor.evaluateError(X); + + Matrix expected = Matrix::Identity(3, 3); + expected.resize(9, 1); + EXPECT(assert_equal(expected, error, 1e-9)); +} + +TEST(FunctorizedFactor, Equality) { + Matrix X = Matrix::Identity(2, 2); + + double multiplier = 2.0; + + FunctorizedFactor factor1(keyX, X, model, multiplier); + FunctorizedFactor factor2(keyX, X, model, multiplier); + + EXPECT(factor1.equals(factor2)); +} + +TEST(FunctorizedFactor, Print) { + Matrix X = Matrix::Identity(2, 2); + + double multiplier = 2.0; + + FunctorizedFactor factor(keyX, X, model, multiplier); + + // redirect output to buffer so we can compare + stringstream buffer; + streambuf *old = cout.rdbuf(buffer.rdbuf()); + + factor.print(); + + // get output string and reset stdout + string actual = buffer.str(); + cout.rdbuf(old); + + string expected = " keys = { X0 }\n" + " noise model: unit (3) \n" + "FunctorizedFactor(X0)\n" + " measurement: [\n" + " 1, 0;\n" + " 0, 1\n" + "]\n" + " noise model sigmas: 1 1 1\n"; + + CHECK_EQUAL(expected, actual); +} + +/* ************************************************************************* + */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From 131213a983521b2095f15d3ce0d798645f513538 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 1 Jun 2020 19:52:50 -0400 Subject: [PATCH 035/199] fixes, better tests, docs --- gtsam/nonlinear/FunctorizedFactor.h | 58 +++++++++++------ .../nonlinear/tests/testFunctorizedFactor.cpp | 62 ++++++++++++------- 2 files changed, 78 insertions(+), 42 deletions(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index b990ac04f..03fd47a46 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -10,8 +10,9 @@ * -------------------------------------------------------------------------- */ /** - * @file FunctorizedFactor.h - * @author Varun Agrawal + * @file FunctorizedFactor.h + * @date May 31, 2020 + * @author Varun Agrawal **/ #pragma once @@ -26,13 +27,35 @@ namespace gtsam { /** * Factor which evaluates functor and uses the result to compute * error on provided measurement. - * The provided FUNCTOR should provide two definitions: `argument_type` which + * The provided FUNCTOR should provide two type aliases: `argument_type` which * corresponds to the type of input it accepts and `return_type` which indicates * the type of the return value. This factor uses those type values to construct * the functor. * * Template parameters are * @param FUNCTOR: A class which operates as a functor. + * + * Example: + * Key key = Symbol('X', 0); + * + * auto model = noiseModel::Isotropic::Sigma(9, 1); + * /// Functor that takes a matrix and multiplies every element by m + * class MultiplyFunctor { + * double m_; ///< simple multiplier + * public: + * using argument_type = Matrix; + * using return_type = Matrix; + * MultiplyFunctor(double m) : m_(m) {} + * Matrix operator()(const Matrix &X, + * OptionalJacobian<-1, -1> H = boost::none) const { + * if (H) *H = m_ * Matrix::Identity(X.rows()*X.cols(), X.rows()*X.cols()); + * return m_ * X; + * } + * }; + * + * Matrix measurement = Matrix::Identity(3, 3); + * double multiplier = 2.0; + * FunctorizedFactor factor(keyX, measurement, model, multiplier); */ template class GTSAM_EXPORT FunctorizedFactor @@ -82,27 +105,24 @@ public: /// @name Testable /// @{ - GTSAM_EXPORT friend std::ostream & - operator<<(std::ostream &os, const FunctorizedFactor &f) { - os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); - return os; - } void print(const std::string &s = "", const KeyFormatter &keyFormatter = DefaultKeyFormatter) const { Base::print(s, keyFormatter); std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor(" << keyFormatter(this->key()) << ")" << std::endl; traits::Print(measured_, " measurement: "); - std::cout << *this << std::endl; + std::cout << " noise model sigmas: " << noiseModel_->sigmas().transpose() + << std::endl; } - virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) - const { - const FunctorizedFactor *e = - dynamic_cast*>(&other); - const bool base = Base::equals(*e, tol); - return e != nullptr && base; - } + virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) const { + const FunctorizedFactor *e = + dynamic_cast *>(&other); + const bool base = Base::equals(*e, tol); + return e && Base::equals(other, tol) && + traits::Equals(this->measured_, e->measured_, + tol); + } /// @} private: @@ -117,7 +137,9 @@ private: } }; -// TODO(Varun): Include or kill? -// template <> struct traits : public Testable {}; +/// traits +template +struct traits> + : public Testable> {}; } // namespace gtsam diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp index 7536aadc5..9393a4410 100644 --- a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -20,14 +20,15 @@ #include #include #include +#include #include using namespace std; using namespace gtsam; -Key keyX = Symbol('X', 0); -auto model = noiseModel::Isotropic::Sigma(3, 1); +Key key = Symbol('X', 0); +auto model = noiseModel::Isotropic::Sigma(9, 1); /// Functor that takes a matrix and multiplies every element by m class MultiplyFunctor { @@ -41,60 +42,73 @@ public: Matrix operator()(const Matrix &X, OptionalJacobian<-1, -1> H = boost::none) const { + if (H) + *H = m_ * Matrix::Identity(X.rows() * X.cols(), X.rows() * X.cols()); return m_ * X; } }; TEST(FunctorizedFactor, Identity) { - Matrix X = Matrix::Identity(3, 3); + Matrix X = Matrix::Identity(3, 3), measurement = Matrix::Identity(3, 3); double multiplier = 1.0; - FunctorizedFactor factor(keyX, X, model, multiplier); + FunctorizedFactor factor(key, measurement, model, + multiplier); - Values values; - values.insert(keyX, X); - - Matrix error = factor.evaluateError(X); + Vector error = factor.evaluateError(X); EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } TEST(FunctorizedFactor, Multiply2) { - Matrix X = Matrix::Identity(3, 3); - double multiplier = 2.0; + Matrix X = Matrix::Identity(3, 3); + Matrix measurement = multiplier * Matrix::Identity(3, 3); - FunctorizedFactor factor(keyX, X, model, multiplier); + FunctorizedFactor factor(key, measurement, model, multiplier); - Values values; - values.insert(keyX, X); + Vector error = factor.evaluateError(X); - Matrix error = factor.evaluateError(X); - - Matrix expected = Matrix::Identity(3, 3); - expected.resize(9, 1); - EXPECT(assert_equal(expected, error, 1e-9)); + EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } TEST(FunctorizedFactor, Equality) { - Matrix X = Matrix::Identity(2, 2); + Matrix measurement = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor1(keyX, X, model, multiplier); - FunctorizedFactor factor2(keyX, X, model, multiplier); + FunctorizedFactor factor1(key, measurement, model, + multiplier); + FunctorizedFactor factor2(key, measurement, model, + multiplier); EXPECT(factor1.equals(factor2)); } +//****************************************************************************** +TEST(FunctorizedFactor, Jacobians) { + Matrix X = Matrix::Identity(3, 3); + Matrix actualH; + + double multiplier = 2.0; + + FunctorizedFactor factor(key, X, model, multiplier); + + Values values; + values.insert(key, X); + + // Check Jacobians + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + TEST(FunctorizedFactor, Print) { Matrix X = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor(keyX, X, model, multiplier); + FunctorizedFactor factor(key, X, model, multiplier); // redirect output to buffer so we can compare stringstream buffer; @@ -107,13 +121,13 @@ TEST(FunctorizedFactor, Print) { cout.rdbuf(old); string expected = " keys = { X0 }\n" - " noise model: unit (3) \n" + " noise model: unit (9) \n" "FunctorizedFactor(X0)\n" " measurement: [\n" " 1, 0;\n" " 0, 1\n" "]\n" - " noise model sigmas: 1 1 1\n"; + " noise model sigmas: 1 1 1 1 1 1 1 1 1\n"; CHECK_EQUAL(expected, actual); } From ea8b319c43ea64b563792c3c2b8d9ccdd298c5cc Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 1 Jun 2020 19:54:04 -0400 Subject: [PATCH 036/199] remove TODO --- gtsam/linear/NoiseModel.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 72ca054b4..d7fd2d1ea 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -619,7 +619,6 @@ void Isotropic::WhitenInPlace(Eigen::Block H) const { // Unit /* ************************************************************************* */ void Unit::print(const std::string& name) const { - //TODO(Varun): Do we need that space at the end? cout << name << "unit (" << dim_ << ") " << endl; } From 0bbb39687f5c1b4f2e34e288786a9acd58a7e17d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 1 Jun 2020 19:55:10 -0400 Subject: [PATCH 037/199] improved documentation --- gtsam/nonlinear/FunctorizedFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 03fd47a46..82d2f822e 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -37,8 +37,8 @@ namespace gtsam { * * Example: * Key key = Symbol('X', 0); - * * auto model = noiseModel::Isotropic::Sigma(9, 1); + * * /// Functor that takes a matrix and multiplies every element by m * class MultiplyFunctor { * double m_; ///< simple multiplier From 7486ed7993208fa27f9b61c23cd7509e26df6906 Mon Sep 17 00:00:00 2001 From: Martin Vonheim Larsen Date: Tue, 2 Jun 2020 13:02:10 +0200 Subject: [PATCH 038/199] Added test for Unit3::operator= --- gtsam/geometry/tests/testUnit3.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index a25ab25c7..0f98e4648 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -484,6 +484,15 @@ TEST(Unit3, ErrorBetweenFactor) { } } +TEST(Unit3, copy_assign) { + Unit3 p{1, 0.2, 0.3}; + + EXPECT(p.error(p).isZero()); + + p = Unit3{-1, 2, 8}; + EXPECT(p.error(p).isZero()); +} + /* ************************************************************************* */ TEST(actualH, Serialization) { Unit3 p(0, 1, 0); From bc7f5e6da75c9011999ddab39e5d9d7f857703e1 Mon Sep 17 00:00:00 2001 From: Martin Vonheim Larsen Date: Tue, 2 Jun 2020 13:02:22 +0200 Subject: [PATCH 039/199] Properly handle basis in Unit3::operator= If the basis was already cached we reset it to the cached basis of `u`. --- gtsam/geometry/Unit3.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index f1a9c1a69..24a8c0219 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -90,6 +90,8 @@ public: /// Copy assignment Unit3& operator=(const Unit3 & u) { p_ = u.p_; + B_ = u.B_; + H_B_ = u.H_B_; return *this; } From d0bd3d87154f411a66e2cd3ca2e537e46f47568e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 2 Jun 2020 15:13:30 -0500 Subject: [PATCH 040/199] removed dependency on Eigen3 since we provide Eigen 3.3.7 and Ubuntu Bionic provides Eigen 3.3.4. --- .../Dockerfile | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) rename docker/{ubuntu-boost-tbb-eigen3 => ubuntu-boost-tbb}/Dockerfile (72%) diff --git a/docker/ubuntu-boost-tbb-eigen3/Dockerfile b/docker/ubuntu-boost-tbb/Dockerfile similarity index 72% rename from docker/ubuntu-boost-tbb-eigen3/Dockerfile rename to docker/ubuntu-boost-tbb/Dockerfile index 33aa1ab96..6dd9dfa62 100644 --- a/docker/ubuntu-boost-tbb-eigen3/Dockerfile +++ b/docker/ubuntu-boost-tbb/Dockerfile @@ -2,7 +2,7 @@ FROM ubuntu:bionic # Update apps on the base image -RUN apt-get -y update && apt-get install -y +RUN apt-get -y update && apt install -y # Install C++ RUN apt-get -y install build-essential @@ -12,7 +12,3 @@ RUN apt-get -y install libboost-all-dev cmake # Install TBB RUN apt-get -y install libtbb-dev - -# Install latest Eigen -RUN apt-get install -y libeigen3-dev - From a6e9b0287e1c72384d982226c8b167e79be21f2b Mon Sep 17 00:00:00 2001 From: "Martin V. Larsen" Date: Tue, 2 Jun 2020 22:20:35 +0200 Subject: [PATCH 041/199] Update testUnit3.cpp --- gtsam/geometry/tests/testUnit3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/tests/testUnit3.cpp b/gtsam/geometry/tests/testUnit3.cpp index 0f98e4648..ddf60a256 100644 --- a/gtsam/geometry/tests/testUnit3.cpp +++ b/gtsam/geometry/tests/testUnit3.cpp @@ -484,7 +484,7 @@ TEST(Unit3, ErrorBetweenFactor) { } } -TEST(Unit3, copy_assign) { +TEST(Unit3, CopyAssign) { Unit3 p{1, 0.2, 0.3}; EXPECT(p.error(p).isZero()); From 92634d152513f1acc8f878421fe17b7c9781b936 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 2 Jun 2020 16:33:57 -0500 Subject: [PATCH 042/199] improve and modernize the Dockerfiles --- docker/ubuntu-boost-tbb/Dockerfile | 9 +++++++-- docker/ubuntu-gtsam-python-vnc/Dockerfile | 8 +++++--- docker/ubuntu-gtsam-python/Dockerfile | 12 +++++++----- docker/ubuntu-gtsam/Dockerfile | 11 ++++++----- 4 files changed, 25 insertions(+), 15 deletions(-) diff --git a/docker/ubuntu-boost-tbb/Dockerfile b/docker/ubuntu-boost-tbb/Dockerfile index 6dd9dfa62..9f6eea3b8 100644 --- a/docker/ubuntu-boost-tbb/Dockerfile +++ b/docker/ubuntu-boost-tbb/Dockerfile @@ -1,11 +1,16 @@ +# Basic Ubuntu 18.04 image with Boost and TBB installed. To be used for building further downstream packages. + # Get the base Ubuntu image from Docker Hub FROM ubuntu:bionic +# Disable GUI prompts +ENV DEBIAN_FRONTEND noninteractive + # Update apps on the base image -RUN apt-get -y update && apt install -y +RUN apt-get -y update && apt-get -y install # Install C++ -RUN apt-get -y install build-essential +RUN apt-get -y install build-essential apt-utils # Install boost and cmake RUN apt-get -y install libboost-all-dev cmake diff --git a/docker/ubuntu-gtsam-python-vnc/Dockerfile b/docker/ubuntu-gtsam-python-vnc/Dockerfile index 83222881a..8b6b97f46 100644 --- a/docker/ubuntu-gtsam-python-vnc/Dockerfile +++ b/docker/ubuntu-gtsam-python-vnc/Dockerfile @@ -1,16 +1,18 @@ +# This GTSAM image connects to the host X-server via VNC to provide a Graphical User Interface for interaction. + # Get the base Ubuntu/GTSAM image from Docker Hub FROM dellaert/ubuntu-gtsam-python:bionic # Things needed to get a python GUI ENV DEBIAN_FRONTEND noninteractive -RUN apt-get install -y python-tk +RUN apt install -y python-tk RUN pip install matplotlib # Install a VNC X-server, Frame buffer, and windows manager -RUN apt-get install -y x11vnc xvfb fluxbox +RUN apt install -y x11vnc xvfb fluxbox # Finally, install wmctrl needed for bootstrap script -RUN apt-get install -y wmctrl +RUN apt install -y wmctrl # Copy bootstrap script and make sure it runs COPY bootstrap.sh / diff --git a/docker/ubuntu-gtsam-python/Dockerfile b/docker/ubuntu-gtsam-python/Dockerfile index 0c7d131be..a9a9782f4 100644 --- a/docker/ubuntu-gtsam-python/Dockerfile +++ b/docker/ubuntu-gtsam-python/Dockerfile @@ -1,29 +1,31 @@ +# GTSAM Ubuntu image with Python wrapper support. + # Get the base Ubuntu/GTSAM image from Docker Hub -FROM dellaert/ubuntu-gtsam:bionic +FROM dellaert/ubuntu-gtsam:latest # Install pip -RUN apt-get install -y python-pip python-dev +RUN apt-get install -y python3-pip python3-dev # Install python wrapper requirements -RUN pip install -r /usr/src/gtsam/cython/requirements.txt +RUN pip3 install -U -r /usr/src/gtsam/cython/requirements.txt # Run cmake again, now with cython toolbox on WORKDIR /usr/src/gtsam/build RUN cmake \ -DCMAKE_BUILD_TYPE=Release \ - -DGTSAM_USE_SYSTEM_EIGEN=ON \ -DGTSAM_WITH_EIGEN_MKL=OFF \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ -DGTSAM_BUILD_TIMING_ALWAYS=OFF \ -DGTSAM_BUILD_TESTS=OFF \ -DGTSAM_INSTALL_CYTHON_TOOLBOX=ON \ + -DGTSAM_PYTHON_VERSION=3\ .. # Build again, as ubuntu-gtsam image cleaned RUN make -j3 install && make clean # Needed to run python wrapper: -RUN echo 'export PYTHONPATH=/usr/local/cython/' >> /root/.bashrc +RUN echo 'export PYTHONPATH=/usr/local/cython/:$PYTHONPATH' >> /root/.bashrc # Run bash CMD ["bash"] diff --git a/docker/ubuntu-gtsam/Dockerfile b/docker/ubuntu-gtsam/Dockerfile index bdfa8d9a5..c09d4b16a 100644 --- a/docker/ubuntu-gtsam/Dockerfile +++ b/docker/ubuntu-gtsam/Dockerfile @@ -1,5 +1,7 @@ +# Ubuntu image with GTSAM installed. Configured with Boost and TBB support. + # Get the base Ubuntu image from Docker Hub -FROM dellaert/ubuntu-boost-tbb-eigen3:bionic +FROM dellaert/ubuntu-boost-tbb:latest # Install git RUN apt-get update && \ @@ -11,13 +13,12 @@ RUN apt-get install -y build-essential # Clone GTSAM WORKDIR /usr/src/ RUN git clone https://bitbucket.org/gtborg/gtsam.git +RUN mkdir build # Run cmake -RUN mkdir /usr/src/gtsam/build WORKDIR /usr/src/gtsam/build RUN cmake \ -DCMAKE_BUILD_TYPE=Release \ - -DGTSAM_USE_SYSTEM_EIGEN=ON \ -DGTSAM_WITH_EIGEN_MKL=OFF \ -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF \ -DGTSAM_BUILD_TIMING_ALWAYS=OFF \ @@ -26,10 +27,10 @@ RUN cmake \ .. # Build -RUN make -j3 install && make clean +RUN make -j4 install && make clean # Needed to link with GTSAM -RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib' >> /root/.bashrc +RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib:LD_LIBRARY_PATH' >> /root/.bashrc # Run bash CMD ["bash"] From 8b66960a42d30cb8dfb0e3a7be08e76f9fcfec30 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 2 Jun 2020 17:02:14 -0500 Subject: [PATCH 043/199] small logistical fixes --- docker/ubuntu-gtsam-python-vnc/Dockerfile | 2 +- docker/ubuntu-gtsam-python/Dockerfile | 4 ++-- docker/ubuntu-gtsam/Dockerfile | 8 ++++---- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/docker/ubuntu-gtsam-python-vnc/Dockerfile b/docker/ubuntu-gtsam-python-vnc/Dockerfile index 8b6b97f46..26f995c56 100644 --- a/docker/ubuntu-gtsam-python-vnc/Dockerfile +++ b/docker/ubuntu-gtsam-python-vnc/Dockerfile @@ -1,7 +1,7 @@ # This GTSAM image connects to the host X-server via VNC to provide a Graphical User Interface for interaction. # Get the base Ubuntu/GTSAM image from Docker Hub -FROM dellaert/ubuntu-gtsam-python:bionic +FROM dellaert/ubuntu-gtsam-python:latest # Things needed to get a python GUI ENV DEBIAN_FRONTEND noninteractive diff --git a/docker/ubuntu-gtsam-python/Dockerfile b/docker/ubuntu-gtsam-python/Dockerfile index a9a9782f4..71787d480 100644 --- a/docker/ubuntu-gtsam-python/Dockerfile +++ b/docker/ubuntu-gtsam-python/Dockerfile @@ -7,7 +7,7 @@ FROM dellaert/ubuntu-gtsam:latest RUN apt-get install -y python3-pip python3-dev # Install python wrapper requirements -RUN pip3 install -U -r /usr/src/gtsam/cython/requirements.txt +RUN python3 -m pip install -U -r /usr/src/gtsam/cython/requirements.txt # Run cmake again, now with cython toolbox on WORKDIR /usr/src/gtsam/build @@ -22,7 +22,7 @@ RUN cmake \ .. # Build again, as ubuntu-gtsam image cleaned -RUN make -j3 install && make clean +RUN make -j4 install && make clean # Needed to run python wrapper: RUN echo 'export PYTHONPATH=/usr/local/cython/:$PYTHONPATH' >> /root/.bashrc diff --git a/docker/ubuntu-gtsam/Dockerfile b/docker/ubuntu-gtsam/Dockerfile index c09d4b16a..393443361 100644 --- a/docker/ubuntu-gtsam/Dockerfile +++ b/docker/ubuntu-gtsam/Dockerfile @@ -10,13 +10,13 @@ RUN apt-get update && \ # Install compiler RUN apt-get install -y build-essential -# Clone GTSAM +# Clone GTSAM (develop branch) WORKDIR /usr/src/ -RUN git clone https://bitbucket.org/gtborg/gtsam.git -RUN mkdir build +RUN git clone --single-branch --branch develop https://github.com/borglab/gtsam.git -# Run cmake +# Change to build directory. Will be created automatically. WORKDIR /usr/src/gtsam/build +# Run cmake RUN cmake \ -DCMAKE_BUILD_TYPE=Release \ -DGTSAM_WITH_EIGEN_MKL=OFF \ From 780345bc2764753aae8fbf277dfe477375eff59e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:24:58 -0400 Subject: [PATCH 044/199] put file stream inside scope to force buffer flush This was already fixed for serializeXML but not for serializeToXMLFile or deserializeFromXMLFile. --- gtsam/base/serialization.h | 12 ++++-- gtsam/base/serializationTestHelpers.h | 57 +++++++++++++++++++++++++++ 2 files changed, 65 insertions(+), 4 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index e475465de..088029903 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -106,8 +106,10 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input);; + { + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input);; + } out_archive_stream.close(); return true; } @@ -117,8 +119,10 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + { + boost::archive::xml_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); + } in_archive_stream.close(); return true; } diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 06b3462e9..178b256a6 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -26,6 +26,7 @@ #include #include +#include // whether to print the serialized text to stdout @@ -40,6 +41,13 @@ T create() { return T(); } +std::string resetFilesystem() { + // Create files in folder in build folder + boost::filesystem::remove_all("actual"); + boost::filesystem::create_directory("actual"); + return "actual/"; +} + // Templated round-trip serialization template void roundtrip(const T& input, T& output) { @@ -50,11 +58,22 @@ void roundtrip(const T& input, T& output) { deserialize(serialized, output); } +// Templated round-trip serialization using a file +template +void roundtripFile(const T& input, T& output) { + std::string path = resetFilesystem(); + + serializeToFile(input, path + "graph.dat"); + deserializeFromFile(path + "graph.dat", output); +} + // This version requires equality operator template bool equality(const T& input = T()) { T output = create(); roundtrip(input,output); + if (input != output) return false; + roundtripFile(input,output); return input==output; } @@ -63,6 +82,8 @@ template bool equalsObj(const T& input = T()) { T output = create(); roundtrip(input,output); + if (!assert_equal(input, output)) return false; + roundtripFile(input,output); return assert_equal(input, output); } @@ -71,6 +92,8 @@ template bool equalsDereferenced(const T& input) { T output = create(); roundtrip(input,output); + if (!input->equals(*output)) return false; + roundtripFile(input,output); return input->equals(*output); } @@ -85,11 +108,25 @@ void roundtripXML(const T& input, T& output) { deserializeXML(serialized, output); } +// Templated round-trip serialization using XML File +template +void roundtripXMLFile(const T& input, T& output) { + std::string path = resetFilesystem(); + + // Serialize + serializeToXMLFile(input, path + "graph.xml"); + + // De-serialize + deserializeFromXMLFile(path + "graph.xml", output); +} + // This version requires equality operator template bool equalityXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (input != output) return false; + roundtripXMLFile(input,output); return input==output; } @@ -98,6 +135,8 @@ template bool equalsXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (!assert_equal(input, output)) return false; + roundtripXMLFile(input, output); return assert_equal(input, output); } @@ -106,6 +145,8 @@ template bool equalsDereferencedXML(const T& input = T()) { T output = create(); roundtripXML(input,output); + if (!input->equals(*output)) return false; + roundtripXMLFile(input, output); return input->equals(*output); } @@ -120,11 +161,23 @@ void roundtripBinary(const T& input, T& output) { deserializeBinary(serialized, output); } +// Templated round-trip serialization using XML +template +void roundtripBinaryFile(const T& input, T& output) { + std::string path = resetFilesystem(); + // Serialize + serializeToBinaryFile(input, path + "graph.bin"); + // De-serialize + deserializeFromBinaryFile(path + "graph.bin", output); +} + // This version requires equality operator template bool equalityBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (input != output) return false; + roundtripBinaryFile(input,output); return input==output; } @@ -133,6 +186,8 @@ template bool equalsBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (!assert_equal(input, output)) return false; + roundtripBinaryFile(input,output); return assert_equal(input, output); } @@ -141,6 +196,8 @@ template bool equalsDereferencedBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); + if (!input->equals(*output)) return false; + roundtripBinaryFile(input,output); return input->equals(*output); } From c94736b6b6959820efe628d52cc8cd17c0269cdc Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:39:54 -0400 Subject: [PATCH 045/199] bypass assert_equal tests for file roundtrips --- gtsam/base/serializationTestHelpers.h | 6 ------ 1 file changed, 6 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 178b256a6..d29899072 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -82,8 +82,6 @@ template bool equalsObj(const T& input = T()) { T output = create(); roundtrip(input,output); - if (!assert_equal(input, output)) return false; - roundtripFile(input,output); return assert_equal(input, output); } @@ -135,8 +133,6 @@ template bool equalsXML(const T& input = T()) { T output = create(); roundtripXML(input,output); - if (!assert_equal(input, output)) return false; - roundtripXMLFile(input, output); return assert_equal(input, output); } @@ -186,8 +182,6 @@ template bool equalsBinary(const T& input = T()) { T output = create(); roundtripBinary(input,output); - if (!assert_equal(input, output)) return false; - roundtripBinaryFile(input,output); return assert_equal(input, output); } From 686b0effbf4e6d222ed26c17d2c00bb7dc878551 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 9 Jun 2020 02:48:53 -0400 Subject: [PATCH 046/199] better comments on serializationTestHelper functions --- gtsam/base/serializationTestHelpers.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index d29899072..031a6278f 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -41,8 +41,8 @@ T create() { return T(); } +// Creates or empties a folder in the build folder and returns the relative path std::string resetFilesystem() { - // Create files in folder in build folder boost::filesystem::remove_all("actual"); boost::filesystem::create_directory("actual"); return "actual/"; @@ -157,7 +157,7 @@ void roundtripBinary(const T& input, T& output) { deserializeBinary(serialized, output); } -// Templated round-trip serialization using XML +// Templated round-trip serialization using Binary file template void roundtripBinaryFile(const T& input, T& output) { std::string path = resetFilesystem(); From ab88471c2a5383e6e094e8c5674aa86e9398a4b8 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Wed, 10 Jun 2020 10:06:16 +0200 Subject: [PATCH 047/199] unhide doc section in PDF --- doc/gtsam-coordinate-frames.lyx | 17 ++++------------- doc/gtsam-coordinate-frames.pdf | Bin 80806 -> 121711 bytes 2 files changed, 4 insertions(+), 13 deletions(-) diff --git a/doc/gtsam-coordinate-frames.lyx b/doc/gtsam-coordinate-frames.lyx index 33d0dd977..cfb44696b 100644 --- a/doc/gtsam-coordinate-frames.lyx +++ b/doc/gtsam-coordinate-frames.lyx @@ -2291,15 +2291,11 @@ uncalibration used in the residual). \end_layout -\begin_layout Standard -\begin_inset Note Note -status collapsed - \begin_layout Section Noise models of prior factors \end_layout -\begin_layout Plain Layout +\begin_layout Standard The simplest way to describe noise models is by an example. Let's take a prior factor on a 3D pose \begin_inset Formula $x\in\SE 3$ @@ -2353,7 +2349,7 @@ e\left(x\right)=\norm{h\left(x\right)}_{\Sigma}^{2}=h\left(x\right)^{\t}\Sigma^{ useful answer out quickly ] \end_layout -\begin_layout Plain Layout +\begin_layout Standard The density induced by a noise model on the prior factor is Gaussian in the tangent space about the linearization point. Suppose that the pose is linearized at @@ -2431,7 +2427,7 @@ Here we see that the update . \end_layout -\begin_layout Plain Layout +\begin_layout Standard This means that to draw random pose samples, we actually draw random samples of \begin_inset Formula $\delta x$ @@ -2456,7 +2452,7 @@ This means that to draw random pose samples, we actually draw random samples Noise models of between factors \end_layout -\begin_layout Plain Layout +\begin_layout Standard The noise model of a BetweenFactor is a bit more complicated. The unwhitened error is \begin_inset Formula @@ -2516,11 +2512,6 @@ e\left(\delta x_{1}\right) & \approx\norm{\log\left(z^{-1}\left(x_{1}\exp\delta \end_inset -\end_layout - -\end_inset - - \end_layout \end_body diff --git a/doc/gtsam-coordinate-frames.pdf b/doc/gtsam-coordinate-frames.pdf index 3613ef0ac82176c8a82e6ff0fc5fd7e05ed19c87..77910b4cf3b26b20020515cb885e2b4c1222dd05 100644 GIT binary patch delta 118821 zcmZs>Q+TFb(5)NWwr$%^$4&Tq6F zca1ShpP;UqVH0rB5rl*gSQRZCt=z21I5_xu$dUu6Xn{>VeWyJhoPgMC! zVwtEGIIq-2CQuaz`=v*$XxM1c)Kii*Y|QcC22{8WeyZD+;612UotJKR>zGT?p*29X zKJ+|4z*FMMZ=quaip9d=jWr#^Z9xas1=1Dixi_zA)h_p*9BcO;Pi^v=9D9|}-NQ9O{)sHS6OruHodHEV2kcLh zjSp0b_m1mZC45uN;b~1L*O|`u0t*8RVQ0mpqY-Xc^d`gN_kzDGgDi{zD+HlXPP_J; z2owd1K8j%E*mpnL=sS1}ksqSbVdeN4u9x(B|5Ib~wXO6s?FR{a*$N8P87k*RSkn@5 z^e2G5PrFe4HV_O_eME*s**C7eoG78>YT zxheNd@>+?;j)_)Z$aH)M!}IKHXlxs;D^vbKbi#zUZFG<1k2Qv(WQmFqE~^5;P^ z<mir5ZxF!e^+bEy+G2p$R@KiLDHPorE8hZ-A_=LM=KMnSSpE|?9$OOu9=^k3y0ZTUcoevExDts&SW4n z&?S5kQ7^>5U5gD@fd5Ys5uXKQc#KIZ&YOD(c4MjDY`E-wAVg6piq+s+b7C9Z2Ne=e z(-pOAW>(c|rvLggbaYUUW^AD&kh#W=SpQyW+hK#}(a@uLur>9j7_OaInLKw!r#nFv zLpJpq!|O1?&?}F@FQdD_dj^Reqr1OkMmA$+%v9B^x58Bq#1A)m^v<6St9S{154sp; zIumO?mF&FPU(%)K;CbB1X=HvXEf+qysfDR``lGaJZsO4FfPT1cdIc#E3~5=dTy4&~ zgH>S0;eawU_Pi?xWd}bValj(CaqINCyAWKKnq5(V-0Arv+{71vOV)-D<{9n!`-}9(^P_& zk#TRS73&Z=ssym7Ao-rHEdS?yW9@@U|F-StCl{k;i@FC^vX^!@2z~P+hRw_({v{ec zE{|M*=+Aog_q&uPQsqJC^LsJahEf>AH8NNQrTH|~%?W|q2PttJKQPGJp`V1j-*LMo zp>sYZ)g!d>(b(`h=DT4%Uw>(MdfW+Ox_}M-c|WdYzQk288GQ;-oh9R!r}1rvw` z`caft8+-kHMGg5il{8*uz_(~FTQv30cniY;J~Z&Z=Q|4_YzGi%dD<73Q+8-<=AZR? zg7gxKl2G!tU%=#aRn)L+gNeN@Ek5LPOBu3L(VDczlXn5L5VcBttZUsz=|u$sQAy2pdZR{b?Qx`UsDc^3||uWE3+)nXdhwIndKIQ1Gp zzJi^GpdP{3d8}i<&Qe4`wAf9gdNXqtPTt0}+braOD@OQ^t>Q&JSCI2HJXd@YjCC>i z+LrGY)yNE6T!8f%XqZJ8{o*d1ioD@vgU!dC&;yM)k!qoZ&gBr^ts+x1eCS*Cz{m2(|+^KW{)XpQ!n#?iW*Wvct=6Hfb}fa z5d^f0cY>#deuVZ~a-(~5Pd6vg>HK|etigOgssc**z{_WXs9_{>xM&^vH}-5xLPqs8 zOUDM$A0O|C+eACpBgj@utCPjD!j36CirGj@i-!Y?+cjI82L5*<+=Syf2d1vB0PG-9 zgTSV)V}`1wtLw^pj$iA7|L3{~ZKJ%mi(&rMhX?IEm(r)lrA;z@t^sLOJL_BhadXec zyVpZmcBP6+hGMQ6&Ac5=(|Dc*hs+?y<$_&ALWzyk92aLna}1R*+0k}qi)omg-a*JU zF?m6|ER^mqTd`5dpj>jgLk>g5^P%mBa)?TbU%m0V}HrGYrpS!%2Hq*c6if4)c zWF5Uin4txdAg3Hc5b9H>A|l|>i!)|UzVVG8;nfm&v!21l#=!HQ9+9B)?0i!M;}j&% z;I#a^clE2AqfxOhxzF2@m6(F{*FZU2Vo>V0I!*!2?kks9SPHR#qa z6d2Lxrw_8(&9PD|d^{u_d;wHG6m8(9rU=>ZJ;|d*@^^M69227$r(Leu>HB7H(rZ2# zW@Z1ODdAcW`9U;ums4C>DWj>jhhh|y>7n#mk}(Byx8vGta3|}Vi|uHh5^_tvJaPeM z;+l?U%nmwAziw#?0R($qpy|nEw!?7pdox4t`v&#x`h~JWx*|Nu4iH4^=@1ZNaP{*t zD-CC)ljSPwRE*C5$F`)7yzD0Zc6jAvh4o#x{b?Nd1(U+3LE})i8a}2k2Eo*Xlt2bN zv}R81Y1AyJgl0$psG*OD>{pi0-G3k-j>~!(^bc83rl+H~)#}q@Z8oHX6{=x~E6BN= zJl4e|hE;T}d;IgF0K^3q~gMa5ec?%l%gA_{+Q8NsuJ#(-eqLBK6krs}+}I?QvKv;BdI&nYe4> zOyvE9Ys66^td;-J2Fp)8apqdF2eCD&${y6Ac?VN+_!%!{()*R1=?#<<72o33f2X-H zFmZ!-mB}Bs05=P~(NOvOmzJaE!n(qa>{^XIahxNA_5x|Ox%F{ekD9ZkPH4|(Vg<5fp|L5&e}J!PB1kti{xL%T%@Z^x-8^> z3o)j?uYjVg*e6RR_?1M3t*hsnx}c;o0yq~#jj4oDY_NEL#HP!H+`Ysc14>y?!L z!5^P&k=ccu^ew0}Q^SH|pdD^3Z7uFRKT7nt60$l$6Any{)FX_v1h#r=;+u=7#7T&u z%si~m%+#R?kzl{3%HzmARmF7sAS-K85oVC)&}!ny1m?Z zRYkrQkWyOpgyNre2&C2Y+$|Bre!HbSs)zGL8LB8pC3Xeck zw+M7=_t)R@sdo+{2kqoECud3GFDTP4yZ7Ft^(!bS^vxPqKu1pT(s=B+EN0L-2f5jE z0cWKp+JtAZqPpcdP+q617?Qor1chAm-*@?O$qfr2(g=1DCpCQfvdwHI$tCw%8li|1 zCj2P6y8<<&L|>AtDoULOx!(L4F-p-acf z3_46yehgg`#)R^|h6~NW!Mn?@a{hbB2c}*Y9(B*mN*I8L?~vr*ZzTgR+c|1Za+pq0 zJ0JSF8UBC?<)bVJgQ3N}<@63VdFHdZ@BHFX4Z=dcdSS>mf{vZ~t?pqucNqq%oWM%kt|oAG1V@>PT{a=+3dh(M4!4ZD%_-jDXPbrKZa!W@q`6 zaUnlEoBV1JHe6#230T1}TBL+n;i78HDbYg?xS%S{M)N&4Gsl~C+V7tNugn7P*2RbH zP6pP&RziJP;Jb|xhM+(y_kE>44WRUVh5SqKw%o$yUld21&Sf%}so2NS$Ef0#>~;f_ z>*}d6UQ9ai%WLHV$3tC(nGwK}lNbm!xR;NJ>-5XA>Sx_tYrw0tZB>DdC2}mvDd=bU z{Wz5&c5KP-ipys zaB%SGV@a?@XgySH#N}>w_sXaP){u0Wqy_{F6C@rA0SyUc8$_z5c^HSFo_N%QPx5~< znHIyD)6$M(^(Q@Y-Ek+-9ROW>+B0Z5jHJHm2aY{zgn_IWo$Fm?!|S=U$IetG`mO7t zap@OZ?W+oeF0DxJ0M$VQDOt?GSZ6S4Q`aZg05PU|58tBnIAY^M6u#ZEmP{DKU0ml) zs=LhC$-h5yU@IdjC1GmS*#`J}8vIZ=Olw6!HogRW12_LD!TZ8`$pI*WUpAa6G1i77 zGkxFj48I)kwDWG`c4!n??+_M-<{Fg6uP*QM{#btfiV5(>d^T!J9Hmy4ijkr_PUvb= z&QEGmB`st1sZ+No;86SyBLKeL5LvkC`%T>{p=9&Rm0ORk0WL~3DN~`7>l^W#0ZDei zFEgSsk%f9mVH!Q z^T1uvda@YGm=_83$i^w$v&|vap4}lBnjRzLL6@#)YiUo!Vf-Q@l9uQvT+ttXuI@Ll zvHgglE4xn_eg^ns= z({JPe1Olz&krGV^G|@UhXmVyvaEsGVpuNQ}L!f57ne}%&z%`G%{ln0YkF8>Y9^(}s zN2vl-EV|98PSr`lE$(tXW}(l0kxi}Jq5GtiU0YHrry;=kOVdUpAhniD8tY8lc>PcG zg=lu^rl$LBaAmF#{64g-z;d9g`lkil(OxMDh8`Y9(xk8uD#lFzqJcuIXCPGT8ltBA z7$6j}zbDXAA!a5Qm-y_VAu&N}OMWf)avzXm@EzFKUuUFt3;qtYh>+8o*IhABYE zS&|~N*Cok4h7(AEkpG!Clg3|!mhCa=H1=useF^B;84d}cXw{J*@4L&eB}vN0OcL?- zU7jL~G*k=aE1M47Fe7kD9%0@eW#9i93(!H?{qxI57Of?ajGCSsG}9BL%tv*^&)>5_ z6Ky7az5fs@A1Qc}f*eLVPIDhGThB(oD(SN!~tzoFf% z+KjEln`VgEFI1ilzo$Dib=#*)Spk#4SQB?7JM=kG2!(6TVE0^t^wU)dMEIE3Qc1|LOV~96HVP2DY6x}L-Cj+8zWl&FoXf) z)JKkJCUJBgh0YQ-W?UtN+vpF3(%axtZgx=><{dymZ#Nj&rJXNinUjG(4=~{W17n~+ zRyYp9W0cWVoRb$3KM!@2KyRfmIIg$v=z@2_{0lHej*eknK3%|t?sYxSmWYOUaEd&5`$ zflKjp(MB^QV4+uRn}Hl60uUdl;_)Kl+~-m0lY4!PT{H$qS%n_qNe0m3PoYJTz})2- zh-2B$jPfK?Y2Sr67uEMBHr^zUF_P+P(u}b&HapiNv)|U%Iyh^trMrIaoz=zOxX@^J zqInI)GEd@$!3pw$U2;}`Knnbg#r)8H@N~TFsI*XS&>B0t>In!J1LV+K&W45N|5SRs zIk?{)Tb`D(PKX%AHlrYkVaTmuJt2}!|E8egd&P_vf+(J z_d|||1g&r3yvo=b39l4ZEpPCW9BNWR?_%V(IIa;h-IcK?RULQ^Ih>HtHh9)-MBK>z z8zs80tBY(^B>FD-7pUpSBy{-5HL^BZ^qlnY%ItIGSs-FH*Tw^z z+kdF%Y(70ovFZL6*qGlMbJMY`6TNN8uYkUJbwEXREAh^`oF(L*2L3w zC2d2>-hPh^V$3zWg!9t{;rdUpIOwuRn0&M1pTR)0aATuH1O;>K^SDHM060}LZMLm5&GI%Q1omKlzf zvv~PaU<*y3!CD}Gs2iPnq`HGBvD~EYoY*Bca+K8(;D!7A`|U0#ho2?vNI|XBl-M=f zCiL3!&Es@;DyVS|5G@$-|C}`s9_~8NoPh>N?-BsPP^ ztl%ZU#8Vs>49N$IuhsfsLy1*=W(k%a^~`SBPrDB7YR(eoG9u`hpNDmse`a_g7c2zs z?95^s^uKsrx?gq$?6cf8ZWl&mh~x-O-wIuKqSxo~q7EPzrm`=Cj29eiuCC8JmEPGF zS><8;0EK!gD{&jD(((J7HHN-Aj0`I*w=sv#3~qzY6|HrX5*L7#OZp(G2 z>^rnU#{9gHU9|~$Qd7b_d8g8*1h;YLYFk;q{OUzXL_9@b-h>}oQ_x#^lU)mT?S!g> zDltx{I8C?@L9#|PUCFWB?ocdzGNIgYuErWFFfQ#qI&r@4q9I)&GL243xB4Wj<2m_p zvB?P8DpaXXxKA;m9{(4agBX``YMx7HsWJHRlT=~UC_tn>E^&kFSALMo4Dv-32?5?6 z`U(!y1wObX%wS-nbPi!I=!6>?><2sybQ|CMfth(wEn{RfeSEgg-r}E+7G@qTHBS{u zp#54-Wy?tf^GR39mIfOf(wLY7ETRK0aJMebeNUYK6oyHzP7=D)F>u^d`pq{A#)WS? z1^MYO0=7yzVK)pjZ#Q2rhP?8jQqC{KN&Dko(QX$}14B9~K2c=+-@{?O%kf#>`Fe}u zl*TZ_GGvRO(OMK|ww|1Rj`InUi*7kSRC)#HTPY;#MDFr!*;uu?SV)mKQ)@GF~MRVBz(C~vR z{;_)c?&_PVh-KY=^(VEq(ri+DWDiV?@ebCX2AVJ+`1Hi#q7;GF2jRGRzm8W>RbFfx zrir>J!)FZtlIjzYck56T!NSqp)y>7i#NmIv{+Ara!SR35#dvwx$^PF$V3o14ce8Lw zj+-I?4)hdUH(JrV-*k>~l%<1*2nS72l`Sqb>$B~pe~+1T!A3~R$5@WS|NZ{=^TDQ* z4+>h|OkdeSOBqUDv3U0Q^Y!fT{p5Di^9oC3UQU5wnx$qM&P?v_t)fXN9JW<@c7svW zP4kZ`d~#`v=1DE5;ZnPgV9Qz^1Hax3kv|c1z$vm`Rh#9IsNR?5s{?HD7OIm{2Y)zu z>d;$zm2X3r*VDYNf zpzr-)!bcNb>N|Wpf9_`*J6jA?B<64du&Jec=5_87?wkabsLsk`dohO7ZA`2MDr*_g z&5q4C_B5?&878=BDeby>s%^+6PLvjdbFOXq4CQ`^!ph_fPw!Ym3hySNu?eVk>MVD- zbo*U>#;ar}^TgTLI3C=Q5-Wr1-@0YuI^aYbRRa{vy zw(C(vj05`=FAQ5f)k@9efRA)9J!D^OCCq;BjZ zN`V(N{Jh_NjSxnZsRpXnwm~Rqqc}dE@>p+)<@I#6$gA)Ct8czUj3E?JX6oC^W6&F zNr>Ho3P>aW2*D5OJ(@HKE{Tm?Y8?Lc&z@CWaG|>LS#1nfoSVF*#3-f&&AH$cW@FA3 zZk^fT8@_!%hdL&vbdrPhVdpnYuI>~P> z_Q{*iq7VIEKq1i`({K)zlUkG5P@2%N zpdBUVApQZI4R{dp(S@<$BC=%`7C^$qe{+U90%u#Z^<7cay`vh;5e;X>8)ePW4Pte- zY=D55>1OYqLFy(W>OW;6{QC&CG$OA;UL4>*Nm@x1!o;m?I&Z7Uypzg7j^IObEcRN! z7R|}RaY_dwga@G=`QvT6sA}hYc+Mz- z10hn|-+APBfJ;HXhkeS9nER;IIQ7?+lFv<6o{aH-|EgE7B#-UrzRS!%3sfMvtDC!C z8*4npUMxI&C>0oA3ngG8gLYrl8GC7>u`x)E9F*K!(ALj`47S-9hLnU~VTX+hl%dS; zt`q^mjb;A?XFON#NdV=)u8(8!QypGNTPfrdw#-8XKFgMQl*#AW|GbMsRsMQdUY*^- zoAiiaHaEWG@c+gQadGFUph*T|$NCWD@{|uG_Kgb96kUW${PzbZWNq^_6%jr%Gfrj|heAeI-eh|ejs3?%?REyc zkis`+yR{`kw{@-RE138>8A7327E_5GdX$H+Aj#OLNw!y*ls5qgy16{oXZ1WQ=qT*N zr4Ps1u&e+P2l1U39FC)5x_={_BEZWI&ZMG9*;uAAH5LYnZZ5+9tNk>4yP|Ef%CF|+ z2jSeCUyDUne$GAyHP52mamphec(&yq*C;6#holhx8a;|D@tMJ06SU&6 zyy^W4%bSKyH9ma{7$f;k@LVJRmDHgS&YaX=N2JO6vW?zJ)}E&sgn9jgpGe;b%F5U6rdX6%`< z$-kw}dz~xhK|&;rE6W5XT3b8-bRX=ifY@Mwm{hre>lf&AD^gzfjJ#q+X z(v8magKl94Gde7M8VtJ0=x)5GWQIDs_OSiRBa(*Q8zy!{pe$@o&gRBP?^y(r>h>dG z{n=554BK@GqN3Ix0gz>oux-hQ);;EhQYXli!Jyg^rbv0)=PnTbJ6K(sq`IYbxRX6i zq4|wN``aU9j)Qa)FaH6X`00b&Tbj+04dn^}=JP>^q|?_x%h{`dY&lh!D;+5y|0Ce! zwI5Zu&AhtS3%PP_1v7HGzmNc^X!pQV5_}cZXN66727ur*z~32Se7WmLJw7`6YX*52 zh#+B-ddK~t?vgKa$joH-3X#dG!NF=kyJOs3NA8XEcNL(bm8SXgoFf884{s{bRk|HI zMac$l!3e~Txx8v1clzE99Atk%>=zi$|6jnE|9^ln%zxQBc5e1$bTWEi^1Fi5Iv-m1 zkMQ1S#*I|Aabqm@vpXvOYyo4JrE^yy$0>egP@;W8j(QV9@Ir77k3suidFXu z9ndB4=2qcsnUJVysl$uEOF%Ed8H!DzX|AL7s1ndruG0`?o4UPLA36U}WH9obaQHW) zmDGOrbtPl=?=IxK4i5`pQ}M9!_R-Ns=jeL8+z(S{{N=UVfQ8g(9&b|k-=d_67H~uY5nK5%dIZZXOcql3gg9ivyabpZ@_%vPC+KOdFXW5@+D9Vb`}Yo1y1qo*<3@anD$$Z}yF3WK5dc zs&MeLvW^+bP$fiApF>En_(6Z=;4FilB({sv>cC9oGOBO_G1txH21tq&vB2i_!TBtd zd;+H<@erWA+cCxJSwTC{@?PLF#$Rfss8t|au^5F@GX-{W&ALCvNb+OBO0~S1;|RK#0*nQW>|NWa z89x!$`;}*b*|M^ShIvl8<363F5UbIepE=XPJt^&!1;#Su1J?G$i0i8%>sUDhk{+Ve zf(eI^VlP=d1bVf|{tN9zKx@NYQ;nwA!m34Ewc*{%N#1HL!5iCzkJLBKssd}oR#~mJ zK{Gyj@!{1g0keLhW9)l}p)ex`9_!SYLGABiTMx6q+{+}=l5a%FG4mMS^vbkJGqeDZ zu#rF?)hAwR3R{#k3TZZC#8Os^FQODlZ_B|6bxDD(hm@;Eil-MKXYIXBhFI6pHt#kXKUGauKno0T;~TC_S(YJBM}w)7)JLz89_@KS!u=3&+C{o4tc}*68`Dy9A=>YzyVPGLjVJx zf{;*j+%43pUtz3p;xM81kl;BD;lki<5eW5`G5>;4l4$iE5^p7hh4bvUFzB>NA7ARK z{~ij9QXF>0s=hxvHry05sN@u~>fQ+)yfXeG+=Fg`f9>&G?VqIj&ZSrgDd{AwIlc`h zKfjsY>EABp-*adV{u}7^evt+*(YJOC)HiImIQ6I4GZo>7TXb z9Ij-p^tB_WH7E;F&7Dru19Az_sXYkP1VHo^A76S{2yf0f3&v6l*KI^p)1RFJZ=|Ds zOm6>kJJ8!AaPj<)_26dBPR7o~$Myf`usO(hxH&nKZv?TRdAT|MzeILyBeZ6U9WIX| zr5rCE8^~>PhI(^ulVbvjZ4e1b($n)>xm++AbyXt>1R^72W+r2nqf;mK5xVl7di%2T z-}YJZ$vfIwZhGo^>ZgeWMIh|AizPvfd?i5 zn2B`sAdVG86liNiFs?+n3|R6GjJZi%XisOU?en`QRuE!8GMN0gsJjmjSi07JRcAOn z@EMq5Vv}lKL5W@#Fi9#X6v?+wMyT`{N`ea-YP#c#3uZ8n2LMg1h{(L{1#HW?k+K); z5M0u`uK;934e8cfT`T$v9<3fShG>@r01uP%ZREv+hTOn2*g?bV-y0sn1P?6)tkSH}_ET8Iq8mTaB<{45-7m zpDX3d*-B%w6}59|;H^dd$C4LBGB`)4q3$Uy;_PPTCOo|5h0=T2iF z=>7{6UQ!7FwH6l%B;(x=@$m)!?kf!k0bbw?M_>%=3ZjJjBK#OeYWVL9%mY{(u*UG6 ziKK8~?+@=s)2}ins#N_$Pd)eB%s5;c+8X~^A0HaGfS9y&32JY?ksMSnD-}Hq6i7-+ z8VvaNPXg2nz|KJqd{Nz^S|NuBW01Y*bo0VKcuxHQqV?%&`r0%r2 zoBW2ggW8@cM>lcQk^mkA0Y~*Z4DGD(gRGY%lHz?)BLPor=Hie(alBuzqaX3-XQlCNFCSKF7kQ%c*PN|JB8d7DxeVq= zZpo8?_O3u;zFGJEwvA(NyrXx?HsC|ze8aYAY~PjYY?)GeC3zDk;m=ChXBa^F5(`pz z0!vo4I=7rqR(kaFRDs9nk{Bc1a$58|^&J=OiqFzp-u9w@+Kund907#sUuV(dU z*iG|QJ4yGhbv7mzN^&1r8NV}S8Ozsuc4#Lz2yr7w3;K%eVf~t=o`VE+BkLn*GX7^0 zo-RI&T4f60DSHfsTn^l~CZ+2Lf~l(`3&o3mGe(@* z_f>^FZ1CSF8VzBR++c93uwIopMPh!lDh}XtRvgkHFgn+`VbIBBNV#WWRa)S@V6T2q zIX!rm!>!XVb{Rd0PG`TVNxmILT)5`^oi6#f6nqZYMoFE^P2{}z0>3J4NpU~nKI>ki zxCP5^5gpf>pEPR57C$488EsYfrWV(Uk&%!nbd)%)U?8k=sDA&g`k{u_G@ma2j^$=jEsUX zM3d=dbpq+rPZEp(C4)y!yt9=ZB6AP*1nN5Vp=<$?x$C!T65yq1`00oCt}qsh+Cc7i z@IF1#G86b+dye;Hl{d!v-GF)|!i$omZTI0k@0)4=I|jYOZZ-}E^+OZ;#TkSNJC`2) z2EE6>Q&xJ9Z}i2q^2Wa3xJS|!MyLF7&*V!tY0cy+bZQ8STB5Z`hIINwQ!l^MFs_&f zvBUe2kyoy^PX&+w0iYh|*ek@32a%>us<0{zabITE( zW%2kfX{neH9KExLJ@Cb}HAtaPL^QEpLB1=HO|U<9{{SK>dQa~ziS1Z7t=k4dy%3{N z>w*RB3EmcSGPINKwjhs$6MYs}9RJGdv@$oZUtIq-B&y~vBquiTQ51bk>UUzr#9D*V zU_MX}o`$J`YzPvKI`jK?c_5qbjJvK`Ztc7}QD&o`!~#CNZghpWn*QD6+-(d0R)6Jo zI=?5DLIcRc_*ob-~j{I#WUhbburrGI>IN{cJtr1;$RFjqH?8X zg$YlV06b;hC)4x0s;Vr;ETJ`CR=hAB55Dcuk(uDva-9&u4|$YEQl^p+At7Oa?@b%I z(|Dl*Y^LAtTC3=-e=S07GECAjms1J~Jv?sWio5HW@uqiBv>Wzy~)3ElN zPc(i#{daLBr#S9A5l(7VwxY%-SXH~XE2RzT_?qBbwpvd=8dnnCt?B#)|HSD?6r-9h zMW&m7Pfu%Q7HzqgV%V3Y9^nBv(p~t_o=*$Td$+zvqUVosaMcL7ZiS1O1m1P4Xaear zwXZF>ExY0&BvikCVlAYnZp~UnMoK@l4_%PctS_=BUZ2BH(p6cs$BVAca~yxr`s0$A zRhZ5g)qX?Qo(3@;)%bKDCg@>MmI_grv@tHdkDWneZj*=x7x0rot;Z>3{g{kpqqyo@2C>0yjhE)jjX!@cp93T3e@X857WI%=2Wl z&QRXeala*X%#S8r*9L0wCh~5y0ldxX3IXEy^N5S%r24WdHp=D8tZiy~xV<7eWQjfK z7pl%pp|F&jwDsST>dT$wy7@P8rVaLde#-rpZsf(umY!QgHZ+!q3SOs8aoCyHV$j*53QuDgN^0L!$`X_mo#QMU;ytzz~^e z%4Fc(dUs)EUm0Q_!**;TK2IofGYax_w~shr{aJXScJ0q>qSMOAJmsuc&Kv3V%3`(o z#$>5|VWGRnLTMS9R3+>#+jpGtpEO9NcMvGY_M|0zE$TiPh-WLlu> zmQMV3%;p;C~YGZYzcPec0 zK1=&$Q1!NlI@}Yu`T*yftLUXFswtwwIygav6g}Yhh%uPvNnmT$Mzh_ayJ9^y{B)kR z9kpTpopWR~y-{-LpCH-r4>IfU#FGB6UB2*5`)c8DhnEBhjOSa#wO!(4#h)#rXNPcm z*9b0x)Zig4s~O2Zcu9+83>7^ktk?7u1MgeY=g7H_+8$g^BLRWNn)md#C!Sj3tNjNX z^T~#`Uczq2*Co-S+%ESk0_irYc~I$eTyVBYknio2i0UrFCVc3&1J+$0M8RhY~Xzl6ab(Q#Ra$?)WHW%ppt#A@EIH&}g~7H>=5Y;J*=y z(tSVI&))u#lSffJALYkP6}qK^W@h(ky*}uVU~_5({v8aE7k#%;kzp1Y6J9Hc9!TbDdhMN-SHueR3kv;n(o}j^ z%;Mo7HRO%;2y>6YAB=HN1MjjRv!*>ajM}l(R3GH)=_L4_(u$H84{^Kb`cX9I4h#1E z*xr@G>oh?biy;^G=-{@=sC2`#QFWNCpAQtqW7Q0Xs{6#F7bz6&Qs7rX;^S)ZxPkI^ zJ8PnA3$&xYD|5g}F7a$}VdCMe5tZb}l-;lsDz25C^B7jR>09U+;r6oI>303VvqF|v zr~;Z6M7f?@S@>O-@gdjH-48!#%w}E@H?m!#0<_*)@+3U&Rf-_4n@cm1Y;V`0o`OS7dWzgv@j8POeF^(x&~#F%>h7x!7>>rrOFVk{R`RU|?1V*mGu3={JRD4(c9(#dF z*noZ%vj|@a8%L3bcS2xs^?zrhT$X;KmG(9%D&wm}r##8q?0&*MvH$r zU-yn`TxjNaRvQRKF6%xu7#`_vt{41GV!vFSdxncoEg~XF48!oi7SggX)Cj|Jhmy6!TW#85 zC^QJgNFpA7-qvn^wdIc819Wm zU#z7LUl*&qGaEBEFtcAmU3lIY0cd1ZOzg~WedxI{-1g~>=@hf*lxvGqkeod9;a47?&THbi?yHvKvk>m+V+at7< z4$$R|dR=cVxg>t!+x6ozo;r^{w8CZv^hr~GKD03ZnX!yG#4 zKa$KBlqrXi^;EYqhGie~P8=kuoq`P>5N$6qeS{WJnq<#q+FFn&LbbQXwBHcK&93%3 zQAi7&xM?Q&2I)Z;7ZV14cEbq~Nk@shiFO9-#{BZi=qnGC4NI1v$u-{cJnF8gdP)P+@AiAi2Sxk2~c3ObT^IfLeU3`CFR}E@0Wk;_4zZc$N zK4$bGI3rubXbSqxrb>AJy^{Oeow*bg6Hyy2EU#ZVNM&4X(%0la0iLhhau*WX`nZGY z%PbMAcjKz1(TaDoB3w=greTrd?I1Z580DwftN0YU4yOeXukMuL#54Lf_c+e;JmDfH z$|fjlKYW$$B8z1fvJDR}Vj}SG9sL&hcXibnajC-<)u%quN^WB7-6&gjKK46=sj}~X z{~xx_fjQ7N3eVBTw(V?e+qO2gZM?B<+qP|IH@3O4z3Dg8&a~6^N1S=ioa?@?$5_Fd zrE#2sz4CC05_p7XzLJy}Vj+*{Vp8yoV}J8C2qAR{wsZn)(4FD76*S3;zksi`mB8i=rJeEF+pB4|3t1In z-6sBeFS#PuAGTMxF}Wx;3IvMxUL5>=LG}7=Zz>r9`CI9XvHBZR_T1|V4nS!Z&hPUK zq2IqT%4)NsNhWtUqe7A)I{+n*C1M5yyAfFv(57?qcOXgN#2;-|H_IZ-$@YuFYtpi_ zU45IG(kY#p1{W-lRG7xm*32o<)#G#eaib|86Z+ zg0-o@(7)OQ9(O%0sD}w*I(4P?x%}$<`a(ID%WUeslo+I4D^^yx40v%;K^oSa=n#-*157eV3B*z)k-OCuo_{01i4iU!8v3`egI6m6Fy z&P+L$Dj{=osRh|RYZ(57J^x%AOyq>-+vd=@_{L~l(SK}ZWQ}9r@w~XBG=z_V&X<={E(|i@KwvS8ChzQ zOn|MGu!NO5wI<(rnx6N$1wTCo)DFzCygD0x$nq6mIwfgXeI}i=Wr($^b@9w}BX@K_ zp4aS}s!h~L=Ob+rB4z}Vx`wW@!-h#Vi!At6gBy&1&i-4{V$5p0iwRhSPrd?8< zVy9Zrv7`|RKPRi&yuj+4!SwBj;lUuRsDGI9;(ukew&H=@&u2 zc~ui?&La7(;L;k*`u-7vEsh(``@Ou^7|yzzx3u=JiYW{z0WY@&k=$9R#kOR<5*YVt zV#@)x(6sq^6sNyT{Lfd1KT8*VL7fv$J+mrh$$r+EI*jW+j%H*c6o`-j!GsLg^$+bUm273%sU zx&<#toRl7$PmZ~>4U#ZY?kV;d&16x)(&)aE`Aqq(;{jlUxOVD>L>Zq>JL-2awD*F; zr&#yc*4(?`C6iO@5SeF8ogZySKBfL{3(fce7z6C@D#sNyDE7`@l;0bbHzw=TCkw8< zMUIpNMAPNv?fr3mLikY07xMFg*z0n4lD#rb8046|qp$`3@%pEhR|G}N&sSnk49-1o z5Y8LP>j1va9W5zZorHR+`R=6&QN%A9FBRG>-*l+mWxaWsIpbb?whx(vd-Nj2EwaM| zl~js7JE!^Rcs({~8A44x)5o(9>z}%5>|WFoe{CBJuRZr$9Qx9PQ|fT4ZDs;0eAx4F zo{p2e_>2mTD&tG&HCEbkXNqz%VFhIH9Pej~NCBnM^q5cqpHxAPuV=|baM1NX6UtzYoa?(mtn={qX7DQIktdljm~N#d9kD<>3%at#PhPcEc%g z;|>1aiLh!wz^VgI!btGyVXIW^8Q%Uv@qCi$5RV4C9Y{6jrHGca^R?6Ia`V(z_@qtW ztM|^&j`f8YgIUcC#>t&ze@7UgulU^pO9#A3r`(jJvVfQB(~F)WaW~TIq>9!+VVt`; zG-BKn4lOVt-9bl1#P!P3mEpZGFJ|xA#nrG-2qOFA$8t-(aWDV!kEf0-_8G~BlK~{&*LrmGF&F+PMS=1lhwm(|9%wHMVv)M+qa*l z;}>biKh&>H_a%;k-QKB30ZmBdn_O9L(t`?i#0#y}#YyqMKC9HN^a)fa*Wk8YXw~f; zBr*{%q9+tiy(@+KDejq%TjDWJHUNXnQVy{me$wV$J%w4?>;jc_`j+;imp_`qV@?{; ziyzS}XSTeHi}!kfX_Yto(3^J0_N(OtH<5Wmi1IEWZ`I{UfQLUNMQ4IJsUfZEhG0|o z&i&PWu*~GYYghS<Z`6dzDgEqv|QRCf_*Iifm-!K)txun2q z1HV=`Ts=`iSZ%SsP6>oI`Syc;#GDC&9r~UPNq*l058aT}fMh(nDpR^lfzE#krCXFe zk6k=f)*EMe84%@y6(OhL%fLXzuV5TBtgV*#%rg@xlMpNmC~-Ddi59Dt85@O6mCe}P zZ{I$;6YB?>TUbs9A=b`Hl#MQqfm2~kQ2`tAml~TfyP26d-ur-Z^3I`Ib^e99)w|>+ z>9Y|yIzqDrq-)9g@_bV%&VQzJsmm{-;i7Kig@H$La1iW|x~>Rppc*Jk$yRjhaQGM9 z|Cyq~^>aAfrb`n^WbGlop&T|+RR3?z`yb}z`u}2HW{&@jdD*#>Z+NjFxY^nNXH_xQ z14=DA!EC-S#Gprk5GkW{YRO`R*OZojwcd0>kK_A$4V`91tyJau}tBKYu`i zL5LF?h@r{F1}CjT2Dpd6+f*I12ABaY2w0joB4`SD{Gj2@6cR2zC8$scO95BNfKX6F zX6ai!X=G?(2r%hS1TiCW&?#ij5PBg=-%rm|1j?WGc+~?%mUFbtA-fX zgmHQp>AzGFJ_w}aPy9p3_8-4m;D3j941BjxN)5s=ISUyAyzt8ITprMnhy!>zC`??a z(MVnqEukhLuZy5zxEmn+Z1`_@HD7oGNUtv3APvN?2Iv3849G=@fghrVOet`bl6Mfrn5+32gwDPy{PxXnc5wF!CHSHQ{ZwE3}ZhFcHY0$7{LZPxxS= z!-gQOkO%SjfoQf@8x7$N+QMJI_N4IB4vGZKARrNkce|->=N)qss69$vc6oUr7FMo{ z5H`at3z$*&-;wJIKcRv-l|MJlk;XyAgbzGIN5w%MH9@w(Pe6LO1||SBgzsYrgN!@= zSMOqF%K(Btgbv0b#JKOm+cA-?JrMj8lC9MbL4xls<$ysDT?lxnfT1fCsVKl=JbT~0 z|K;_~1ep*74mr=?5ajIOp+1!&&!~;Mr1`Xezh45LjdgWJnfdTz@xDJNDvBB@pgo`g zSx86<9Reg+Yy{Nf4i4A_PCB84KPwLfjoB02sRzWHqP_31o;+sl0jYs6NfN#QfO1iM zzY-40@jLq*NvMbz`ybpVaPm=~@J%$!*z{R1_k9zkM#RJWeed!O`6=ih0XMY%fCQ$v z9nRGQ@2cd!4f|cIN6gKh_GF(6NFs zQ$axPP~8K60U3bq2&fR7zdrS*K^c$(=@T)yH~l7#=1T+I05C*|F9E~U0`bL$D#CH< z!n05qurt?SvfvBkcr;MvB4FTN8m1izsYVxXT*EUlFtx_Z^8|+KbmJO&;;X?mnem%D z(aW~%d89sIwpDb`w!bs(9(rYq?{+?ZULL9;K+MYl$>jM zDsP|a%l~M0a--{{p6bjUo9$(F#g)T2_@hH6+ZiD{BrN0qB%L7+8>}1r%7bJOGp09PcH2WsjxS=TNEH9DVlE8PBFzq?82GR)b|ziz567K1hE5vNRcvz^J=j2HM0H zfQfQ-(I>ou_}zaa!j1;5+JW&yjG)#hw+^ig)RpEpyFU5oi@j7PeEUYUo8V0edCJ!e z@K3dkMtj~sbwnI=39u&q#kn&fyLz}i^pewOm8cP9E`WXKXr)ADq^y`XHK@7wPX3Zy z9e@7l1EzVHC&5lPbH!#Zc^{+367Sy+Ec_xz6QZQPJFpphk89v(U33qdVdsd(v}toW zJ?xuy(=EHS-Nk|VPdl) zq3j2Kb_m76WUHG)c<>`#($tl6G2yO237(RA9mz%upkeDbN7;K5nl*xy&!K<9oGW~B=->d3SqJmWz}}&Y^p=N|5U&qAI7Bbi_sG{^|})+ zSI7Tc`x&eDyu($7^C}9PVnwsGICl`OZ?5WeR+W4CDEG8U`JoEh=GK1k zS!yeucZz$g>W7(nWWeQI+zr0yJ;lq;FnY@FdDx__#$CIrPBk#g_m!v(yeMc#*kGyI z!r<3BEpZiy&tm+9`ete)qC;ylU)7@OJ+E-PHw_uC9Q1MsTl5|e9Zup=Hx@1+W3o6e zLlf)1L0Mcfiu$w1-|!M1a3SY9k#kFBqFsfyqg1^5HS1nNV$gS*;vH^-RPPen+N%7R zWhV3U5p#y%>boL0H5IM{5NOmgNqMM*dKwmGB7M~0>2V4M>kud0X&IWj4-4FR zc=Z`(-z~^d+PV)}e;A;A?*6A+*HOUTO}5Liaa;(I7lrI(EE@3aDYz?aKy@s|PG}g2{;K(A5%m{t8!OFpqQ>Gn zkwX*j9+D_$SdI-Fpog)CIl=&W*R9kV#~*!C3mKn*11=2j2;k-=}6> znzja`UShjePG$0;c=Kn5x9e9~&TCF#A0AfR#X2J2VKGl-(YIiXEIGSL^6EJHgkVmQo`I)|>DF#0=Z z`?SOTu>`nm&^Gcgu^}~aF^dWg~ zIAa*B6Ew^cfEONlNjags$Zgu2W*c_*HZ5Z%g2sw!iY6osDtj?0&JA!f`*mE@t+|7M zMX(a*M~YN|p0Uiq*=Yd(MQNO7_6Ny(?M8~Rn&q$Bv4PuWO|v|2S?TqjwnvSV^Qiti zm=M*{+k{kZDHONwN#+hH=k;G6!9hqmWJNQvf}qfK0Mhs8I>>QaW%Trnek|x>m)WmK zIT&k`F~heFWZ?pcLbaEKvC>vy^?Hc7AWYy;QHWlI^fcbxn6S=;yXGhlUH!T*HGX+H zaJeT(GWoYy`RhH}gN$OzcsS2^6VW7Lr+QeuY6PL@%002e6uVhw4c|(QNspV<)cDHq zB?QbI&{*)2^|xKN^08e0pJn+Vubt62wP=N?EF<60@cQS2IF4J7jgxjRA*b{Oc;H8S zF}8zQtxcP1#Y2PP?z#&*S&)hp_Y(sAm9 zm!usUllgC_c>QD%@CiFHN)9YV4su}-cOhS(aMdZZEb|egy|b*}Jl~KU7|9*p<(Bpt zPPu6}>L9ZxQoQ^y^DJ3$S08Qk+bXPqN`5@FHg30RZc#Gkz%fl%Il1V?7l?j+POO32 zlCm0&6b%?Jv$(GqgefZM(gY6l;Xs>Q-ZDFV;l(sE=%#FFww3d6ty(XZn{xYjo#9IL zI-G;L6TD%u{$9+(tE>FiZar9^FkJFR00Y=H744fv|BHc||Oh$+Z8HJ1fD}7yzThY&Qtlj-2SC*)iV^%I{srkiu?7)@pdoS5*wD2 zuiWr^M-0VNm|~@W?EYBx_surVI?AXtS9*r3I$`~&pYJwcjj+>oEnUM>{lb4yg4f;kD;fQJHncrDzd`(jC zwL1A*>{7aq_RuUcuf1@O2Dfv$m9|df^@g{r1fowp$OdTk9_>JTjt`}(6``J69M90( z1eXgq{OCPgr4eXKs`iy=;#Ae+ z-AVQ`d%2UTOSIY}o*3&|Rx?zO73p$M%{gBnRp)h^(@KS-=z$N(-Njj>_@N1h$%n3@M& zhc;!&sNovgpjbLO@$=q0Kym>qrhQ8zN(_BwoJalWSJs9LwHLdmOYO98cL~kO(lc0{ zkiWr|CmHMUXVQLozUzKq9EWsFiPhcmMH_pj)Vbc=v()wq+s;@RKvcUdfMY{YXKKJ*Uv%QAF~;O)*-hX}U*MkAyXR zJmB)#g8C2u|LejMBP8fo+aP_W6fvj**^k&v^2e75I6+_ETB|QRV47+r^&n%yPVn)o zi&>{+b`jPmy?2NG8`$H{H$uI>03!JoJ5}BK$w;}w`7s8lkbu#O%E=DiRcK25W?ZZ- ziavg-rK%4_)iE{jU%Yq3u%FNOv52KJrI$B|ecNL-eNSYCPuXN_u0f?U*hwMoATebR zubfMtIWbpHrw^=`+q%fFBTS{;{a*UI(@v<5wi>G%nAgem3I%1XLBRZrmyGfB)G0Ga`^Y+2pzHi!@Yy-x1o2)2AY3T7&jfWgy_W!$dj@@y@FWbeF5+Fk~(MkCD z=!f-ZsNL6zT_MZyQRt!jsm?n$KZz_-a$>O^pGoxF&HT^isFSvQ!AJxn+WlaA^50L) z)Je(f2w6R^N89QXUp(2FEW1_>5|jFtH@-GXL!E0!v#;V+vr0>w=~wd@qJKmM-o9R3 z$Q~lVdS5ST+2cXoe?g&douF{p<$)A%Ri z^X*depEcqEt2k=NZwZx6yt&VNKOq~b1jXj{-aq)stGQd%`mCZh3_JGq`7IX*p3NTs zP&QZrlcGxZk$FH}Tk5D#%nEj%X+v6*6B_D9UL_umR~e&;Sk|w}tVgQyd-{X{Zm_Sp z`sgT+M*@jjv8ox)DX|2)fQ-789<50{*7+EYDd}-OVcwJ$|C}hx5fs6 zO>8?_J=NW47{k$H`bOM6RZ0D)muk?dl7AoUUSx4bBuJVMhC=zEM5oS!1ym-7XLB3iY(*%IEfpLB2}2za1xNp&NSdi;oaI*aTU zRVoW7r|U#Pik};PZTc(oN%0H+wVlC?brj*&rZ~}g3T$S#JK4vh=O}XK^mz-|B8Z-C zdhYot^iXP{+!l4GooPM%af!oU(AHN^aRqk_cDg*&ybIQ_(V?}It z)-=_$le-()jfNRn!P$?*S8LX~qv@Hdjd1%c&O365Co2hjI$R!~hrC1xtAj^UAp(v3 zsP`4#brud|IX&_a^2UzpRj83%ZwHdR`UDwKBsA70JVxc8rmP`%+et~CSqe2AZ)b_= zTu*wU@L6;vQDj?I9(O?RCz!UKunf7_xZtJTf_xWmuexLYVG4oeTe@y#il*a6;elvs z!O;#={$OG&X0I+^a~)Ayg*uwkk+k=ENGA)S`kQ<%c_NyoAchvB$5hU^>VI|DbfgRE zpP|&R&#ZhtLfki2;-id*Mg&hMrOcDn<#x^UBaagz1Q=A9Bga6{aZn!vO>$2ZWrSIy zXVYP2&TZ#YQ?ym!Q!bY!`4Qjbcy74Fuz6fn3jt{0t58=%{SOFs*4W>dL;SG!zozr< z>-!f094~ls3Is}9SrO2eyo0a|YJO_8c8|CBbFZ5fy9y*7qBGeWrhx4R?|-p@66sY` zxnp96IRD)SmBwAC zAi>@eLjzqIG4sypmgN-m85@#)9j;+G37{G(tAMFf+0=pEb+WLims^}$0!gYlN^;paQ3Lfs*M|3`u>%A zpfTtDv;0PSp9|}ggw8=={}0|2I#D2O1_!&-Z-rPCX8C6%#(qLv+@Tm3^DDBlgznv9%~+ncs<~AJ#H{hB z9}do1c`g92M80Uc=ee1$qw>sW!@ei79o0mqe{smYUJbhO&>{HSt4X6=j%f*VF)Sp;~F}TQ7`LhA!w0(ILVSXgUc&_+*Ho<)S40fiI zl*jdGo60}h-yrI{h}e=>o){UB_RlXQ7zT$*on{x{7155!?NJ16^UbsV!W5 zn8R{4c2?sq(pg!Ou59IFV3?QD57w=AX2nCIFs%&b2C0IWgg&>!N}4L4+6-R?&m+}8 znoWT*XI8%GVo0UA!b2D}wO(K<$~I(eIW*2*Fc00imn$lrv1@iqd>4HE}{Gf6?`FZC(WNF4_$|o5Jjyvok2fP;*gQBHRNjZDsFqP5N!zY8G`YRXsU6 zl2)nPmYrIrzellG=-RwDUH#&WiBF`CCG^rI4#U>oXbYE#-zk^9&4s|JJY?3ZO#ITia~b~5Zm3= zlAQhjhWJhVT+g%^*w>kZ4WYlB(lpZ}HxKnF2I^<%%4hb8Zyy51K{SP_G%YvZ?$08t z4Yf^gKy5A_!#{s#6M(;6Y|p_^5)O4sWR7Y+bF~)g%atgJ)+gdxrI^lS>;pC>2EXM) zy65?Ya~lsQ@MPo?7F_FIA~xcO)eG&@-Fkahxv3z27GX9)sJu4eS^ZGH|Cua~DC3wq zq4?_`XB|VGSwy$%Itht0&qHD`?LD}LdlGdf#?hi^4MgTKS3@r6x##bneK+17!WfMv zo@-?Ppt~6fol)uct#Q=^AANvns1=BWn{$;gBAJTAT~YU()6^QP{2HDnET|rz)|-H) z4BzE4?@a zrOb(AO-{Js{L3MVKK#saEMdu}sT09ot!n>jE*<1 z6x=Uf$Jx#|hUe%kRzCbs3nQPdgoDVl%s=MYZ;*YfkoNzV(XliApNuYfp9mA2g@gNl zHZNINIsX@xbN!*Vw7bGVA{8MOJ`&)HL_;$BdwUiHJO+`KiIq(%oH!_enx>K|g%nyP z2{maUmMtl$WQ2FD_vLH%M)%@lrRFKyCGYFf?^)nuJv@1KKuc*7XCE4rWY1E#ARz)? zNPHEV8Vnf)1q~Gig<}7REwIQap`Qt+90wvYh;$EN`Hn6K3JLh5C5I6+cJGSf7?6eq z4}uO3LSYu5!a_<4qKtxa4xpe&;RMjG;r)gGjR9s!vWJWgQw}>cj0EH6CTbG@wu(A% zI06SEBP$E@`Cs$0Q#3(|iV42}PNG|QtC5N)&ZFcl`z5ln8YphB>NdFaO#xP%CZ z76_zU(15ZQ5@QD|1k3;-BGbwe=$Vhu9x%ZJK!XMJdw_$$f_@WR*Z)_%RC;x=Xh=pI z+6ISz2_Dh|Wl+L~C_q|35&0Fe9qy+gV5lB4XlBE zr-eIkb_zL-UeFnwf2SK-d=GP||T6D$sEEpq)a8 zr2nB2z={6)ciA{ADdGpZLaKEI3QF4V|E<4ne0&@eF#P#X^n2UD$W7iYAr<#KKkC~~ zRYT$x3=Cpa93-d+l@w%;F;UtGOZXdrHvtLzCw~aMSr6$UgPaSl8`qy3;P`xFfXwgi z@BR2>O(O)W)`1Q<6(ns(Nkn!U@(=jlRr$WU2UK6{slOQ$zdb~V8L=pmE8Tv~GT4+s!Y*N_9*#A}mpr-{~%R3Q)b zC}^n(5CMr&4MZ?)lWVyU#2^v5;uaA%4k+Lup?m*bi+%*qGeYkL2_=30tsqAxhQE6p z+Tq3g7i$k7d8Y}2a{lxpy-R%jn<3fX@))@Xp=t`4`hp%4$pKRq|NV z{j@TZggak&fPNu9a1vg1@yBg4>`4%O{wg0Ap>`=*4t~KOmwHXjdvy?yn<2L>>cI8f z$FanG2l)oSmZYDmM7Xa|@ZDJU+jTQ6^C=$FfY+oWZ)LAz7FeoKnSCqz)~!|yO&_MTEiZNXsFz&30pem`u;N-fg;vNabt)`(-g&(ii1q<%wzY6#uL)75ts*!_q$-#^b!3lv6vl*X%Gy zCzLO9Y42GExgXGmZ0g*da8z!*Eu2S1;8b>0YH*v_J0Sq|f&fnq3`(u-lHmSeXQG$Q zGmOQ_U$%b)A7j_J%{S>WQ|+9JZ#~Br=H2vaW1p*t@$$IJv z`&L;$mIO54Fuq&Rn+89e%uS}~0U#+WBT%SaYX&un7ELx5)4jtQbZ2cjHLMhWn(TQfw zvBt61!_8C1?9KZ|tkBVMN@=;Z98N%%@s!0a6pT0M7`R-@|~07I`BXq%ei#qOE(^TPp0hyq8 zTH|!M!p|IzhrDhQ4mY>zgZG0S+ZCMW@hmql2lrj|oJC(9wZMMvQ=g51EHf0wQ)PNONQknTMGOB{HB zy?WcAX;J8T%!i8W-?;4T6H9lZL1*O0vHZS6Q?P70U(D#)7)U&jlYLvT8#x&^E6BV(WH|PTasYDdnj^_uwN6Ms6}j6Kq2hT(xi+T- z5ZxAEeRDr(t)mB8X2GYf7}43b1%PCq+Ed!@n*iu@)2cwuNJ^F5$f)j5^7!Gb@)M95 z;-(^KZ-S1HyFMh%#=Vo<>?m8e?_|<*hsT$$j^s2iZ$@0U`R&KKsxh#%CmK*r1CTqn zo?MA-E9ipd`mD~bHMjP@&UU($jChIEKUgW9^IXnRa(%>mye?9^Jv({Xd_exsOXsz; zA2vs9N@%mGM$D=Q>>4X5`l-XeucefX)S6Q7Pve^nn~p*Av!%VRm*lmO2ZTeUFU6d= z7#&HkA+hC&lc;qzOEqqt!%8|@GgY!a$hqf zf`1l1N#xpylJrrn>i^l)ebLPrRr>8l_{lU=NzBUJ!SjeX&rK2d2n~>X{Ze2KBMaV6 znzv5wwd|*o;B(&#|G|VxAPOHpj(UZmcSb&n&3=L~up{~pzRZv9*+KtV8EB#fZMro| z<2|IILv?-QCEyn+G6gqh?j0#K3o~xHFgI^P>qPKl9_E~+o_-2_Y{n`8L-4psi)jpT zXcZUl>g%y^aS%=v^z^LBCAWaYsRKlFftDEbGM3BtG+F)D zEch0aj_e!frRDa#hWiA0DU{3rPZ6fze@E&* zV{WTX(z&^QU0(nh!u{A$Qgd`pTlD!%&sHHY-z+`Z8NXwW!3>+mip5 zP^Itp>E=Kd5-xrYSrcY$33bNgvMPHv5Di#ZC4F5A>ANcuul09ZMJ*>olD}g-Rj7uvS93K^Wq-Xc%F8gG0g3O_nswkU2%4B4>!Hd?n)#X6&A1( ziY!EqdqXwWJDOqjVe%NHwf)-~lc()=6PRB`rh7S8ziuu?tb(S67pQtmZTZ#e4VD>| zC0epBkq2ywn0W9~#Tq#aRv;VwUhCr$Lm`|Al(sb`LPfLT;z%G&-)V}Hl$Jbn=KY!4 zm|#azKBH*%r~=#Gr8FF#OT%6h6~eI3$#Ru3YeCj2HtI(mZS=3C8lSA_q+2ajpgA$W z?Xi@g{$6wK$)LC7?>Vc(A-M9!9BjYy?JysQuPlK7-?yVCuQg8`5lF1y?1f*1{r2Th zT+VItt8UPY5iBQcUgetQ^r=e1BMvDXZDz4QXSi;f_$~`J+8#q7*n4sfyOgm#_>6Gu z9G`iNr4||scAgx8Ww8QpwCv66T@jj9xz*=< zE*fKYxdbw|zUCVrTM??cy z_=9Rv9;MX;ORRra6rnyGtG#^tTHbv|$N7PZVSX{l)?(uU)qZ9bQVtA^l@1UdDpHaM z!|E5^?w{49u8s>oB;%ztQwHHI5C=)Ji=+M}!ZQ$X$H%Wy+e{j%ae@i*%~W)C`%^A$ z=e_6cmi901)=%)}JXQOZHUVCWkJA-IMX)<$2x1|gyNI}mNSW)VDyA(>a<}!1y=E$77)sY~TA^VxR z{44b8+2C4}pez0i-_6uR@ml(r(jKMGPM7bUy+IRCRWXNJ z*m8vEhDK5r-O0>$eGZn+Eb_&6uT%fiL=Uw>`L@)0+`1GF{71+6$DDx07K?0|ipY!G zXzSZ@uGQb|wF@=Hzta=d4p3NM=zRvroxhngr!m=16PlVUr_AQi7eciOSzCbD0pSYf zZ|~S1tXgfQ6(RgBc3L*8$wxgWFa^~hxn8qx6F3314H>bO5}+?cV}T5Li6ppuj9-(u zA-}k_IX=g|RH4d0L;izCm}4jKcy`Y{vCa8$E04V7%WoRqW^_>p^)1D1O;R+zTselq zYjC({R{5q`p&ITb^w6vxj}>s-ZTN7cZjR|IdwT9W;I!UN^4PcLBmK+Y^yS937?$U$ z7{#kfnBfTg7c-~GrcXcf!V_q`#E1$zuK-D=-vCARi=w~n_OxP`ntoIx4PzYW-<1gy@oubc_@kq!WP^pR36$#yY`%xNOmPHNOS2hws<3?~ z31_=(S1Q#Oxkn#cjPV~&>dS9#l8l86m<;3w@AJU6XZNmzDf8H4%MPYCgpWu)545=qH3<@Y7pcKhtxRk$z35BBth zmI-V|eXNz_)gra`s=+207@goqdFhIS8)lsRj;pF#S@btl-toYVEHt6?h zY`Ko;vFsfx$92%SN$z#RJ^Nf9l_JeTMsggo<_^rp1W+lR z1VxwX4w?{|5@1psd(nVt)dBbq0qZe$#t1}n5&Y7@AeG83L%&4FYXud}IMg`5zobGY zb+Xpq&2+~m3ekn!%6CVG3)%N#P3K*5vKew_2*TQFs#VK9B}Bw)dA9vga)eT)-m})b zdIPH8PKJ={xVZ!b+$5+sCpR8BIlC8M)}`;lLpck&0ndAxSdp>`$rgD1V$r*zZPD7B ze`=aHsb+OK<$p{$X8-2ysaC>?{mP;Ins~O#bM}ewKZ9hQs5xJ7Nl4J>Te9&h)Kk)< zJh^yr|GvGPfJdOin}b-iyNNW%$7~Y*rr>=Kou9h%&mr-qjBdRdz5bJ~Ys)~*)}d-c zk^37K5r`JYXBAB!V@J0@71e_rVkBI`g|Rco*Y|V@ckO~xc7DNOY^_>(Q5gE1(>^av zvU;%BB8;o-p}TP0t!VQxD7>aHs?T%!D)B~r{Y%BI^Lht;ek|g9b3iy5^jh3Lz~UM6 zrKtW!j3n|;9V@2#KWof`wlY**?Lpmj<#5P$I)LfF!OSlBxY&`BA~D7@^T3^7pa zolzd9vV!h8J13zH@1xdLjKn+K-WGRMQ3&zwNO$J7Ad~g+R^GQ>|BffpJclj2`MF!) ze!wP+uTm4?#X`3i;nQv203NIf?u1$xta&S+^^m}zI?HV_6 z;F3O^QNGuD{jF9Yh8{xKFm035`Af6#1K`<%=9wz^;CEQ*!T?Uj>mb}9K9cIMv-+tz z^4h@SCHTEaz)rhy9Gk()4An0IRo7KJ|dt80$x@PavHP0fFbpL%vsUIC)&C>GVC z);n{TxS+UsSx=50bvpY$jM?{07mF_XWl37kMvTEROt78p7?&GR9Re ze~O)NZwq-6aEpKs%ZrXHHf*s|+p;=V%7K1~=pq{R{-0V6Xm#|@HP+oLfM3YPb4PH` z5`yGD|W4?=q0vDX5O8%o`;C?KY{w3&g|hPd(oKBWl#N=<>C5-P&-!j+CKxQ zZf=-I!lL!+35|NL`Ep$;T`SUhXN#=txT8RpZ?9Q( zh7xXShj{FW>ZmLjZRBuxg4bnxVV8LKhi~Gb%b2jGQwVTBUwNzpr0Vf>TV|qqQt6Is zJ#?9f$l&eJJ>Ec6YMo>=Fta=@g2rtuP=PJ=OBoIUpH zsGIWGo2--=cKzeGt~2ksF0*3yof>7cGrT%!EMoE7keR9BB!0JTMMk;dt?r<_>r^^S-BD_Dz47x@}LjYv{%f}4X8D-N5#W^8LE$JDxEilxhUBp#BK#ZG#7SHSZ(ur zUPw7qb#oHy8P#+XjC@ymetV7**VX@mDV`(PQP>m!TqIuXZ)NK@>drZ~yWo_{kU)F1`=O(hi(W&q@z#fHZ zxAOZRY@PFSSaH9tW7|n%tFdi1X2UkNtsOSD8{4*RJ85j&J~?OZ%zf|N^B?SAzO!dO zYd!1925g*9!xqsu(YcXN96V{eE$kAHPC)@2+W=v0@}|N96~cezHs#+g)r6wF^Zl5A z!~Pbet>3V-2+pFShA!e}#b(HO{-I}sFYm`DN#dU$62(em`%KEeg?ix@+;b<3 zM@T%0*KoZ5q%mfNe@wyb9R4m5om$_%*l9a73>>u$$~fN~(3n!6d^#1nUT>zVVvii0 z6;T#Zcf7NQC9Z^{Mjt1l%d|UiDpO4HqzHP@e`S%OC-pV+hDT5(j}371Y-PdGWV+rg z-PpK_qm`F4DNh;W@z&_pvD{y>5Ic2twWOXFJ3#c$QFw=y66U~eAf=_jPXXJx$7I(s zK$V&kV^et4TG*kG_UZCDSFTu=JQw-Jx`kuSn&?;!wfz>St~#lCY{|>|xLTp!V2A&Ecp880 zHYI*9yLmk%R{FG?b&8*^9fnlYwo3%7} zqozq`c$P>*IvO81g=~;_hK$(teoxjc=+p6)I^Cr}~Bs}_?-Yq?lO0Y2dB%*n5Hlyz(c14K~U^so? zS?})VzLl}$Y-q5u6HhFL2>St(~F+Ff!bdb6|8UyK|srP)~WN@XY;EGBf zq!Y>WSnY1Jd-@4-N)N~N--#vr|7+c0|NpH!U+b}~9IXF|6|ypaWtdpt9RHUqRE$4g z{4S*=RO;)b=W*E)B62iKf+0*C10f<~e$Z><_pETGOJ;O89h&K`f0(l?C*0l<|!b%7AGA@~oh%#%M%4bICZRnz|shbs4I!cE9v0J zU|?%JVWR}8L(G$Gz))v1!X4$tFd@(&!|ZPdOK@=;+8ck|!(8#gfuO;`IrMh*fvUOU z;BCVQgT0`XvyKyJ%%JW-rR3tHGL>%%Dqqp@8rBeo85jr%2;`!;0uj`3=lP_>2v5Y- zlfJMB;G&*=+1*uspx`0AXH!PG`Fy^qtYEi8HevpT-o$1&zO2n8_`jtP7<%DhgK|K1 z?7LMZk(us%Nj`n=KR^Qgz5-0C5ScgL_01#wP?X`#9u!H*gf?i1<6t2kP`kiy2u$K$kBK5gh`D+6 zIL&{G*ip`YE~o#}6q3-<(b3ZZ^K}Pf(w8)?(LbJeEd@}Q|G5`0$W{=bcJvnOUjV2@2O9l0_^Mwj3~sUbl@RUqaomEJGF7X z>E#e8cT;SD1WNxVNB<{!SwLVONRZ(APUW#af#)X$$fv$N49MrWv2Sk;7Sz>e@E*qw z%T81?W9X-C=_k^27xSA&(kJ%FXB&weBWKg5&Bx})XCI=yWb^Yo`zszQj$9zXh+q-e&BOEgdyI(pDS31aMJfdq zF5u~23sj7}f8cX0I6f(l?qb2ON9m>s{*TI}psWQkfzq@-T6{t*B(WJ=e>6su(V8?A zOiZ^qD%|b6oPp2}jL_a45s)=EVG#Tv%J&8(cXOffv*ge_B6EU{X|wcNA4WorTm8dL zmOnj!*YBwO%Ob@n8B_*m)QX{o(s2ROGTRVr!A3!;+LQ34o*Q{V1iQty^gQ;95)2j778by+N<;;i;XV&PQ?^VBJFE1r=#=pdp;Y@k2ptqEqBtC5>&fE0znbP**stZlPjq3B_$t>?f@jEn zb1(lcD|*ebYe>N}5{+{`YMVAMuAJ&|bZ9wzS30grPgXqGH^R&HFF@CkIWe?D)m#t> zGP4uQ1;wHRMJm9-Gl$Xz8vhZkR4aEK5bTCp&Z2Xju61UMb##M-`SldA*T~zo&Yi`D zDIGoE-Hpw_gcQ00tKZ}q`7o<Qqfv-0iBRDq*?(Y>;`E$W(fao8F z!F`h8(SdpubU5RdM@I;j7XZKXnu5kd>VvOzL;3Ya9TTBbV6fxc57tvbU~{{LDn9e} zzPfiGq~M$&RcTNE^@5@IOT%8(GA_R9fmD@KqhsIJ*H1tP|m`*n84r@Gn$z*O+VpxV^zU9nrU#P*RrUt z7UzUXwv3IYT)`FUY}>rTy}I7~~5N)`$y6li8}-y$s|kG#_(a zMvlw)t$VDCAb~;v$c5}*?FEFI4oCVyTS0hiWKK?0P8A|P=%(UA01XxQR=AS85b2OF zUW`N+XOFhtredYD;7N#xdl?2-fPO(eOa$*@Oh=Z*O$6KaW zxJ4qG1}&O=>E6B>;N#DZ4XzyGW?iY~BSA0NiKVsCQE8Tog@QK3JF6LO3QU2DQ4SjY?H^7Flch(7hd1_jn=YJ4S|o$lPP0}?fLH|p_4klre#*8^i)e=gl7{*jd7}9jQl9-yaKa+_bF`$hN<$H~WbNO}9z#a!BNPnnV9c{*hPy znD9DJzF-}04xs#PG*YPA2z$Vgt|f0oF--a~Dn>0}6v;HePwd1{`Au9+zNNNtyDQBEFlA2AG#tgP`?S7o>jjv z=*RnwZNpb(t0jojN#j2jfUB~0e)g(V@Hjm3mscW9UXf)==e{QaMm5;lS)4D)4 z6)u0t+Y%jdQg!%bAa|n}vVD|K%q-1Dq~~%&5Qt7Y*cF7;M@Lj@Mmj^ygpE}x5OfMg zO_^@ZytA|TVz`lEDBRpU@k5T~UP}2<*AjP+avxdBGlwewkn3qxPCYQ8Qzk9nfj(3I zydZ!}1hIHv*}+7Y=QvW-^Kp*nY@hM7a!Ay{P<-<=kIMF#owQ_(?%8%I`#O!pd)=yd z12+{Pu-~%6_7~brk<}qFWh>dlbiq4DJy_s!&df|>JP+qT=@Z$LjP%9-rH|z>$b2>C zWs5rClTJNPgerEde{oxTB`*x7FOu+iWNJo((m3hKAiLP>ljh`>w@d4>bz(`QJa$X; z6ZQg3bG(??^-0cl$OezS3s8Yn*a)oyfGRP~{mtAwD|0Nl3vMUK#ZbT9fv;2PY{seS z+L-iS6)z@KmF$uMl9Rr1HkYg|^K+Dkj#C`6Gos#|SI5fCxR~r|$;4fKjnBP-vJa7i zOa;HK>zqI}Szi!FR8<=5vMq%KQ7|U~w@%Z`_V}6vr*+(Ue!1<0PG73e`FUy`Flzcu zp+d}g$^2C;C@rRmXk!0}D^o>cg6%emL?aJb6)pjCL#aFRWPGpwPv2`VF!Gg|fo*K?*NiOBd&`Cp2@+*23-ZlpgUsEYo8goayO6Ak z4{h}0L;VPgc1A~xgOv1VAHTg`kEm_+GpFb@4nyMioz?`yxlQo2Qv#6^qemUV=&2$7 zeF6}J8SOKfG4&zNi}~Kb8@lG^oVM!M6tRLtcT8?FNZ6Neh2jc~`##azz=W#C0jeCu z{`TRt8gb23+0gm|x6sa-slFXwTOZv2RoD;zR+doJ>8(c{OVt zB$F_mn-C_h{+n=K;|;t8)oqXs?pxYc6y0ChR|VtM^b?G3tA3ZJwyx?y2i_FQD)-);*0WrQuz7Ot=o(U@G#pI!LbO zdTFQ$#{g0azANE68udm8$X?#>TGecYq^majp*2XJ zp>933>qWhXSuS+<#9?r?yX3;HcjH9E>Mi1!$y&qz^jP@}|JD6jey*0(7`oH1#Z-x~ z0iva9S9EAJuZ6vU1J#;C47YV{5O021-9z3;Ov1xkX#%*}Yo*&RzjF=CwaIS@&N`L` zncXhau?Y1AS*DLB`=pi_3qL`UZ=09#e*V35W<|Pe&NQe(NdHdXL2`^i=zcyMV#-aL zNXQE{S+bnFJ!%ebB}k%tsA2wXo14P?4D{-L?yE4_Fqgv!;M>R*;re*(XEcAW!Y!@O z?IhHp#SX81;h+^lHwT*Yjoa`dM2^%C+>?aKU)dL~ShgPvES| z_-c3jYII63(7b}<&?aX|I51gDch_05GGfmq9e*>rELl@AsFX|#M^RQ?w|r;`#i;&- z2$UxvFc`r%Kh&qr*tFA=m29YOFXvOe=Ly5~VDD4-Q=s$OCc3U^2|gBI!HE>E(I^t? z3%Xhz*`@G)Td3JfYPFg|W(~M>G{&YfkB6cfFy=Y~B7;R6FviWJ?{s7a2M5gD7qbXgGLU#p==gPqa*SB_6o=R5)3CxlBp_B@t0iTxM1cGYL4_ zSg~5tvxF!fM{RC$M}(zMcYO1;@DM$jNE`V%)S)NNzeM-mi_qukO1|}m#if-Hv*8C} zRxghRn9n!Bcj~`JP1foM5nRz26O))t;)6Zw3mlqxafQLQUapPg&q zP44nv$X|KcG6P*wJ{XQapVXxG?KwRX*b!J`z>%s+Bdil)g@nm{?_svTYVLD#K6eXi zZ4w-KABhq@@>zIFfN}gwX+(ViM6^ro?we6+surSNlin&h75o0t-;d0Gd-L;ljz`a- ziC?+XLHxus-^M%1QKgyhJk(|bSB3B$<)|whBQlQf##?vLC>G8#R{qH@5X9}%c#^sz z0Y<+}RvQN}!L$&!I9lC%znS3oVNbdh5P**S`QfO%z7_?m-$C2;%&?(;>>gkfB>+bz z(4uV!wmHWM&fT)0rZfBu&a!noDbSv2AbLLqiNFGZXct`2biY8D>^D(nqkTC0wD2`& z^K}3XN@2`O;)c)A6I^(c$R-KrJ8n6z0y0D!A`2(q32mLKh+Ov8r%$szbzf=+{bpaU znUZ;K`zzvGB%rU-vIu|Xk(-;YZW8&Oz>S9NAnHr;_l58^Q9PFie99GMh@HCR=mEKP zG{|(WM#qN{O*P?#_0Qyn9j&yDjW&Cf^noU7?`cIQKQyXpe^*_7wsV!C%i3U?0J_`i zO*iVW|G4j1;2M(Bqf6uSVW*8bm^x7?csKunGPRtdObxc@Ef~QiZTj$i> zkI9JGS~~<+?d7+2e*I||9NC5c$=UiL)bG7tm`Ln0`}gpL7o_3cf1LhV55jw8yBbsg1?0gPw36u>`tLAm`Yi5ah zYok6hbXCXbov+MzBg&*b4ycP^ss`LiKP2Y9E zh(r&X4JKdm0S7VwseNigRt^G9tTL-N`Pl-25xOt7WViWhUhX=^?HfsL%V_uQ>f z(MpIXh1$=XoDY#?ezWFoGeHU(UEe7$T&l*C`fw~ED;>M2(y4~jpPD}+KQe>TX`yHJ z@rOiiOkMp%eJZw37jPDxoI!?baR@7M5vyM3UGL#7<5cfk95EbAIOcl7lf8nZWI3QO zCnS=;_N;)$kzbTn&=U0ApWrB4LzUONF8Ka%C@ntot%CS`nZqBSqLo**#6!46{^47K znByN@)j0j&i|SGCfa#} z2@czHpbILS+hf1EC)&A6aX6zm$KbN)T=u==OW6cyL_4XmbrAZ(N1TaOpxm&FZAy6y zNsme8!bi^eX-;o)JW&>#f;o%!BoRjQuuB`XM^|%3i4gC~r|7;-pBYVq?69}!XzI0Q zY%k{@44YH_RKTf~Y5%3^9ItPrL%a>y_>Aj&`%%?>Mvw%x_l%RbVHT=R%$=M3V!n6z z!cq$CfOP!IX>1%9KG!mx`Zkf!hf3+Wk>E7WGkwO72J;3b3f3IJ>dDuP_*KmqdoKMz ziBtePEh+?0$?p!eleQ}Gbz2=V@fgQ1W*ZD6p9G?sABf#ab)GqS=RzXi?C#5Q#2-#X zZ+SU#SWOgd>75%K)|hA%%u6|tD!qvpT)S<6gIYqeZcUkEYueDXK3X4clDSVOmxqs$ zdtkoy>Ppm9>3OB)rP}tOF)6gTg}DR2%yl2}S>G&3Ffz(J_*EJ2@XzpjRrwwCTptLU zqM%=*E8shQVEO2+xh#U;mP)rk%tqO5g#7a@56#imFZYz zt*7u;Qb$4aUA-!^eJk>fC3x>i4KC>KZs`mz8*HqKbZb_xnHtH*zlaGN))X2p_6%V{ zuS{KL-N^bBSF=m4tx?5X2DS4ErMAw-Yx=+MO9Jgx@69ejxmzAIfd_g0b{I8~6Fy;! z*fiGKA7hrP_OS2mFy!zG0X8vX(vlwj%??ekVl z#&?P4kB)-BrUL5a$aQH{&i`sr=k?gEQvjekp&nm`mr%66ZrEYO2IUbf&FChz==zjT zUF|$h?QVfg3r;%B2a6AItfHkE6R=(Ro2;awK_!-PK^$iSoB&xT9RZ(}f`%Cs<*9lr z*>?zc%G5zOFvRegx|H@ngp?O2XB6%2CA%ZcT~x5p!;Bt%X&=X=GBYc4fg&DBe&88H zT^JzH!K6-Q#1lS4IGOC4BBn4f+fh{e9ouVy`nO?vdU|chB5VuF@~aT%!fb z_ucZpBAYu*pfvDw+T8XZ{6Qa+r=>=}4V>X3zwYsAlG=6vL#luqv0y+)rAa#Oq{RlR z4&Nwcfycvb0VvrK)J)sAQRPj3v2hpG+(Vs2hz}*i^^PfUCcYN_bdjn1ZwqOWfzL8ll0(0~szRcmM*rO39Py zBoV3vQZcFM1gEOVJ$)^z(tMD}A zKIKGKdLqCc+~`0b4*5)sA^wk-t-GGHPHe%;PLP29uUiD4D81Mz87_oH_a|{kC%ui( zcG_8a8ENIk(S6e1AybvtXTY06>Eln=!jcE{{^ z1~PDSNjyqRMp*tDisowjM;-ltp*$@LtJ=>72@@CHbP^j&SEL_279DAyTPo+6;EjtfOhK^r3UI1heIpPjRvXKmbHLm(AsWq5s(a zlm0WdG5sGABRlJVEOc^ke{FRBw}_F8iHYm~;DBylBc0lF3}CZmcZ4w;;ZDbL`K~c0 zFrZ*0u;flLdIcIZUx=Jkl`;kdM1Hta4CQP-HsoG3;gsvg?Rwi{2c0FwrO!cXD!*su z$_N~ES!b+o9RC_pIZ|*AgcwASF$gV>1Quy8$nW3G!oPnjfgvFo!ob0Oe52Z8f@~ur z0qj!7KMjhT1N^Aj3gN_ZLV4_PwsN2`h)JPPVq;Ka6Hu|BLg3(KKfgfIF%VV1OcYPw zDB>*=d?*PtyW(zCfeRE#Dh!^f&1euC6l5VWEv>lECSIWt%rhiV(BB{g#G|lhVUsXm zBA^m>C=d}h&l)fnukzFwA`()=V`H)?z)=`RU>on~?G<=CF*TJh2@b5wBg87WPa?uJ zWUK#Y0;Nuf75zIL17KooesK?1ae`;F{K@gZa;8Pqz zB-XB8a2g%P5A1w8a8nx^Y(5bIM93)!I1%+p4@~s;vBl z11EiD36!F^GQoIX2#5fGPr(8_d)_|uxP^W_Aa#vaKMKL5b`#qW{*qe|#Ag$`LOy_z z0PPPdpdjxT2l>Sbvixn2{Ep5Ks6hsMTYdT_v4pY}>`MlMbi~pPiUQ5_63~qddj|oo zctN-Y()DTm^cW^22Js6SGzY}xmn2NYR@RXj&e_!x-a6nK!r85i^IZ_t_o`|M$Sj|M zs|)VS7WkY7nlza}G{bEM%pZkR9mcWBD!3elKuzr2Yv4elIxAOe* z3<*93wAqz}?%1e%@MnN9ER+^1YOhO1e1Fwow}A6|66%;a{nBT6&S!R8MHqx~WJwX9 zbtW^$-`k(HIl%~f{+;46X67Fpelx6hm+clzC~F@})uCasAiftDLPTIrRWo$}UxXn{RSX4oLDgCM@(YZ+S_hT;RDB0>(7lK4xU3$H($&r*9JID&rDMoK`Y4?;6@5U z0>J~nM(7=zJ(r{X(j<;??i-lh2JZA3`Ceuf6Wqr8Z@Wog#`Na#P1qAqKT zc!lY(wfZ3(j{<;V^o#tRzMnXGBo@9wZI5wy2QNrvy+$7i%eg=FpjI!6`@(9Bx|{We z>(-?k;ila&0jnni#02*$p6aRypbQf|`MfQnj$0uYx#A~|hv<=QDzN+_^|lJN9!WHK zIHuL9)wa4_NbWtA-#Z{XCh(=peu{`-&j7_NN?2_Pcn0SE6TKnX&3=nx0YmFIslhdc zBS-89DpGGP4xaSuu37A3PvboU1CQL^9k>RPkXrl;Xlke!P6?gJKOKYPUXP3890)nc zn7I-Mrc_5~(N>PabjY}ps|jTpbmg(`I^<8VZ_S+M)nF;-J#TVG@(39|q#2q#k3(i$ z_*b9WPyl9YS%-RbKn|*nMY4f^aAm9R-GbRn5BbYk3sThS_#t76rl;&-lM~6kgc1Hq zt~!1&hI2l!+gwhLs&vZ6U99?fm^_O1qG-||6R@(j@XiJT$qyaWNtwh@b{jS{t?Sb> zm)sEp=a_`CJhGJZcpk7G3vKsc`$HAIC-i{eC%}8z82^`jU`ik^?WR;Z+oGXxTep!9 zwgooc?~i-S@=FyjyActM%v3}TMM_xg!MAvYZ%88>QSjhyz4q>!#gb1+PV`9g z%>keV<<^ zZu8hvPiGU$HVV)h{|X-i28m3Up)p(n@L1lhev40s6+&EdBn}9anxT&gWV^gd!)JOv zLI)SdUy6|?9o9ZB2B322e{+6BP2RT|Ed_je^L1FaXALaXc!bkueU` zO{mu=R+ly)d=O7W3k42(`bRnZN-HZ{519O9Pk-7u3r=N#kN=&db)s~wXJXk)elS8| zdh(BzI{XE(K`onuyD%qyn9k&0r>$?NbOxkTin?Yrh&{X6tTXK!W5mqdZ#cryLnfKD zyt=v}Wgkb%~!DwO9BJtSVJ|C7vMNptZHHi1h)aqJ?H3^(96yP@7 z5VX&JsmkWA3#C^4r|HMD%L)dGjl!dfDsJ9`?WWonHnk$I-n8LX7V;Hq)BXS-pt-3f zEnbAFJ@8mqPyg4xuVXdy53MN7y}P~!I8amn}rVzayF7f$C<%<+9U!fU;f@B`Dl?D_es6j<=XaPEu24l zinL|gqDy?g)n+tJ(XQvdyTJrpS%?B9^4D6r@~1FAulA?CvQ1|(03uKDw0P;zs9x#! zs9qU3|3{USe5w()$hG!P7?xjh0c_$mikv^!4ut5x|8vXJ8_oF+CUj}2h>!cPbO`;c z4M;=J{cP+XK#ni?BcS+7vNq>ZHf+~0_0Ou&iSzJ_M8Pqz_96wCVOP_Sz3i3s zVhExhY{U}K68*gy5B))UEWtQhx7r9XWOpjs;gpNo4J8XiFM!xbeR9NZw=d}Kw7*wa zDZS_2Rq1-4X0ndYGKdN6UC&1%$9bdF-j#ySS^8p_w(`fOGpB<0F`bSMSn=v3VnT96 zp#WC~vDl|e|L%a_q0Kp@qVH8_`hT^JZFmH35S;qU)-#^9jHc99>ShLrr~irF>0yY5 zj?M@JJjj{G8vY#pkcmzGymQ=Qb>X-q}nd~hRDgd z)T%_TA4+*GXGNR!X@dCZQFc7P?GPbhPNB*oHs;q8G3z?QKjorup&T#~UG}!27}$c8 zozfQGNL9gMkTt1cmeXmz=ql27sFVU&)}MSo==21@@;5aC7amaLnD3$^eCqM(?yJPq zcf=RE^mEe8m9!MBy;uGGT^6JGnkSq3nUEeNqK+__f=(rGIod%2#?ZnD!g!h6bq+|) zQyB?EuB3JnDTS7I20b1`mxEGGe4sd0?^0-mS})c@ANV&CPEPMHY2%u@>>rpX!{9H> z*_?s%&$t?qL-m^;CF2-|V=i;xKu&w{yZPp76=y`AY7$t`Mowlu#l1jyvo4tF&iYtP z)VU*3##eJ0*|m~mWsWEB%4O0Pz5j3sw{xowz2sTdRcbyj6;W+rgVQaL0?TV7pAjS= ztDeZ&Zk?#^NOKSr{wxeeH>UqU8fxgKG!)pJsE+2N4;(6b{aKbUR`=PjJoM;nL=e8? z4Qtz%(teJAt0eTu;%3`y)(q!Eo;Y2$Z@krv6Fj_)S(8Hyi~5Fve(#m|>089DMe~88Cey)pCbqz{DgnNXG`JgS*1{)!WIok5`qVuDO<*hVJ5PYyzc? z-}yVf9{E(ubR7N|zI8zHuR!l5k3O7%!bapp!;cp2VT@7_jdMdO7BHoXNo^$$t+u;y z$4y<^Ssw^WSTcI@tZs)Gr2Pt$Wp*H$`+P0o(sn9tn?P^Y#GxBMD(@s#{s4lKckG7w zS*Zgns{ar-O-07#tYl_q9f@P)I18B=;7Qdq1tD(nLn|eiq&4v z(@r&YvV8`tK5T%Qa6pd4V(xPBJ^ zK3PTiwr^ulH{E60I&lAX?`hXbT9=P3o3abO$f@iGoAQK@DkJ>H{${)XmO&>rFro$} zLSCm(6cYD1SN4t71ZM;cvMF$078eIfD>x8-R_PBnoi%fczg2|ZFH$OxRtB{9Z0xOj zh02gTTV%3r#4z@Tvg01kMrdGF2Hnqqq6|t^TX%H4kV;`0Ie!7}Uom>dK1`+-9SCiw zz~gPJuC**JgNt7N$Ao=t*~f~tN}EgprmH&7+KB}6AE}>7oAi;Jmi>{xqv(I& zzf#`FZ2CQr`Rp@)Qsr&%g~m5LtVS@d!OPOeV{Li}eEgW-(DcNWbesh+kGv~;eBy^t z)a&_aabh-kM4m_*S`tit*QwYTZ&j4NWM8Jzto-U4h{$-Q?x*<`_>4nk_fHOm?`V+l#?pc z>b-eLD!CMZlM>dZtNIU^q0?MziVmH%ruM*w#H=8*v{#y~kJ`(bX(2|mVxfITf$3-ZnuUZ0}~dA z@X!qMVrwY6YKOWuV>x_42oDZgiOZS(QwfC%BGx_MJzQpi_6Rw)Q4x#oic_xSe)@B3 zbz5___U39yVXpuH!d<`jSxo6!;cuN(>Bi>dMf31R58eaDUhETVa7Dq2w`x<6AOmCX zRd)RZnP(rSUG&n7(Re;ZLvgdmu#6PcBe|9arcvQ0D6hZrs-oM%)l(^HnS?TeoHvii z%gu<~;#N|%J{}NZ+Y_buh+Al&8x?qkF)F5e?B)+ivvPqemqv{mE^_ zBl&w(PYI!4)a1Lme3pDI{{UA|Pfr>8m2XY3fMXf8hWfzA{@0%z{2~OY6%SSB@RZNl z!K1d4T9FHggH3EK>T&KYHAvj}v(;0%!`=6sYB&}ruGg)?JFxyj)>a&=C|MMl{dH4Y zu9%9iEAhC}F?JXIft@G)idwrdrn%Y27>c*D!J*}tll7XQu;s4yvvXuFLhD{79^Sig zNs9~>)eG|+9V_FPG#unM+(kVrUkE?AXp&1nc^*7adAG{DhV>ULv}Ss!O1^7EAT#&h zTQ1w5N1?*)g>cMp=pQbmG?8UhM0c+ZZb1*<{%J;-&ct4!xBt>$d{6lha()<2&;zv( zJY~(Cktylw&tZ7v$#3gY;6^*NdZ5=AwUpQ_`3SWMFothD$Ub*bje*FEV}f58UgsfLZU_S{CTm>)bPYQOX*H_6hZj@c=9D+ zcoIrAuG{Uk)UG?D6|>tOBR*w{vM?t zd77a(z<~9Cq5E44=UzS-qy!?|YeIg{u$USO+`p7f8@1Tqrep;!jqD)W8u+gTI4Rx; zI4q#HTlTonYGx={h43nNAjn)aJS$cfhHvcDm+fk+QysFpgGc=9N#V_TexXT^qsE{) zNDcl|Ri3ol(XxBZWwK&|OxRfAu|fndVSc=xNgxWXQADe7g4s&=rxQy?-87yFwH!4G z*zE7&+t!|DNkKp_H2jucj+49!D%g7lmD$6|_2gq?%Z2b{NJnl=%r%W9UuXN!m?e)sTo)Z7G?Uuq$^0Hhb zpTWlB)}(*1!$#^dyD7|Kv5zj9<~y)90-?8M_D+19Ni7-XiWE7PV<0A99j$qb4SL)`68T{Fcv;u)Y z7H&?I-*TL$vPs3Y6RGI^>DG@okT>o*uB8+eyKLN{58pP%Ax(o}=omq#0;;0Z4X|=V z34H$?g3z;}ew?TU}XYX4BZ@tBL+P{HlTE?yic5@I9P!ykZ6 z6kxVpNG1y4&fKyrwH>8)%2PH)vyb?3Cn4lbKAB5fnIxV?cSpV-pgZoow4x$?TOz$k zcvQK&W&CeQ=J{TWXrQ%G06Q$7?2MOu%$uJ;LCr|vQu=Woj1_E%^! zZ^?uFXG?x7Sh~wyMx8*(-H8&W_Jj5i#(v6S4OvIs%jS-PQKB^h+TEyfKhWuVO^Y73 z5bV*dXIR6@X!#IpwYj%)vh529d`NZQM7&Sj?8bnAn$v>kxQc({x!=mx2}*5x2VX^J zk8DaAamiS$DK`u|M{2#QYSOdSShfk@AnL-AzufJkToq?_NnX;7I+&N3;UE9}Sy-ew zoD-jqTU#$4L2HwK-47d?0@UW(V%BPZyX2l_Rx858!0N)?cAQy5VUJI8l|rVrgo=sO zZMWn>6&2@DTdUvaO_s!Xe5y-i^WuI^dI}}30=nZYlz9hfkXbi&kkt665Oj2AgDjp+ zM|Gow)}Tk!ao!R)$UdlsExw45nSiy|6RkbV(^%G~;Ky_s7;PeHAY$f^Ve<`RBrh&( z3V&<7kU#rPOj23PftO;XlXs7->#jRLiWUR{cGNwY<{H6Mv|xQ`tz$dPC)A$m1BZhmoli^0g8%0sksQ*p3YjVN_NMi^#StUq+9&KC{n7d1@RZi=C zcQNC|+txeD6`d~+$y-J|@VXVDKgX>%Wx_Ld`q(FcR=Faa(jW=^{W&mumgc~rH6wxS zZ)&k+bPeC>TE{*dCn>3O=a$e=K~Xd%VEa!TcYY=de;!Bpa*z8l6BOnXfKfJk);d-`7z(u3tH@9(v);X_@{<#%8s2v@+rr>W0P8^(elN^|H>Nz2GZ7!s z-h&p)E!-@sj&;FJY3P7iXcHh%XdNm$^jx8YvEX)rDp1$7)BDaiJ|3Y=er7XvF0~=u zkUe3=)#mo)oUI~9`Zlkl9xaVNs?_{~65k>MSRsnRaU8*|#~kKA%TAIDI|Hgb7f)3s zr?SjNQx<&8Sc8^BhwaYe^FN2Tjbl)4rBhfhJTzHD-@U)qqupKMvPirtM}!`r$JW~| z!5KD>g)AE0l?0yr-;lwM_muw9A#$ZJ4>{OxhQ&ON!?*F(n(GM ztlYfbkks22bbpF@5#?c&+;rSI_s493~r!>n4)Zx6~P$G%VrVE9{x{mT-9k zsxr6)x9k#3>$0M~ndl9x1C&}8iwhe{w)qa_rGNa9)mj*^=9$?6j!cqW>^(mk=cYNZrf-8ps&^I2FK2!EO&KGRc4jyO67C&rhd_ zX6BEYpuWOt{=H?zgGW5@Xd>Rf_-6Gyg6?%F?xK=zL_^ORN3RSWNKxYF%11q5YAJ!= ze_1EO5VKtLI4GGk2m$9Tpgr)XAZipXbu%3;?gXkQn0vmV^7^E(H?AI|)W&-a*njP0 z(rW%)m%N7^b{9_(@f!FEoXQLp>#Jr_89g)% zw)mC>hJz1=38(6js!&|K-b|oxrNw9rN+a|9<)@vqgcUT{O;15VD^eVmqfZGon~hbS zIQh2RibXgD`Wr%jBvdLd1&{q5K&y1NuZDXknII%zfbpi2Y*O$YAreY#hfO!A-18Gz z&%5ocL#@rbP8U$zbFB30fFB*X38*o;a)#SAQkH!e@B)8yN;K)z`b@96P(%OG)Mgb* z6|T*PIwKjbd!&?&z0A75ttIB2h`i*>+CHlLtvcu40J+tm+A?83#^ZVd2)5B{O&o_Q z4A8%g8|3mj)-`cVnvI$m*eBI#*l^$a?nj}&Y>r*9+c}+9fg{kBhQt(YXy5NrIytX$ znA+K@-hOKWkq1g2gIG>xc-T3wSHeX}>$5bP=}Tj~@*2@?2xdaeEGQe@0`>Q7SfTNG z(udem0ET%z3g>l8Q;2*C;P=x0VT-Fb@6wlN&Lzdsv_?>k$=@ z#x!V}$RdMYQTr!GW@DW6x2rzPyU6mSw%x|y8#$~%{i%w?R-J~s@}90qaW#93=CSm1 zPN;(wR_3PQYm1?d(~B|`WfBkvm8js^%VUL_eJliDaNS(sl9lNPXdlI9)GSicB{%=o z&YwYh7+f4g$HUGiCi+S31-XH@;dnwN&2j-c%d)ci)#i=qH$=YtSLjx?vC&%*f7)L) z&+O$D=Xw+x``+Ap#B5_7S!DyRe?kKzEnh zNx{vr>$7D@Ab<}JG!W9kpFv2z?DWNMrfIGj=8Y#CnV(t?x-MxDnZjRKl zUi_*wZch$3P)%tBTKE^+W*$Bk`>RjBw{?)Y=9Z-ra(~esV;<@I7*L}a%XA5p+ zn~|1mdsj<{{*O!7VfX%R;u#hy@x6X+tSZ&YN1j3fwoi8eP`(Ss>-^!&THEe0YwTX8 z`FK5nRYf|Mh$505%iWe3Cz#H`8|m+9b6)J-3|VWRis$%J;3y&>o zpXJBzLD3ITAR~z;4?(vk$3$E(edQK%jQ|mMwOih}C`&0jznl zq~^kUo&8SchUVvdWyqA`A+801`=yS8+Igr#Vfi=-)9k`p=KwKKL6Gh%kN<7Tm*am6^EtTxBg|*! z;NoEWpERGDllyDt*Kd*vsBdv}BHw8Ij<3C5L)RD?^)){fgt_W6bh6yIUSnOCC+~U| z)p>Wh_Ikm8*a37YuqdIW(K7S zLz->FvABR$v#_w%ktr&M@PJ0@mY<#XN9g*tgD_yr`sS95NghiAP^_%TV30y+X3$PA zFn>XR@PXb4VH>h5Koi6J{(B-49obk3>giv8CPS#NtF8r~^-2i&$Lq%P^QUI(n{Gg) z-}a>pP$rH8$}(8U@o+K8p$=lm%j%1e$44gAv+>?%4w>E91fBx&JyQ4p#M99iPZ2)5 zlD0AzE=E;JRYSP|`2D7-xv6{kN&Xp1lt3 z1MlJM|4;JGHY>WnYyW1)qSxY|%ntnz;1T2(XftR=dc{ZMJF-;*(eT$m>UrM$+Q`O3 z78HnuEH*Z@9wnu#tE&XOhAFnh*GPf{^t9m9Jbgtv=*5FPz~LM1N<|Fwgv?y&VnXE9 zstNYl(7h=NI{Y&g>^$8M2q!=L#H@eMzR5f4ySxE>y-~JrT;-;_W*jzq} z)a9k6k$zcP86Sexvo^B6OF1#S*gHevyzjocflU;DK%&5)I6FJMtcregiOPQ#O#q_U zHJ{6=gu|=A((=2Y!uay!!pbRNe|x#g(a_}B=-^`iu@olc+ky%6gxztw$y!(YIz+`- zPW+vuvUHI6k%W&I%Ka7DLgqb;*KWi1$^r5Uumyd2~JIW}xHHT2)=Kc8$D zi6_~tlm%!7h6nk~AD_vU)@Nty=k1@iT`h?jsn7br!GsP$%KUjbzOLV_!Dr(8w#XAv z7UVQ!Hv$L`m@i>r(hp$uJuj)tCaLQJ8PBVO;EVv|V361}yDE|UY8SC*b!8b5#?IaW z^2Ouxvb#$ghF%ARl};rYIR`+1?-eYQT}@pDcl+4?5W3mS`HTa(7YvZOWiBvza3NOk z#hnK5{iJ&~_C-0{skcU8-e@AJO^F+k40E%QGzG=YDy zQY+Xy*&2iXBWC3+VdVidQ?ha~wfu+0f4QYyj6b9=Y-a%iew@iaF7?0D1p1Ke$JJx? z_vQjHuyAtyN9;q9rZ#p!XJ-H>&p#pH2Mhm!_k;Sse`o|H)e01mD$z5sK3CxpL; z$;}L4Qu^!q$6{e-0Wbmo$7K01?f;j_0bp|eKPJaV(8baT_^_Ze{5A3Cwm*9rj^;ph5o-%P5*Vh{3GWN*8ki7JKF#t&;w|Su(oV($`@jt))H3k zCtf&P0ZqZf_`3>AKuab8YAs{73m-=;Z=Vz>e^?aQ7LZ9N2N6Jh;#8EU ztLG_(b^86&btTEZ-%li{X+*jj%;WgR?qk=H3 ze+d~FhrS*(9lEpvHLcTL?{95am19JUkvlr<2w80W#kE2?D(CpcCK-ffy3sj>nBdL@ zQC1+EZ?i^nt2Ks@Ok>^^#Hz{7l@z`3gZwAyKv33=;n!j zWgrWmUJ0lhO{4BndRbJ+3I5Y4DbZF=Y>ejo6R+XdU=0lrYg8?HCl80J+~Dtf2?ca zy@2+!ye$UzKWk`C^An0$^$1`h*eK&i7SuALLnqRY8-qZlluMqC<3EH)UfG>E3ClR| zr|%YT8o^bh^W$Fj?&N_NdtIX}W%(mt1~pE!a2#=MpNs0MwG`e$OKfuF-AG`0!JB3e zl-Rz;yO#t6YG4T#>D-win~93-e{?>wpgYG!<&|mV3<#q}V?s3-J8fvGk5z)UB9gKM z%4gU2js;HmibKQCwk2NKM~ZgurqL_L7Uc=Fzn1IQcid_QAycXt@vt(&@m36q?25!6 z@Xm|~=FLY|I8%smJxym^CN7n`{h(F^+oJ>9+8FoESm4fuEa#u)ja^pvf2_BG^$bAh zfV%*`%3x1X8ff%0+%Q?ViCHN5TO7kLVKvZC34dy>qGdQhk09c5c!5;~C-_!E=cVJJ zzCxqNf1vzLczBIdCzDoEC@f^}1_F7Yv;oF0Qm2&)j{q&tVL|*cO09(ee*HGt0b;X# zYKW&v>RMmh^b*cD(QN=|e~zQHVvCwtXj}5_t_6wsyQ7bwny9Ygme))^p8;FR>RcoV z)uPsXqiQs^k7)&IK^!Z@+|9;FOaa1;4;smdc|CfQ+-nK9vPxxaigi!ov=^PF@otSm ze0;rth7h@VPe(7ve+q5ZXin`rZ3@=N zn%#jZi6VD1ju<~MQrFr8oYSW%&1_`i`E(I5n0eByA&SO;I8=Tnjp3CxYoco)p;`%v zaM@?A-WE)l>SKrr#;@dkuHwBos=pEI?iuAvZJk9dVzAPK>`zL^{eO^Dq@^nsnwvy) zuGK>vY}4e9xzQ_de`wz09zseiMJH937*H!oF;UiU*gDh~(=F4(1B{7kBEfz?P03mWhwoj|TYMwbtbAj(; zN>ItcUS_8}==|epnhZpi-ci;luMsvNz^@+gCagU>o*2G}NQGZ{Ky|+qqxiK83^$XA zQuj+QCPapCf8@bSY;|M3DFxlHt8PJBGO%XI#4)mB6!m~WJ(CJem=&kd-RnYT?vyb~ z=xQge0Xn~7B8oiu)TEU_({2)5f$4gJ+PZQbHSy*EWW-&rNcfszR5dvP*I^sf^4MCJ zGVhGv3^WyB;Y(OXzOlAsQYEBGhg5o#=;U7>T4E)uf0R^&r?;3u8yv1J*fgLmYh^`- z@2iH`s4pq}BwCAZvv05z+eZ;L+mNwT^hJhD;l;kXf0%>S=GRtW${*M3OqE3{xm8eOXvHh_vG;`y4r@w?(j+PUJrBI8Yj;eD zyF;+}(My!6)8$>p=ZWbG15cv++eyF<4QsL}G^HK64DI|^uFT)2ZC<~G_!iyav=LXA z;b5@QnJ_jpk8lrP^WWacWSxa1(^xhk%ZC$se;d}>$i75|%9)5=)3SZ1ZBHFK0$VI& z@%Wa?UFeZk;g;>P+gOmkmE4H&)bYm&yUJm8ZI(i;So}T$<&2#tBUl|{vfY#WX7_Wg zyk(!z@H813<{JOS5b2D@S;-BCH@9)TVo&tBZR7kghUXM7#COOc^}2uumJTBKGvEO(y_ zJk$!9BvSB{uf-`Ja1n7D(Kod!7;8=Oq$+vL{9e>Qp&E6J1oNpjicGY^u4bU0lyivH%*)FfCji}HC+cC1NA@i8WV3}u_g)ou zerg(510(zvKodvb<0wqabpr_ay`3)YT<2PQldUo+Hah@FbJ=S;8JP+&ai~9o7 zrGT9sNe`0p1P-hTMCwP>PH8?6e{W?fefyp@IT-p>(@o5s!;kv2pyEt>J87Yv!Z|Ps zvR&DI1q4Wj&XPi`Jn#$lRC4N;Fb zBaAnNI}2c_I{DI%IKogKJ0E>+mAj;=xaLDTEuVL>x=adc0kx}nE_m=xe>^wF1xKnK z(%^RJ_9_2^>nEoB1sM5d%UP@`$0_jmSX&s-PiCnQf+xRzBk-CRpsrDe{QSqf|^##eo`WYHf6h_z&}6g=_ikhv(s@)dCNq==*$#jl&2vc zByFCz8b(m&ecs;bt8s@>43u?WXmQ50l(N-9TJGckiYddX*dKqHe^TKHDoSH@ZIS&F zpyk2IV_~{kHamAp(VsARW+U3-pfUxufU&~cg4;3@QLxgGUqF!mNHr~`~z{L7@KJPCX1YQBxy~L({5Y6E6 zBF@1GK5o)-v+o?p1Q%7R1)nn1{vZ;|5zIlrlJtnW^Y}$-1{aNo!rFzFuy&tKm2+^& z`HNKJcn(;=x+;XKQkr}|@2|hQnI7OyA#|cB9I}8ILdfzye`b9h?TQx)zU@H`?=9GB zJP>LyT`SYVHMUSLE(2Gqk50!u-pf-xy-X0^wi$Z+tqluj;dJ|*pu;Ue3K`N*(3^EM z`dwig=Xbyktr`h(8V>}u(YUsskru=PkgC&%ON&}JQs^;L&tK3J&cPZlH-S0?>)S%M zmpMTFE2_*8f0+{FX*@tyo{K)eRa{?r?<^LMUQ@gbftg3?A~puL+M$FlT6D`1j>@CM zk7_|);2T3bZzNtthnyPk;S&3iE;UJ@Kt`Mm`DAjT-^v@;$}BUb5{NogjEVQ6yKXz5 zXNl)ZLSJcUZpU#16mb1>c9m@&3r6%Udal8owpqvFf4fS%2T48^O2&QnlIbl^S#0!1 zDR1VCs3l|e4!a(PK-+aePLi;bj_4{u-1OUf90T}|qh zIz{`B2<)wXx+LBFnlk9_JmU4yd0ZT~73#po)eB`FaDJWQ4)>b^Z_F45|Gc>>)VmS1 zb1G{4e@imCYL#p}3L8ph9LE@ZWIZdy1p2Uw7*Bptqq39iz{e=ljp;F7w*ud4ryK}@ zild9x9*WWTK76{uLifw-(i&ZZR|e4GLY$FHPr{~^NXP$~0rLs!(8(OeM zd9mnSJ<}X)qP&KPBEp;;*RjWSVdUofQ&2TXY}cn7|Frru9_m)^4UHWgu!!O#{Wt|@A&Nv)A~G3FD;w%_c9e$^q#Ro) zW#@5G6K52(*XzDpkcFF~GRe2FX_>Jj-q|#EXHucP_e=OqCyReF0);E@RGQ6+LJUdL zjwC-}REBdd&ju;vkYq5H9$Hhg9h7*De}i%A`z~qeM4&^+81tDhn;bIKbNaP4UMrlU z0F0+Z!<^%qH8$&DPng-ytxsUVO+C;~zqIxdLrtuxUTroiXW@W}-5#`J|4RZ<9t7Fi zFC)@Zt}-l9HHQ&erVSaE`qCDtQ1V)_rABQlekS9LXnth`&a+xL-iPU0skWG7f3kiZ zMUHHK303V(T%SF=b~mk)oE<-g)stbfULe0O4_ek@X*)#1)rW}U2@-m|ac0;#L5!0z z$4=82HjhPjQ)A!_P?@LJWSoJ&&i)x&S1e{h8%iiE+19$iryiW^qDDSXSEz`ePdp-$ z?=?lFW~a42(b;;fA*Ko?+yCa+e_$jQkABg65_OpsYhH5gx375;$9@Dch_N&WCWzK_nhle}GP8t0Cp5ldO2c+Snhgs3|GiAr$ zjmqh^P%PEZvHD!LCHJ7O%h|JsTcwVUe5ZZY9m))HaF_iPG*TDP1!3Cof6F@$=IV#6 z!D1>VXeFMXKx7Z|=MaFIYZR`VMmgo6Q+0T0>>}R8d3nIA3n(5AN)!mrfzA{to%$W>F zfB6C2rsnjag%;5v7&AGde;tnb#@0V?f}uUsloE!>uW{eE3`P@NksY40D8<9{AT<_7 zbh9_9JPHuME$n`(o(M7zJsZTNOseFmy1p7zWf?$bK!xK!t%pF4H2CaZO_#|*B|H{D zsqRojf<7v+Le<>U3;)KqA}BkMe%~e6?}qB>y!__=P|4`@6jpP1e^pvQ(L=dklXs)i zKBm;J!`p?nX!8AafPd+SEXv`(kTHMsymL!|z` z#EDco7OPZ+M%u^fe?@C0FdJXMIz!)q981$2FH-q)U^`VCvGi3;^j<-Ts|vTt8cj)@ zXu3{yGq$y5WjrTL--j>FDdg}`)=7!GVmO6S^w$6)#;wzYq5xrZD0%3UOTj#b?k?IZ zxyeHh0yELrL!R#`A!I_Upw%qDNUW0gmrhMpdx9(_-{Kyi?$219uAD_Y7M+)z zqizuS`R0}QO{GWdGN`1P!-psCatnJjq8O^Qt*Jvv_C#o+Mbku~tWNDSBVwiaLf}v1 z5G99i^b$-;968iU%{hUbnVstXHP>wsf|@bK`pM1{m#=bKG*m~ofy&2#AN*w!L(5uV z&}&?K>NGure*z^e^+jkkZ@-ict2ommoFZHtOapg8m5LYa`kX{IZ*@0vrbUP015B@* zcogvlFJ%7J{V>|iPqeF;;%3}$bB$~-5lpAp(+1;8Z$yQLw%HE4cx6^zN=V6q4opEv z)5d`<7`yZH7##LY;u|&X8Zc-lUE#^*X4=!pL`*YZe;|y~)Y~xTpIVm~U(2A&6pO#@ zm&*b=;iOR_EvF#d=y&N`soGjD3G7uO`;G`@3uZKb8tnZ^nxsjOUm}wlFP0-EQx#xO zk|IkmQW%(GyC8^xa zo~<<>F7)|%SE8;B8~G%q5Z9cIex#*FVKLmh6BV&)6dZvmS$Mw#A6SpP)5^BN6Igu_ zL7~_3T7l@IAB@yC}Ccm(*VyYFaR7Y|e9L;Q_>6pf?i27>rB7c)-wuu3i}#~P;{`7?9#I!P zf49nIQRRaHa*qeRsFP5Ksu^Ttt_OopC<&p|PBY0XCQBFROoIXV&qs&xP_oUPq$Qt2 zA8hT1HT6#&>|M}IX#C*)o*cUrUhu@M7c+=Gr$vH?f@sJ;Xs**4=eME{ctG*+BA$ne`Z?~s# z95RP&H>sM2X)8F@^?}%$DjY%V0hCS0A=2X55d1%<%ca+W-w<`mUec-eI}BYkt?-sQ z>MVD5G_v*+tVSWnF*t|-?9z1uB(SnGE~I*iJupmnGWdQho=ni3A?fw0;fK(df58_D zJ@(C`eGSNXv#*TSa;k{uw_Z=_Rux1&;SYw3f2OV5iai zy&!vL*^DrQMyC~kc8Fbon)@&+Z47@vdd{~s^h!=tHWhPMJUxWKWo#mSe?FUG3)T);7^a7+ zXo|C09ql$KmnP7Sr_i zjy3UtVVsBglQ-Ex-j^87#g%(hNE!(SCfiTuy8z_ZmleVEG@>6^AuA+stZ<9{rM`YS znsFgHXi$!6ayIQmeM$-ZM8cI_NvM)cN&AxfS!fRj6C)3BTy?|q`>aMhH?K|epF^g=x-F6`~OrsM{3+iGoi=TBNa`8R+tb3M_+6{V< zWxqy{-!V2KQU}n0*flnDp4)OZHKetrc#lg)6G_M}gSRvKk^sR%0j>hk z*Bb}*S#z$dT;3>+`En)77hkfg-9!>s(B|SE_xS5)0*^AvuyA} z?+v(GDaD!5jht4}iN5M~64I6o*(fR<%ClBSCRaUkRlZEae{!bF^as6u`F``A^)%A$ zj&wA#LQpEmca0jEbNQRIE+;f<0lk|7qRlt4ZwPR?$W5LB;nz(sxC`-<@e%!&^MnL1 zEMc1tMr6w3Q&g$%yxIQoa0vCEJ4rGEkZM=wzV>&HC6V)o)NBJOoVNG=%v)ZHgiH@J z0(hY+EXlhif9AQCD!@st&<(U~LramjU}27QJ9KU`$$V57NZfYoy$pdmbqQf}p{nzJ zX-FB7T}dbvv}XF-%O;E!1WlExi%}N!v>II^JbVk;&Wmpb7kUTDaMaMz+2Er+es;Nk zOt1%zOi9nU@=qW{+9gcIE4v~+KZ#Zvix`a> zR$&7>gg&JMRxRx%dgRuX5Oa<=z?<5zZ#Q~#%tffp4|8tgIL0I0-xif*7UjskI5Ev- zS6GEvf5zp=qOaeh#eG{Kh!JA7Zt8>%iO#MMO5zw5cFA!t{mM136h8_`012^Uh>(C- ztqI>ESgD<97QLVvZ7>i23#K(IV#FBV2)65dEPg!#LJh301bglnW4!IOhrxmGM^I12 zqq5VH2JW}Vt*+*(`=G6#302V$YH6X2kX^8Ze-+fd;xG%_b8 ziz^f4xMa*1Oq5${2UGB^vIb9-D*gMq$%*H6)j39tI(#%(wWBOnb~z_i)AxRBSaHK4 zIg&9njIjlLP0{kj*X^@Wu$R>9q*9k5f9iGMXryPK_!m&wS7l!_=rnnVvgI*DO^k*J zTLf-Oth8URPfjWUqip^K!JVQ)TfYY9HTDEOZfRu;VMjKpL!mI&YWqgZECcYCpab_e-gif(z~QcBXI~LXI!4rb%hRx47&n%B7fEla75+{ z+J3LCwQ5!ELM|7=t`->JD1rA$y2gG~F5g!kggsIp>tz-NyK47DPO2+|XT-Li867Hu zB<#WW$_>v}mK@=eqo!ely=H9qnxJDwCd!Kgg%h1$u@!`xF3?(;A2$Kde+6%NAmyYK ze5C0OAeh^3YCpk3C?Wtq4<$}iM9X+{N zJQ2b3ke1K!?kFxo_Dhm$(BET!{aOQPSgt*j7*@Pb!EcYX3hkE}sY{uPMLb&a2J3#y zU#!v3Dq=6@I4_I%f2?>m5cxg=L1i9T>kHY44s;|&!NC=Bj zhyuf=u5Ec^SU%23=j&`+cS9lEwm_!`sOfqFC&^4Vf8M53FROzjJW&7M_T@2+V3JF6 z)t96yE}CGq;d>et0Q)7-?HN7-Iw~IdG)%6EgI~H>@>7%xe*jyA&hhF=yf4Q!X^RsV zJ&ZQLWpEUI(`jXEL0%ui94Z!dUn7V^%(Ki`kBNg<4fWhOA97G3N?@~kCvM7)It#ZH z+O`zS0omXVFkU7WN_OyUtU{-(YQ3BrhFk>GDY19~E?7jsioTJfY2)>?T2VJGD?6vz zI-m$m7b`{+fANy4e?nYgpBjIoJw*KGmDP*IlJ$f|dLRs;S+fMtyU7m_5L|?XKb>x_ z`eb4rDf67)o4(*XdS1J-WM(1aM$`)CW}9a4R>+n{lC(CpIf@m4x3Pz{`xC`Dy=Ayj zTY=93N<5=7m5zNZ09I>R*@#t(>+#R}%#uBhR<|7}f5d>ybFqmb2KSGx8l+`Mu6IwP zP;L;+wG2*ZK(k4vP;bX0JJ|d|sV`=pF?2 zz+UKtyiH2*7saH)F?~Oi_(}p9@;GgC%J(k)s`af8rNRs z4$h5df3vz+!JkUQq;)FB=!A}zz4++DVH^7K(XM29mm;7y!2s(iId|l3-zBd=aCOAm zf)9t9bMRl!tCUV#@=p?NQ>6Z`i~TZFmeUOgOMxrxMH z=%9P~!nu2{n5BD(XLloC9stYh-D&6CH#dOnF!B-NPO z_2oJOS*?_G;l7PAU}z)=FjJ!+;>$L(jB&KeaF6}qR|ysC*o@Cte58ML$QmMhB*!r7 zf3!Q1k?n+yNLO1KHO5mSe~b2m1B88YTx&53r@pH){b{Nb-^CmDrdTe0pkbUBkgb{# znJJaOXe>wL|1`{vrdPC%8X5Kr?+p8<-}X<<<`)FknclQI!|eD;S!0>wyEwk*qSM-Y zjJ$&SdL1<30K``M^L(G%az66u%M6TBe^nZ*9enNV3LSFk|8rFz-v`0IjDurlk{V-ck>@aq=aclI;* zPW+1$ijCiII_a{#{6`sOsuCc_LzucflFEi8boe5ckU6f+x)AqI=@VF7!IILDVWw}% zLmrSDS%DCN7kuiFZYaY9I+E3Uf8BY<(>1inv0rbDRYeMu<#!Vk$Z~w%=Xu)UpEV&x zu!Oux3!yGc_je=G<`nYdC*=^N2Hupw994m2-$6g3>9$we7;vH$Sxly`r(e(ymZlu#hrjs9yf?$Rrz}mf)vPL8;P-r(>4Ye}{QfyF#8L zrtfL4uYe(@nqL>6&^d1b{mkuLqxoV&7BR!-@HSU_BN%i90R~8)KjX2dh4^Qpx|*YyWmFC2kA~C1AK(e{%20@x?WTqcEvE zeqQ8ZK#Nn*p-u(H6vQleygSi+Et2=G zH7_?1-cdhG;@~z8lQdT+lVG!=g)&{MGRo_T@y3)apw)eAf#-k9Bl}HiS~|z9YeIgi zFK#DCTisV*f8|wU!MZ+tbo3NC?-`j3>4jMw^^jGTM@AG#F0#83cY3d z(P@-VFH#4cGE&g|BH!1QqcxV8QiX}#%TH~L&?*naQ>R@!C9m5xJ5X46I*lj)aJ! ztZ^giWC}=S)AentF{Bo?QV%t`r7%6Kl$=810p`j>9pNbV@nd ze-0Ifs%xwxM5Wdv21hL+>@cxBkpUyan`dG%m=Uj$q(xqHe~>Yz)z{v=Bl!o2J*BH_ zOJ7MxpHzMKPNkj)-!A-@sPVw9H;t;ytrRw45pb!hejhT*a)fMkLpF-vRL)0wj}7l8 z%@OgPaCSlO=ezp9ilPPlAN8)xCx?_8qKWEn3sw0AS zaUlXb%OaU-xNKKe;y#K<6K`)E_n)!AmIPR!8+5Fra-;*MwG#Fw&$U*PfQviHQ9O;;w7&T9$ya{Ck>490=0}*Wz=sGJe=K!D!dPeWwksV#VD$%Y2u>pkj2ysiBW1mlQuf7O zA7KNwcc`DjB+xAv$?jS`#cL^(&Ir)Yjv*X>g9!-KeDV)P{fW}Mk;@P`Ymy4DK!n;K zhcnYdsWDspC@v`8np0|EW~dVr@=Sp3b*99W3oUOsk+5xQKPB0Ocw1c^e|DjJ9;7E2 zifDHL-7OH|G{844R-`p_cYy`bOUN2L!7CEZu8qmK$a{CLB&3nlq&sH)2%Yw%V5!N@ znY`X@j?cmnNkSc&r#eiV->AxmkKmbq7*RGVoe_yW-XI9p^;vO^Id#R#!N|W<7|3UP zk;BDD*1hCPJhyvs^VPEwe>*PwCkbrx8T4}|^z`dd#9KA?%pU?8yX*P6-FRraxEz|M zm!oLT?6nfhz9qaFo$6+SU}QGek`Vly-|XBanAoC3CYdG@>$2Da#^G5~_l@!}_1IGb z97I}O%KL`f+eVkFjC{`UCina?7-sdfCsw5f%Wv40Z71JZ?${PSe{uU6VRRAaD-!RL z`In14*niTLLS?ge7D`* zkr~=+Z4&LFVs+@K20w!VSAU{}SG)wLX8{w~PFf+cww9RsOR2Fxl^7SY=-qz%xdD{! zz!lN8KSAjH{G$z>e+WvpGsSjuMaJ0i47Zv95-9!Ntdy}DS%n9V zVqy7j`VpSH`@){bxXTvuoz0&+(hlJC$efYDw%|KQU)AZze=NL(q68Is8T97V$Ca8F z`&3_4gSEDZ{&a;LnXiearbL2N9n23p8kq^oTT@KzrL{2vA{$8{cL7c(e%FAw2mpTMS9V}0_-M+QkQR5-<3o?v- zcS9pimk-P6e@9#}?)UQqQM}(%i1s&Ts*sJAh7{oDM zU#QZ_WaaW^vxyg+^YX3YZVr-rfxR#IwVRBxj56y(UV|ra!3xED*Km0E>^x{|&rPIy z__Yr+0)r5DQD$(MK3r%&gflLG9xZ47EY6+N*hl}~e{8hrpl+OMHMQ)ON&|5eX_ljM zsXnu(yXi(o98ko5gFtgU?sb$tdkCjr1mc9*P#v@Dq|D_jL+SoajqI8goxuJHCw^9S z^bGYv^}U^lgjHoIhDTW;^G=aG2nMI6QOL^Y}%Z_V~44dn?IInl1PPTlWIc#^E zS$O?(e<*lelV-@P#f^AnV1`J4q}Pxj!o7vuLg~;a`pZx$#-d?;_XNs8+1{`l3-zJLrhB1%GSmN8jRvC<%V1eF9oFRm!r(!a<6sEaQIQ4Rk<4 z#CQ;KrE-%PrX+WU*B}ixH$(Iyw^XY>lk9F?-n^kn0@=re_?SH)U(1LC6DzIpb z`G3WZew=yzC9{UK=2#=Zi{>f4i_Yozvl3DH+9;f3idL02n)e}8XR`f^oXr%dr7bBj ze@y|tUsxbZnKU2I0i8vUN4c;U(f2%C?)$+enW=5?Bhe)FhI(-Zja>Tw>l^)B@gwN^ z&q9WyIZn(5_Ty@&h1#^o&vZeT?o+gZb*@subSEj2y5dbJl)&IdvtWZG0NNmX`$3GIUIT1Gp9wb`E*Z${qhi*d%OIv@Q$1V1frN$boi>8 zGSnk>Jm>e&!x-?>+bgDU?I9?7_VuZ9o<$Z!ea#mlVEkv~g9(J)q;LF!Ztug+e`Su% zd^TMvP`W5-aG`2tv@BA%J&49vnU0~*-HZ9*tsm5%zDsy2=Q*({)9hsACmJawdzJgL zOw|zf?Z8Zb3#d5EZV;ydxR@^dWP`OxsL5O7-R(w{@7>;7XeZr`@R6|a91DgcuU{iY zgLDNq{he4U>}&F#zi)&+1aetHe~fK=%&P6023Tq{pqW7?sy-t{_qi*2PqNFa$EV4! zZo;*-vy;Uey~~;59JOEz>il^KomD>aMz>w6bL|pNJgT8*;hcVHEx)8Ue2;UG>tk5U zAGN#USBNp8|wscS=Dv>#p@Ad%UdC!0k7gKl)gyP?L%{Gxw(9bYv)r z7|HcCk0^O^Cfo6f{CdcQvWm*64jh=uTD&OIVr#oRaD?ZPG1(CABFrdZR<|hBPXmma zgHY1fr?mztjwu`Mwwscne?J4GQfp}_1g?a}{UQ=O?Uv~iuEO4NBA{EO~Ee+5k3(TK}So~*vV z;lIV)jT#ahFmf-)Qd5kUt0b2Ch>Bah4A+5d=;A-$^{?V}c(!R{4NWOuI+Myj@77>x zAinEGdSSSW;X^v%40b-HEQ`64fNXDaf=X&bje%-gG+$2|-aHF7cJ~l^;VqmbR|yaL z`iPdeFJJO&HN6&c06Y&*kDRpz%mOpmM5Vm79^=!@h=kEv=n7S37OHf76J_SL+Qn0JQcSPoC02 z7+G>PdnXe5}}VB{-201?lz@g^T0ftIRxcPL0ft*gew z!rW37Ql9Nlbj8~(g|fLI>hM6E`NoFCI{T?IgyyiUpZ%NvUfH{Nn(iU@^C~`BmUJ8U zUfoD@9|;-|e}0zU{(>5$0s>D#OJoc?=~!x!mOUG5A8E;3KAOYAu#4SLUr@!;Y+OQI z6@NSv>_eUJzlyQwtnz`p?a%ov^aRbeA9#K?DQF;nf;bxROOs;zF!0YSF_q?u+CV|^QHJJ!(C9%Gy%?g5>Oh#{@UhYjo zk>nL8U?oQr=%eX5-1(@MUCL@K6x?GU2NOcVzrYMnYeAdcw<9xf$+qYqvDG7}a&{A` z5aNX8$Qc9gwC>GIaBZx(MUw7UQrSbRKZ^W0B?$o$d^7O^Ft|p2 zeTXzI)Ukt+qR3=fO3ObwYToKkYEUN{9~%Acz>J8JXuK7y!l3z?(nKJl^VAYFf4&jH z&Oh)A!7f?H&wh%*EQuz@ zRB=xQDlhqwNmz1OEdu0Fh&g4=0AvEvDn}3A+eR%+Ha7ClH_Nf&LF4m7!MNXilG)stg8+P!WKrtFMSRu4#`pO}%4yIzh;c39#= zwHB_#SfrM!V^K225ey1_e~(pSS>*Bs zz*!2x2$~0#`NTFJ27pb@rB?J@ZB4_%_Yf3yKG;mvCHg%`V86->wdx}ukt%uBnTN7* zK+A|&V{(sGtd`i5@s^>L(8+N~Py~6O;ib7#sFHdGjZ+GsQhc#>7I(OX&|ZJYX(D?c zTT5GOkuxbDv!aI}etjpEe_S2;^<5!lZN@%E9w0ZoOtfh$mAY|Z15x$LQJqi+Vx7yb zd2d%1k0uDD5XurPWf#lhV_)A%c5wZkeogGjs}U&4H|AJFj?Y~SQ7;ZGW;=55N(f=a z1kf^@T;pibYd56{DCE{}R`E<0*w3Dmmc?Wc6QKsG)6IISWByrqf9JOCX^`HLse5wy z$=`TG19BD|k;*{KSnf>jD_h9hUQR7N)jJnFNbIFWkJF7KwpLmJ#~)v7vw5~~8viz) z@;-~sH1brui6|a6kj^wDNHhoW(`s_xFS34%zLuJO;vtJWFo^Pv7DziXzFX%1Ek5K| zAZAZpK*Jt$d}6u>f0~A~)>k5vPwW`_vQ6BZTcuBgodhwXFE&3wc}nzJt$;EO*tU8w?gT)KaoCNU@b^2iwr~~i6)1tel4&--a zgjc@sXL6IEJ+CgTQGCV=sR|P9^5EwRz0VMwU9~2Y8AT20e|X>OI@QY%yu`JZFYngH z&e9WPDl1uThxMb41~D^Q|1ie*34ab>jAZ}#oSbGS6X`;iN}Yh3@_3lJxi~XQeC#wA#Jwze7m%9pttFNBFu4;>s;aq z+J6h0aVqdHs&NF035-Lbs+GBIvGd($doy7j2pW)Ze-MjIHvt4CwivQ&jS)03FT|^;9Y4xrX5XjA{~ZJK&E6hU+((n5?UnPV z<%OL=e)))f^Tao44g?+((|1YLx7 zFAlj=`z75(3M(tWJTuLqkx^0>Ix=9QI;R}me^aK>m@+>-&kxmt5=~klqk-5U?ao)J zxTwN`I@g>`UoY7Fs{d}^=0q$q1lIMyMJVz-Zrbfi8wqm*?Bc9~*x-+#7aRl|rCl>^ zA&u$pPbjx-?+Yii#0)q$SEdhsH`y;UZLF`AFM*)}vw{9Uya~bc@g11MUUF$V;x)~y ze;Y2yPa$T~>R0z5h?U3b=fk(c(!uZuTzYm=6wnhsJ9#9qE3eXL|Bko~5HmURI}j|x zk~E3M+4`&k4>FFrsXI!==>HM++|=YZ3Pr{(gMh_Fa>AGjWhPy$RTd*+1A?;4fQu`B zaVe=T#epoF^O8BCufBZ=!Qz*e-EpdF?_$|&G4 z`c+r$LY2;R9l*%TgwytmfC~Bt*;!MHe+CsX^D$A`{w;DkywS;2B?z5&U_-t95MrLI zPX6vU6e=_JwV7L0Sd2e-5a+lln= z)qo|1c_YqZ8|8}$ZID!yI_7M?f0t9Wr-4S(ggublH=|*wR#?7;KGW{*?~grC9W>|l ziU@K|HV@zCrYg3dRmN@W+|*IwL&wN2^~IfssA}fy3u1?UVq_WKS^fDd_8BS@dE2S| z3h^fKy!BVq8J%j$^-+%qC4RdxVFL{@?Yx%mo%T_8zNHS6mFZwB-99`!f2DI>4akkjkwa{N!I@t_XG(0bKlm? zy7Pm#395WitO7eVOvbj7iD_~2g%epTC>YjC#hgE4K|+DNwLGM1fnn7)!q5R4DY3nM z#3NU%wM;%}r9af6LdzT)f5rNw@=3g?|50)(tU6Fi`R>(6FpRw)JzSm|N8%WxH;nSiL_*Q?n_8TJI~e`v7~j=Njy!|z60 z+MHWwY;pai;+^!zl%)EBD-*3UvWvzk0g!fjYV^eBdq8_3R3fJI3Dul1lO<-Viof;5 z!)%wrFe%bmoXrOOFm7TMQn=^_x3+7;o`6iQ{R_}v{jLp zBaxDt9Yy?U7d=rzf0+7wi7i%Y$cEX%(SMvH#*Kd@rrjP@=cNlQ!x*=52m^o(NkLwrQSod|FNp%Q066^6Hc}%X= z7>Ej+)dAv@7Oij#G(*+zJtv|bXfsF!ONXY7)i4VH)>Zq(w^T6*Lyc4SuoSdSLRElT z2|s9wvj7_(fDz?H;Of5I=v&yHzE|qf#jrqeMsguagD&LWy#Hx!xn3O{69pGeeee%V zykOk;p08fT+LhMEXlv9x6ljstiYjoC0#oW-OPt8}`Z{PczF(}~vs6Ty(jDUQA<5^# zD7FZU*CG=`kIJ3S!b#8^IHe(sHy8PB`Sn(_+LS&52?IC3& zvA)um?8Ts0)Qyg3@U5)R&_StT^oNBildy8;2p&plM88@Hk^Lv=kTOyxIy&;)tx4c7 zUm}TJ!WUw*jy6}aU6v}`F57|}dbSd{0Ou6{>P_ALM8h5iX$O z%{@ggmodRi^`^HSixQidA!Es!GH#m?PJ6v`5wEN$KnzwkvCL*LkwojO1ItVs(54SG zlMgcl$MLd~RA=rS<+Cx{N)Zwg--5B?9$Q$_iP68=Lx5_aS>TDfs>UOqMGB)%)pWWy zqXd@+(C5|dmHH;iw&4EZs-Cov4^kxJ8cuN~-qXig`5Nn*mNF(#zho2GNx09_KN#_} zp=7@9m1bVpV`v9x=^}Rd5lfAWp{N1mTl3X_+;cO~btDb2MS{q6%Tk-|Umch_W>%aF zo&AkvWwLL`rF2x`j-4~2RLy3-c>Ttnpb|v3_g^yf2pNSCH#B0__qp*^ydhUjQr;n; zqB0EeW*&u}I3|o;ryyUSt%D2Bd1%qBpH!6otn6l35U0}BGwg1VPrwisG%`?3L-yMr zkHOC(U~%^oscn<#^LePjF})jaX$y97zX0A<_gc%zj?I}%3F6Wup5A{pfKZM3P%Iw^ zp-r$MnyFDm@&pa=_NfCcIsLIweR1jDnP%A%A6)EbQ#7Q3_QyQ`^_8i?AHyOAWjW*8 zLjp;JROBU(9C(PFt(1Z)RqNkUN!J}tB9ay1)e zdx!F)$RK*8c5(d&qYd|eg5a>RvBNUS{!hORD={lOE6@La zu@NV{@xel}u`#p!x7$VuhCA^MclsB*;y$@&PJS?U12##bO>7g2MWxXp-kk}iDThXW zfUtACgS8rpv}i;krZk20FLdG6gv3e>-iFKgZO=)vbWjS-= z9{RT|lmu4LcUfZZ1BxCax#7F2+CVUt?;ZPV1cWkYJAXtc)l6a`x9V-^8T5#2SEpWAlrz4@*)nc`zuQxmwHc3 zDgwd+1_CPz4r-PO?vK_t3mOW4%O5Lg#1`}^N{Et=@(~312F->=!0lxNT$o2e~NdP!S@B22tqNht>~$WW7~*9zNDO($T6i* zeSUs%ZDMJE;*B2_yes5?HIU+`h-=mMV}X7dP|cB~>!TP<7Wq{IV2}P0&}ZM`Nfq5b>e~myk z+8Y3Q)H?!ky|IwEU>@I~63CoD{aZ8befx}i57i9yA&xbsD=^7PtRAj~DByFC+KE5n z;|EOY0#h1lRSX2S4}#brdy!)ytlTHbZDO_nj@PMu6GxM7TRQ?xy>?4-A6bWg*MOu~ zAD1G@lu8AujxdvlPq=TW#k@;CqI#(vD8~Rv4E()2R&u&N{q`>hGoHa7EvibNs*`(( zW^k-cGd;y0*Zs^RptmAiH;eCeSqPeE&i)~udL~}AEUR7($7d9$u>;9-KLQiYH|ro^ zAVowX6V2~+?jk$HFx4jTaK|s$SIGFz1S!gP1!ao_J;H}vRJz(q$-tb8X_4S1p;v(z z6Zq7kdo^6@)we}(gmi(VC0I79zac}Hq7uCyt4-C#oH+qCD)&O>JKgEFp|F>acB5%3 z+=+bMb}9E1R2)=F?rgI5B7ZSIOv6-T0^SlBIlJDgnhU37^k{n~hnUiqo!)aZ{~@AL zR*b{icXHBoQ{}s2-4M81@^#D(XH|hwWl=EIxdT`*GeezO7zy`Rp&$Nfq`87S`tI+S_#iA zepQ0^6iTz*mfZOR+8#5;m7IspNFj#@8{NldK7Q1Y1Hvg(LqLTh%Ic(Jh&=%Nyzl?W zvYS+3vM6n)Bok7{7DQw#tt%ml%o#cS7#)(eeK){bUoLPIf!q8REJkglpKceKdb5)4 zzpd7C`YF2)=coe4c6DiqVBOCug_f{ikZ|*mu;dMHRX9pztq_Ch{7|+*I}C0f zB_O8t`E0Z9A{wuLFY&(D`8g%b`>QdxA(_c-QAMxubgQ_LTPtoS#S}0Kdf0mCoi~cB;YxKKEfVu3bxP)3z?K06v z-w|Z4Q1iWC=Z@OXxPbVx-N)@`jVOqlUPng0__K8fR*qzyibWlPPQzQLJkrz7{OJ$u ztM#=!f}o@j83h)H3Nj$ZmZ3}a@9=$zY#<*2p+w2PHp z=t7|8=;za7e*B))$pfal0jA2C7F^a+6!_9ylWVb$og_S?}mG$5(5AML(czQ7%?EIvTQZ={>`S7y|&Py374 z?k-i@AS~a$%eL8$|_gB_xRi0RrV*HPNbmxOjg}wv2$t9Z0Q4;Ile=Y)om`6 zkM1zigxVXb9s@j4IVQJ#dK{hg-9P(Z?;Ag8QX5j1s+6T-$ZTVgPBNAfYSUbX_Y}25 z3>u3^FYCLjzs=d=+-&RtINexO-nLm2?-0pMq$zfMClv>I-;+CaW1^y!G{D7gF7XvfXtOu{9$Xpu6Ug1^+ z;mdiMzGD%&F{bXz`~03(O9OrC+r*JSs(BAKCqoD$V_W6IQ z)e`iaA4n2==rKPpQsPTw$g&G_Z^7j#Hi%09{V?x6j+3%RMC7F5TdwzY;2b?j$ToKg z&z6vm2LeO&f|TSt%fHbpZ*=E3YS17J#d0(9D`9C%^K6S z=|EsgXb;JlhHQP~3U$mJW`C2xGc@Ck*%G8`G6OE;0}HOsNC(A{a%ixI*2%PmCEaDz z?e3zc*OB-ecr&qnqSgFBupLoLI&FP1b7WvDNcq`bU0=j7tlYd8_Ldw>czzZt`Es3j zH{{M(ABL0GpfNaB4+~AiX&RShFJIjr?$?!ky~iP{OVG<1qjDv1qfC;MV^Pb+VdTXG zwFuzdPL`qn9zqO?=jGOyv~;f0E-0@~OMPzcqu>^_vQu73NLL#_fvh;*X_4L#^|*Rw zC(u6&mtnFJ`Y5U^6n{(D-K&Z>YZV~oq&*=edCGz- zqXC9J zC}Stn(_$n~E>|>@F}HV}_vj%uD;Yg_b@`SvZV_jg-rj8Ksn#RC6a8`;QE9VWI|~F9 z5tt|PGmFWJW*i#r;879usHY9urdmdnv{Nph({N$fIpJ)wEP9budcE9PzOLSuelzO` z?5BSK&%|G4{di*C{df>_WX1cZ?xc7PuSk)wd1dP&-+z^TxR7%p;>w}mvRrv09OXUQ z*eLmBY45H}!%s$?Rc1mA7oWhMa`Xg3Qck5G;#%VAi!ej;+J ze^4qoci?$tIA{#~#4nGGT7OWW(U=xl4o&e@u(j!_blTS>2x!H;KRo7F_wZlb)>}Nl zp)zEz+AX_}lZ2K`d3p1`kkJ3;cBM ze7KN^sLkBi7^i@mQ)r68*U6TmAwfFVuOjA`)*?s&$=KC;ws=OCTj2HD>KI1rW2w5$ zC{{sz_nPHh&BO*xx@*0PS{9UQ=tL>P5D0f`l{0 z=}oIqCjWA~F*w6T!7b*uB+2PbE6dXqKQcUYe!f26KM2+*sj~WIHUcXM-g*Q{YQl1z z<4{-BV|gh(Foe~OINvq>Vj3%F{akkWjAp-e^hUV!Ko=JFY7b?f&j+W4ElxVAx{q(t z)W*6YdDCHe2eyB{b2ug*$sB$0;HV0fveVwt4?ArieNMq=msJk$%|E7p;8f7Ba!R0y zuIbv8eBoh0IDGpzO>r1IIysma*!4aW?d)63&$S$$eHu_tk6lQ_S`o|MbVk^ap+LYqsFwqxFvI ziUu`u1{(dfvTrCiDH!43o6?|RBX|UhZ}4I6!hjzcd2rbuXjE|CKoC+;=J(XgWIj6*IyQ z1w|9)Z?`H{Do7)z7WH2l5WGWudW$}4n7+N>2+(LsbT1J{WCQZheGpZ4RPcyDrZBnv zhM@r2J{bPEv1TU5^qxMMI#e8ouh9~4H2 zKG(`ym{C#Ri9s-HfrUt08}T|5;?3Swu9@>3wlo-C7Y@CT zBkbs9Acmpn;(r@b*oK1@?Xd&$z6zkBp$+g?Y~>*iD@vFWCHn$6L>=CrB=2L9)rqs) z1BtFNUScHw4%+vC>a-d-3vxpTHQk?PZu>s4Zn;ZxCd39XiGlz z9X8LaF%r1I!L<7d*K5d~cGEfOs`vryNB$2aQgx;_Z6mfLN%xnFSd@Z(x%*x=n*eC0 z<*xiN=!r{88gAo~lz)4X4eAK=vGj)BGy#kfC@^nlFuJ2;=lL~Z@BQX1|2SS2it5~h zqaryGTg!p~y!3D7DsS^XT;i1}x0XoI@HtnkhkD#xAits+8*Jr--1D|vxDNq(l16WB zroovDZ>+H2RgNul9}odLZMq6fM~NaRDbZFTjg3xwvdlc~%ehHJ#yDJe`=3Se-Tl+a z8qDJf;9d_x26T3nXCidOpv&4Kd4AJf z&FLZDP|8~WN*SV+^EnCrCfE0h@GCo}m4wzH4)u-4qwg}AM{;r+6=8rpaa1{Pv7=4j z+)tgOHtWbGc01Md^y(jy_wy}f-k77_cM?+q^U*pe1sEhmUoV^DOd~^FBMT4tA^qvJ zUvHa4F!8MQh0$l6-9LZjAG5glSKF)F6W0m5q6KNv$;{_Y<@Y$adWMZxCa@oEt>Fy8 z&&FxBla*)+BCTe%-CF?q&o(Kx>OBfA15ThzS)|g5oeUM73OP>^bUUM*4fAzCOd$`{YCzoFT>96J8II|d*)fm3~NR7Y9ac%dV3u+Xf&HA(HQlcrKs z*re`e0ytDRdqQ0zR%y-LOrBY~EX{~I1W!fslFhS>A=8#KOH2WwXewwEll^Jlx?Ec7 z6oI7O+q{xKQ;gkbgJF^i27zD-De?T^1$-?o$1Zo37*4jw&&#aB%oWwt1uM;lxl4OIm`24u$*Nd4j{Ze@)J z)b+X1$iDeDiSD#XH``!6geo)QI}@dPvld-`Icw#si&%I}lp6eE9GIs-8Ca*AB@Oa~PUBkEiCf8y_vGuCBW;lE@MvJD@Q9vc#wQ@&#H-zw9o&0HQ9#M1h1JNk5reJ{ z-A3R{yI`fRJc-SWu!O(NHNH&Uv$S#%-^S@MvnpnQcT9<~1R=+9p%m9-D*6OCu@fW+ zQq!x(PCY2EnWsD*BLe&!72 z84%$-bkOKu=>8k+02--hfRMtfn}lMY7K<`_*;fNvv%jeP^o3@u{73>d8Jo}MqJZfa z6K#Xmx~I23wCj`&w@mAM8>F|>`a?@d(Gx=fa#s2P`mHs-YEGbvwM=-~kTidH>>ZIU zoEBDr_eC3R&M)Nrn}a2og!^gCBYwKG41l0)X|2XRhPTF&Ri$o1pz&|JSlgY_w$AWk zswkNq?E=+Z!#NTtS@BM%Hf%PIY`MEMy;pLr<2wcS`!-sqbFs+~Sn}Aw!s)7AxR3A-|D-v}A7#$s#6>9T zHa~{RqN7*U4yXug+|!Mi7BR4N|TK3j_O?W5t#r*Oa^Y&L|=1UOF;th6v5#XMBt;>q{GJ z%nnY#=t~UwlR8N{4k@+2RyA6d4Oah$Fsr07d>?FNfM3sD!GL|NWz(?Y=bj0L@HYrD z2&i~}{b>2Glvek;KSC~BV90P5BL?U*8A>#$&^P3W7KGt`emfu>#vqw_Fmv+hDFA7u zIibF<8Hs$p(Tu;y5+N)E{k|;ubitSJ{tw)cSuk?nKOpf#G;9V`zVA@%#1MTB@MFw* z*kJQ)oqzW5M`1x!7KhD)-C)IKYnKnD(4ithO;F)&Ie%!{46bp4^CC>@F(x7LNa>1b66aAtZhV8s4uaad zX3B*bQ6xu*^Nn5wmHHX$AWAh(SVI$w*hY^=^h(OHHh;A#B>k+_p4z2|g=8e)@ z8=#~-P_Hs{`slDe`7E54b{J1f&+Ky+qJ8S*seRJ1FiAN5?5V`Etq)jkVq3$r6rk=& zm#e*-FVooCEufgzc@#h;ocV0FwkXq5l(>CM(>dB(*TxJP#cI|QU=uPpnewa4mXq-3 zS+4fn)xJ8QXk(JSG6ATJ_cFd-dI!qQ=(0ARE?QT2-r_EFYqrCbsLswTFC%$8yrus< zA`QKW8Ya}k*~+g|t8eeO_u%3+*Z}%2e;viv6eE1Rr&WyU0nN8Hl^%>L4A*M=94w^6 zN}r|TPYL+n!3r%G^^4{Vc3G+0fA75)HrqSX;}merbv{J<_r4G}V@T z>FJv6wJbzCXS5^DTK4^A@sS~^qB-iZMK0Un>zHsc{9JC@PQ6s~X>~I;Kb4w^fyCC^ znL*5{m%PQqLJDKwWX-t&c-j!-`ctl-zi0zUWYiow_0WPaeLU02v@K4buEka+? z+AQ%_bRCRG59Gj95OYSGx>hpY$(M0g+uAN}0O^TOMVHq5H&eV1=XOY8!;n+bwA{+d zu4ft75l<=I>>T_1(HDF242G3vQRPI9=oPdvoolw2%2kW#J-=y%>$%wP|LPx{2M5z0 zC7A4tPNUl<4e7a$m3De(+WJ_oz2bXkzQL~=To`7tsMpAu-!90eTKk$9ZI-|tg$un) z0`9riPXj}LPA8E9Y4p76o$G8{jQ<*nENux-zv!He^L3r6l^3;N;gJnAY_>j(7_lKNCzQ0mO%}E~cA7hAI5D1)nFK~{6ltnN_76~VSg_7*$? z0eoL^dE(lt);P3StXxob$WU-OkjhE`1e1`EkQ~+*du3`9)cBvAJy%s}HaD-J;HzYx z3C*|e4Y1r2Aoy|E3^Mjagq6#&G6iLRc2BqqT$I8>fMwGAg0RJMAQKlCR#FsDL*^#` zQU;d`A%pI*60i|2Qu*o5#$Wu2cgv0Qku~#;$iI`M*R&yV1wdc z_)_M&a^+^g%v>^I2>d}j)(3ZR^7?}I#Rok^6mOQl60ipY|K3cwG*t|Mx}{|JeL)!? zf%vr4x-WM@D?#z`@}zV7o@atwX(SC&eEH3f_Klp>Y((d}a)4Mr+FHPJ{{E~e>~X#_ z*lLm&C)SeiMVpyCsnH(#?n?uV%ucP1d68(;350Z|@ld1_$ zK(O84Is93{_f?5@ynZ^tetuo4o4!BA zz1!tJZwp`d1Z{l@IeaA*d^Hbz^}M~;f*jMtVM* z;a-2&V-)8kwtD(XneWlG0{QY&MYpzjt>ML?DtJl`T}khm@0%ETMp)^Y2jcx1;+VdWv!eQX)U)+ zbl*wfh;BUcvdcJH|d`>@YvmrsWgUZEX9`#as`6bhwl*uo0uLkVx@^)>~&jkE% z8FbczyY-^$)e)r0!{avzo>uu0`H;|A!*JOXeXi?bY~dQxQCC&g9`9?`7N~2?F5rG# zk!Yjs)bT0%ItUQ`is2v?m^#{DHfZEYTXf|b?kPRS66i;fYp&xV&fK1Tj&Iw4F^t<@ z%k#(}Umo(Zl&A>#Q#vKYTO29W+EH{$goBHJ-0pj^N|HMs{-f|OTi=a5KdF?x1D8{4 zHJf{ox6@92z)!s2&GX4R=thxjHs*3l%oXZI4^n2Q1r@-I@y5G~io2&tL2T(|4Hk{1 zqZaw+VB6_mv#3M?Sta0$i8Qo*g*_g1MWSitvZEA=Dm6B)ORLa=(G;=RQeC6@_SE#0 z`ObEtR^(goG_%nD#)^?dH%zSqxje@6BDSX^wICdB$%QxwU$rM9iMv>UySzc;T=&Q4 z9@qOUwk=ThvmudaXV)=N)O+2Z?GhqMK~fsC#tU(Jj_Xv&s((m?W`+mbzHiy<_qK&N zdjTD1r2Fq+I6JAkoaK6V9NH43WO|g%ID5(;GI#1_9ad85%ZCT>6?R|{c5t9>kw!?d zfsR3Jw@xKFdK5z8pyTQv2)3y?3E2dO#*YyHCUSOV7NRTUcV`6FQ;fd^BTE4lQ@|KdJCA4FJz`A{)sL?`z#|p z2aN|z=Y_-;^rGbIvVAgU6I|?0YY_iNG-Y-rv11G$MHtd6rLZtBd|1>ZyMaHst)taW zjATJyp=X@9Etm%TuUM^fFt&1=d0sdAz~w!a6L=FW|4l>DYO)=o2s-C$RvaSNWhPe6 z@Nq*i_Z5o{l2ix)=POIO{*1?spW`GxaD*45h#Fc5*}6$F>b*P}rh9il2JsfYv( z=i%PGQnmwb8we}5B+4jWT*wI|z0DOkpPF+;KX|Q~cw?Go?rxau*1KADURTZ_i*9rUjqC4>YIqTXjrL*m7Foq)JH9x;UEN7CvVHL#AB??w}tvxvi_Ili2;|g%Ng*=U(tvL)sP4R8sDufU(0|xnU@NCs=zhStv?v2(;K8YM?twkvV zjEgA0loAa#xhh9C^$0TH_Sh(*b=U;fIN+UTEzV?gDrTsl`gU{TV3^1JcMP zuQ6afo8u^j9@zS^e+m+K|4LP+m9|i7*qL@Q#U<;8qJ1>xzlOLPFYCD(q;tR93( zPt~(o3o#|*#f9qP?Ft%xAiVJY9S8_Xkxl8pwnoMSEY*X1`^CXcxB4N5kwV2KogMjo z62iMD8Jh;M)@wa4%grJSjKbCTG0nWMBzAXNdSv(`2!i5x$L3DoX_zY5C0gfqbjxD@ z=wiZjYU_+gkq2ph$4Ub@*jV+vMN|Fu4U@j?-IuS+r~W+~`*T1zTXeR(M@l;XSIB3}BS}rS zUSxN_a;00fYp;iS!f1iAd`h);&-+k@^KSXenjs!Jpg(8Bzuk4x;H+!2FA?!bJQ|Vd zdXZ>}_plZalGg;t$EYi=A(ln;z}1bwwlD{!PSV2{c;WLk_sR!BD|?hlXfMIQF? zmT({2&u6%}QV;|;*W&#OJ}(i^8c&NLnv)Ti(# z3pU}_eOb@#3Z!fn^+`CRo@>k58F{gz%9r7gznbev%vFhvrsnwX+MKQ2fnjv*59!El zcPX>Z)zVgrB%pe>UBL-#oBAt$A^gkLDDA*I0eKD_dQx|i8{!kl5&lI^oeP6Zh0wYR zH&xii5h#!d*`OK;S$v`ac`l2F-WQF-01dY1hEV$_Mg@OTX9G%=lxqb=F|@(^TrsnE z)WUupfoAai>Ogax27#o+b#(ca1*zN?<&G73MlgPB)X zPzriNZ{thDqO+Xq5-U$X9Z?N;V$ff$;f!QbdYNm!LGzXgD>iS}i<@;B456nA)l4|f zNaVw*vmREhbL2>ZxEq6*YxVEiU51prt5EwsG#BF^#<)Zb9&yXXK=-^>5K8O*Bw<*}yXQB&ID zM5jHEt!*?VwP__7j+dXAad}t zh5SPzFIgTyZTC(=-A%o+4o&9lesAre*-rz<*c51>4Q_E$CZObkm<+XCU@QknYm>XwS@G!j%@b-Yc z@?PbU`iAj&Aw@EErJ~ouE|nix%qT(P-1%0?>Vvhf^)Rtd;}MFlW^PU$YO`YKF9`Mb zsXI%afu0pH5;1IrcC25+39DD z(*uYs?3c%nYrU*dgb+WIX+Ro8dbBi}9j$S_>ZM7}n96#fSf?|GuZu^ji3=O}W|YN& z3S(BAI`mSg@$)xk?ie7q2vrlYLL;$eCqglMfZrj43tk5<>&Ii#VtAyC?6#F z!vgUsplc*Op8j<_1Oy#0l7@)+Myf<-h>a%^x4pbrTEx}(M|;IQ=YL-yK4b40@6!5* z(&TIAP(_>iNXB13i^AO04EINzKmKNbl4qJrsyqAu^-!^1cE(1NliMLG9&oUKqyy7F z+hFK*Q+kQPnzs2(!oyHk#xnV8_y==Dg3}NR`3#15_07@d9WdO^+4@*PZ#Y&Y!dfo$ zKFmH^+y(CnxyVW6ID14NGYc%Nd!o**185&f{iloAmhC7rWE@8Je?tR33OGF4?Zkqz ziNJRPTg@KXQC3_}EdpoD|I$Gl&~Gk+X@=ywS+wQ<*;>ywlD(aI;!V=o$5T|HSJhyz z{+yHIvmvnL0+cu;V>rXqjQAOes>nl)P(e{>>1bx6t|ed}Yz*=ex>iyddOJpZiM208 zI!r^5lA{YO$_}#ky(_Skc*EbKVJ4l+(8SF)!byiUBD^ajfp@yVCX)zh~34j4xZcOdYf8?Y7CXiwPR0b02YTUZLX@w|DsBAoly&Q3;vGg zohe4sEpUsZ-Z%9b5_A$yTLqF4D(zuraOvgWAqq{g%4FzGV|8xR1P!c- zLO7`_NSio*=1fBsv*+5ux+S6Bq~+#r?PpcXV!vqXgp*{v-k$}v72X!Zql9sMwV2NQ`0PK}TV z$$+R0p1-PDLhCewWAB%7my#oB)S3uCocuwIG+3(U#!AFl814g!NERkLSk6h0ieqWx=yBgO6;IElKSgq(Lw5cr!&Nc ztfoW|6^<)A=f8t=cc{mL9nxqVZ@Q(U4J*!^RB=4@S}K0-mK+CaI?6i9%K?f`r!&qo z%j?fzsPgns%R#WKRVklQr}6B!nYFtT$9G5FOC5=n;uq4CWp)^PacMs+5g0*}cNgop z0L1eIDjM5Yso`narUtv`yrh6?pGy;r^R<%pbz2WOP_iNBpq6>S3rzuuPaKWy<)>X5 z$~%#}9Tr5td)0u}G4Hjjo(`Gez3<-jiP(_1z3YmVXR#-l;SBw?3-Vv38(i$2bD1lr zjoJmf4HW`Z?s)2`>r*=31+2P+n#rRBxe*$ znY*?W6q4D;f+XlMIGTh@cehe6N%?pA#;BCt`E@Jxaf?ciUB zx_W6K!zH}1m?8(nd9HbLgn05Nz# znE1I>00o>SD?KRHp*uz&X$E`oc_EL$;-PU;kLdwdzT;j?&=Hht<$W8|&Ev*r|(FozhxSGZ(8iYa4al2Hs z=AFgH0rXGw9>q~D;Bb5wFlULIQf;RCF^$+ty>~&`)!p&^;cr1|!fowQz=A0hS`Jq_ zES+X|G#`UpO-{s}%FmBJX?T0Z{ihAhkmXwOlQg4u?-GgHNVHD!!Dh22(ImPdVg7gT zVw-i9CpUwEAf^%iKH5rE0x=|?p`1AFA20TBr+;R*$=J5x%ide)0QPH2B&uUN^Hn(g z*mCXs2s)7;jG?#R>t%G{)EAot%{Lbn#B?V_=R<035HTuO{U+J#u5h!an z7)tNUxdjT2hCFZH382#PcqjV?#?6K<`{rXVO@=ua@)+iAx6g3VNci+$a?&wpk^n1M%ic(BRnEAr6isHv+%^=YlYhaunGCXx63C3A<3e zAcxC;p2A-I1lZ)^^AH!fU*onm4Dp9MmUHu!aZW3$@#Nw}QwYn@9N8~>a3J-22OTJ) zHg&5)8juEcw!Y!mvZ{z0N>CaSy3`e@{VY6{?oehw!2LjLpYS$SV=O_2SeWx0x~gZo z;5@=lYBEC`xJ2o6iKA&!cY8%^`xG)->%p(&@Nh*x0a(Lt>aROl54HlT70ZZTu~o?A zk1E8>!QMSm&Yf@xuf&CxO2)&gpjiZ)AWT41-}6HkSp@c_(i1ma!@Y zDFU1HrF5~Gm5Mo%ynU+%5$I9my^8wVr?u?t3vHVuij`_)`W60QMn{>QYC%f)L9i2( z-_w@N08S#`IGyQ2rVw;;%VUU>kpN26q66Yd=;tZ;H5dt=^Of^zkv*?b7`Ku6o8RV} z)L$e#9v9N5jOu2cqhzLM;5nE{B7F^5>}VzBfnzb~Lrdf&<>; z9VQGT(_%wSPRI+%H2Syri~HD<-%fZW8LVnKds{H^5q!@KA1XZY%Q$iYgRc+2qNI`} zQNQkt9?xrTen8&MNc^5QMD9R;sg0~I@P>Eo&3-a{uz2Pvq!fVAI8o`R7O)jle9v*SFs5nEuG{@R_-AvB;DSFX-AXv!kBv25W!I$LKN$*J)MlNjW%*gamv zj9^7tsAl=X15TTmYamT_+hbGC9v}IE3n&vCS4#v4Sw*#|>px%oEO?RNqKd!?=5rQ( z{}l|A7D2_YQx-Azp(I!wOT14-Q!!%$MWY`7uf?b@6|Y}Mk+5F0I%syd$qfz4{Ftzq z3;h?+%vo9gBlIDk^-HWy69)bn@Tv+P67zcVq#|!Z!M*)a=lz=QzoMdxxIm4f4WQ{Z zBPnZ<*AlHtjm>&CC#moiyT-5#P!Lw)My6B4T$4{^ zAR<&}hD%%w5p_}W=sP~QdV6tUN4Xn}<)1lIF+@4lMg#VSz#z$gmwQnyY5cS!VNxz17 z3mtY6acnc)k8WnU?IM|tr7s8|08AR0?P^8XVY83XK6H`C?=%C3vPX6n=f!04(-G{$;B5(?Kc14*jmLt`0NinrCY}7Mk`!^0J_!0E+_a z!b%CN19c)V31%U3<>OF8O8fUz5{}A%)ImC--gZz5_{U;JuVYCAt>>2AoY0#`C5YHc z8`BmRx$vz`o*0l1Y^?Ykq%M~wrMbb>2gO2lq)MbbZKRX7q-%M70QAYCBYXS=Ki-13 z)C3Pg)uaaxyc2ejvq+?gy^lxcZSuQkC&Hl~lUaS-w~dE5kjN;qn?<`D*$8G~=LeSC zGa>==%8@l3_7)CA8KIJf;;fX&CBiZ@*nfbua|6GiI@b+eX9cO7LEWGBq3MKo4Y-#a z2$#dNn13r3o;B150STH72%kjl@IQS&4fwnmdqh9WgN?4^G~)0eG9rKo+S42BKP>v-Oy8^iS&13h4GZqFl1SS{E6r4%J6R(V2iz&*WjESy3M1?Hrg zwAt=z-m}6QJAQGc+e2r!xB<&!e^Pn0^x`cep2t2n!iL=nfunCKX;(uUJ!eqrPKJZI z3Rbq|cbktQ5-T|S1&9q{IAAOt@m~Y7o;QEx(pAusG8X#xnxACAy2sa40G?xXtchRI z7swCXzQnaLPQ~pXxU5-%C{6T=Nr+_l`ny6ltsFSUlrE1S@jFtPjSQ06$C#{h=hYb& z>fBfIi+k#|z~73J?^bQFP*y1^+*NcD4og#5)~qP3C7J?XgH@wD)|Yx%#I3kUl~i)U z4<;Nt+UD+$XOO4;;2@NbuC9dXzd_>yZ8cC$5uh1n>;g5n<<|;je?3Ph%?+`_qKYoj z8BWsbI-`$%-K%>4c1{XiAni+J4Y~ZJ z65-!9V=4=-3?IEaR`$|OjlbVkTwpRAZ0D&{TKiZZW6PU5YGI9QO$n;?vrMV@H)WY8 zjhOw0qBj%tvmNb_ZNSQ>^JXb0o5Q8D;Jy)d8_+U&+p^-Y+#xdSdHEKV=>Y%i~y3A~7Kui;uGSb-4m}o%E{M8+C&LpuCGo;=o5CtT^p#WpJX=3SYLQ=O=}e@ISxkGH8JIw3z!({9FO7$-kh-oNDImAuOif68|Af20+OLPv3b)vINVl8KfqHlxwKL#d^HqT@4G zwq*g+n*O*3@w}8@%94~Tac zU0SxfoA#rr{4EV@*65DIa)jQ04O_{y3dOWm zQzwdlQdRxFom>+yBJM}jGna=+YM(*5!bQdcC9$V)NXhG9C zBEq#w{_VyBv9?1d^wrKS)0iWaR;2tedqP>YV?@O?jEAl|<}QUhKOU=}(x0#X z8Qz{dVT|p?jL4BAgc_sezXp}Nvy`3{=S#38-1aS0Z}hJX&Z!Hq^N*=+76 zyW0qnjV5yK?jc%Y9CjS1o9hjR*$_AP9N8P+HeE_o3j4}g5zSs^#o7QNq(}5>`!;cZ zea4lvC9?x*(w}s-PG!8;=5wK3~PiP$0tbOWjyU z<>pSgIDgB=De>h~7h$42J*gia?*p$IoHb2VleBJE_YV;Y>*}cta1nJ=(qO^rL9H}S z5`LlM;EFne#G9|JGBqF7$aij@%ZUSj0_~5A4`Q8(BlC}^A>=!~>!0wSizyE%h9>3~ zf_#dhFZ~2YnpT{xJ|s*}O@|t2eOw?ZR@t>}s3AjtS9G-YAc~9yv!j6ioByUqn8-NV8j&m<{~qiJN#iap zkHAN+I(aa|2n~NmUngyh{Oit_M_9)1@t}R{X&i(ki4cK)?=PD>6Rrwdq41A*)NQqU zy_a~U^Bfk9wO7-pwr>0~TnSwm%8W42DsYM>)3BG&vY2|%Xi6vyjl$%A)`!qA;S(rP zNsh0SsTvg&&d>-y{;)^RoWfI7d;!Ha>*z)wKoNE#W=*kugy!udnKQ|AVJ+8@DNGiU znDE~V!yqp-lDj@9`uW1Ldj8C`7GZcNeB?Gkl=rMlx%11ewQF2F-uIx(83Xi4TruGi-koyci__4cZno@X=rrNkn$dA#5aQ%&!_qR^86Y_2TGDx=-`4E!77 zF4cg(%NMghG9zrEl<5BCCd1x(j0Q1cAFjC8aa4j$cx0~&s^~x>;16rw+cu;|NVwRa z(8QE=PZ^!WLW3{a?IYqQ;_y(~s|nKSV;eI~N>RFQ0z3+|95xJpZ=zpUw+HN72CF>~ zjl#>d;gUA=700rCUj2$HzjS)g0W+?)=Q^|ZZpf%77mCwnYPR@e=|I4{o`eOWr9 zdiJucl}-pDDxUa%98a0)uF}Fw8<4LAWzDmOrv*Coq+me-ibG zuga5Rk$u=yDR~on+{r`sVPwt;TcZUR**SJdIpj^mjS)_D(X)7PTu`xxaADQs3BKDj zSM0+k#0|-#7Fzm~j=md_pHB%b4MUYfGO)rSd!S5!ZxNeb49)=>4yoI~RuC zo#m#Nb#?}SKS}2w?MMxEZyHDOeX#Y6N1EA&G>k4?t71a9`Kk7i%0Irv{*pQXO# z8Hdd?>KSwFHd)3nPw44pNsh564IU)X^A|$hzQJh}e7UmfU53lH(S%id4x9UR`A5`lVFkS<2s0 zq@sH%+ywvi&d@@Y%OZ_QC5=APfr5_Lx~D!rI>31yb_0BP5Rn1<(VN7&#DU%7Eb4y8 z;CSzo`P>YSp63Yu9D8QhpKSjiKCTIs3QC;#luQMu|4@#+*sXxA*WI9qZypj{J!Qp#(|HUj1Fx0Lon1S52+ePT2uXd^+^~VfQG1 zD`6$P!qo?)QnC}sqtqJ^H{ZA4X0!<^9iIrLh=v=GkL{XFv|z=8Gx|2aIGM;qT!ViE zd#bGJ$4yWT_imuwf5D9oZ`|L+Xh3kgRMu^}zG-$9cvH;?G}q1|Kv3)b6W&7i~*Q`_$#=&T5B2ujDGABj%#AowvW4Oay!XEH7%aQdl3a% zPgV2a7x+85x;QAN#*W*yl3RbCQ2*Zw^_QyrEcRM*prpha74J`*8nUrdM{=muKXqKb zf3FXcTKS&ht+(Z>!%@ivvenA@Sgn9bmmz3jKJE>$i#T1OZHZD&Pin9KFs3 zdXKi{c*aX|X(AS381Wu|PL15S1?YtET-oygL|>>(0Qp5W0%Hlt`iU1MUElpJ>yBlc z&fJtR70Sus>h^0g2nNvkA-6wA+kwcR#HI0+jpkM07yDZx^cr?1@YWM8B|`u3PX9^s zPoG7Wbp7CD5{>`?o6r(=Um_xC({fyI#D4b&(n)|}ity;Utx#QmLsW2mue0bzV<2NX zP$F-E=K(i4aFnP)U8d>*(!exxcPQe?KloAl)p3g~u7c>pi8$NmTo_0So0*o&G3L|W#`pjwTgPvWH0s~KPF z2ajpq4Nfi+pJ_PrhD6jbCHoXwI{B?pijq;kw^Cyhp{QCx%l?#P=MBFP{Xqfa1DDk> zg!go7s zt)D2$?OUo)Fa2%&5EWT^GA}>RfWh07W(Z?b%N;IuOS#ym+nkT?Yrue{Mj@*lXz?Sw0^N3LWYp|~r#PgGr-IllEt_Y;6 zUd`Q5GCUJg%6TZU6cOkgRg|y%)6KceReACS{lbwYA?zzglN@A?ei@-oY9iz%&P)`nSspk?KvIT$LIBb zF}r#UAivLu!VD;chcz5RWA#-ZAm>-ic$-H+jK4l!!k|3vF1iXxg_HpC=!=}ukSnO4 zC8x~*y;+8|>ac_%TE7#1lCptp&j$K04?{gfcQaiqKl_kR8@6VI2poJJVwL3jwg-7t z_rWiTrp%4WvU!#WQo~=QG}KhfH>L`InaOx|{&9PM9=74?%`a24;Oz}9R@m2W6PaCz z%5E_kg}dMQbT&}w61w-3>T5`)@sesDuZj+|E&b*}Vd_ph%#qTH(lih1Li*53T&y76XTSvrzJuwvqo zhJ1bYlbtoa6gL05>VChDbuUlsQ5n%g+$+!~03J#Yvgtbn{)zAp0Za8~YDyd(j0w%{ z&olnib!aWuOTG;BE3=%<%g8N%y3&O#{AbccAoRPdwZRQ61qb^R)tF+gBjaDUua9tB zIq2GNgoAM~OlIRmFKCBB>@FY7z>^~(XBVZOoSIM&Vo_BttDhAeDoswaJMVh5)iTK6T!2NA{oPU z?E(2;2sVL2y|acYxbbH-`YLU!xf?%?P-0xi1061+kaG$|tSEoCk3w&h`n7*vMZjFmT$x7n^hfn{=kd^-a8WTHHDyzPqm zTHkmkR28|jx3(Xj1%p-k_0TyrN;ea+BRu70`T$)8h4M<#JSd4f*LAO}ocNkQmkem0 z@=ue|3b#4d+cf#8W_#(IoaxZS(h1W@P2l?+9(OO*ZlE0p^ zV%681R%L`x2?$$%JTgqJNE6$!8@*l@BJgR*{R|XZE*)6zVE(XjnSFuOrg`M_o#syg zpYU<;cvt}LZw|#j(Z1bRZVk!Q+YnKgx}2(7Jn&~;S#5G6B&G>dS;2|?He)RJF6jeQ zWlE(J8R-~zgPUVTr57i6WHQ}3S&uZjF@eC;I zI(fuHNPm0|t@sz$R+=*f7K#JyzK2&SqujX5y*5y_;59^s}RDZ%hzyR0I57rQq%59u*eB<9D>}M593oK=iygblw=UrP?fnMtvX@MLhySz zwkk%v)`TkQK;9aEh_C3C&POe#t64~PO}+CW61bk%*c~*J1BlmwK@HzJ_L|%8T@_PB zMnv=1r1Y%6=hY$MA4i#&l_kM(WqbiD?gax0ZJN%1pAKKjcU`-XJ4}ytaErg#_KZ3i zPf9+0HpF<2R0zL4R60>72rd_y9wWNz;@Qs2TIdr%KTG`xvw!)8JqkdA8ZR#VxD;^W zfL_eK&OE7E_B*(Zr`Osn0}v|{!58YFyPV^RkR!gNfyXFYg+fA%6(Cvu$>mPa=5(Qo?!BC5H z?Lvycf>*j;M{Gq-pB%t;LU(Pk@ZEW1PBxm}qVFOU)X@DST#SwvYB)I_lj*_B5*o?y z>&9Ls%b2-VJ-_9Z_nMO8&w!&~YLcrIJaoB6{85Xl3%kHfZ=L#|N;s?nD0butQ}TYj zu?~JfmbOGbB0jmXqyGa?*rg{5Wo~41baG{3Z3<;>WN%_>3N|<(Fd%PYY6_D{&Km?a zG&C}k@jDa+F*hni>O`nSTLHTwGjmWB?I6 zdk;sTxrH-;QdLQviiU>vKPCT|0E|5TL-Xb71T?n=kbk|nnp)f0+nCxqe?k0TJ1U!+ z0-P;O0cJpJQ-FxPf~J(51b|XPP8A?wYHR9fXbn(sF|r0417v~5rnXL|Q~)zOM}YOe z4*+93TNB_vr8&`mVSfoZ0Sp07_NK+nV^jNoRI~tlQ%4)1lhfBb0O$lTcQmwh z{_26V9RO%+Z0%z5PXb?ZGrNB!WbbJAWnuHB`vOz2b8>bvb_Cix1HPgvh>HI^PiG55 z=YL{50l(A$JF_oK6FXyudx;y_9%YVoeU;=cqw>I?niv0y< z?+E-?8ZJ&iTl4?SfEM6rYHsLgVr}Z=^ab;U{ZDuPvrfSOQoW(Qy|u@`yzTyF^*?g} zIy;$Ko6*BDF@ME0cK(WO4zz`1_-9t6Y|ZQdOpO1Qo4DBjhtAd1@m~$1{AXsUzLGFB zv9q=I0GODX!GAHx**SlO1W^9pu}uHpNAiCI#s4h?|F_Wl|3>bA<>-I8#Q(4N`M*Mo zyI5Px8QOdez`u74;A_bk+5*1z3_up}&!Vw5bo~GM7}@}>J^oK#|J7RE^xx_JAHbxX z4ZqqVWNZFK4I@3{zlA_2aiF`Yi2~5s*aBc?X#Lf*e}BnUZB0xat%0_tU)=tytpGYE zM#lf5Q?URVTiO0Y0^7e;rnV;kwSq6Y{*^z2n2NZxv=q(%X2Jf;P~mG3oK-yRzjFH@ z)%>tC`Jab>V1$M3+yP#6OzfNhI%ZC$ulx6v5EnD6&;KUmzkrzj^Zdim*%9at(Eh5M zk?CL6|9_9?KTo><1xC!)*v{mi(NT6bv^Dvfw*M*kM{Vrl==eqQzZSq()&Ft+*W8<$ zx|Cr!OS+=F3F(Vc91k%#9)Le-m(vVTtA&Ox*Pi$SjhA?;K>((7_gb`wI2 zol$LndrVPDulNlLf1;hm5$5ud%8$e~-|su=gFT|JaY}s*dIxeN2x@J?$tiil(c=R} z|H#nbK=(Cd?;b8qb_^^Tk0GXS(g{(bvxkA>U4!ul`KJ)*E~DUrQH+e+MM&_sXy(Frep8ElNi{}J@3G0vNt7kSdkbzJI!`Qw6#~J|H+<6w`rQ_?-hUqoAOsWia(= zYEyJ4N{yS$#V#4k3w8*K)ItVvp@?|+DM zMl}PCjkMYkM><;-xS79&lQX)**>@6o@G}4pm#i2&a0ndHi?_(HVSoIk|N)8$q@i|$>p+Ojz5+qwfWShpjEJZ@rE&G~yR zX<+%!6blWJ89%q@dh^6=`KustK}Y0tvyWwibZ&85_eBpvZg$FYmV&kB1_LWxa^Kin14vuG=6Tt&MuiBUv5bK30N0>XQ`DbJQ+XtZ#bNN?8#Eo zGC{3me2ez)3MDE7$5K$w0Gs$Q)QR>cHZ1XVy62?VsKx*hDcX1|kw7e_iQOVcD!(uD zbX2L0qsH=_psKXoEX?$=V;iqXsA5)S;$Y{=zgqkKF8C7j;wEvL(SL+L4oZdFbq>n0hpxOtuq-cEMWh3hnItLnP*lv z2{k`5#0ik_II1~BYuQ6`dwe)$I^P%AT(Ce_D!0{{xj^=p{WHWGjGe9LMwZI^-UzS* zc{!-Qcou$RInXRW_J2p2#jd%d5XR-&)G>GVSdCB3dXoWWXUU3o8s5N+s@kgp~IXNn#pxQ=f#)DykfV|rbT7vt$X^C5OOkF$y1e3~LC?75y z`xS1Y30-U8ae1wXL2su+Xb=7GnV5KFcg+|91 zEs9P}aTKL;K$I6{a9gjVo zOWM(a=0m_ZUbr(C@U=HR!5RHVe220nz2_DG^tXtw)fItQy(%t<%;U##n}Gm>&Xhlg z(gw}Gwq!DGpln4;*IZa$?DUaxs`5~&Ci2q;JDzxvcJ;9*!cvt*lV~}A4Y^0^@X3mK zH z`eX3xeST=y6E_DE$wj49qB0%Z_{Jm`52%_Gc%BO+)v5>iBDr%?WfzekpLFnM5fsg} zn~Nmhi#b7<>lEj-Xso@&c*+@em{mdJL&4ac*?*i2dNk(MFbOf^Ru7VSlF26@xRB*P z`7P~*d<52gqV~fyq{g`H0ESN`5rZb*(Zu6w|A}F2a6nt|r{;G2OA%|)EoK7+IqY~( zR4$7o9~9x<^3202p84Un^@;cuK{dS*Um?z`A24I8bP81111 zn<)khOUi2hK(<(BSQCL+Nl2}%vi^V_a#WeJ%oG6Jc^Aw6d91sm`u0P1DiSi2JoFoM zxzmecEadClDj$ioN8y9Ocum9%jO!-qjQ$3`AAmNGR4)%s+R{A{}k4X!rsJk!?itw zv%Fo~>TLFs;iBsz*M$@sP!1HPp?`# z<}vzJpNZLn3m*>8l3rZD6EEH^;l0K{;P_mbcni6dz4G}Ivgl5ujrg-w22|dvHo)kq z6~g#V1!f#BP}m2Cev>04R>ippz>0n4?p`p5Y5=!}O-XPJz~09FjSoZAyMJ(Q@J?ir zUTl%kMa7PxHW-H5#qOM5=#tI}OtdYXPbPENFwW05Nyo_q>B=Gblj#XGw7kB$C#%ML z+jd~9$Sx_0q!C48LY^mlgAAUOiCC}Irx6)t;!+;R&b3QVJb|?qb{z{jIzB009z6n) zN+^9$k+Y<4V7!N1^^zWiMxj@8}c zP<~XTCl?+(g2juELY2KZH9;C5AHy0`ktAS5zP(w{F_>HAJvC{lqRas1z%Gd5??mMb zt`GbbK^gD@3=%>dF%Q*g8ji?n*$`xkI|PBv#w>{)66|IFDKnpnDt{nd>3Zh9q*c-G zmP*}37v6lIqo>pGw^bqfF$7T>`Kq7CkaaxhOvjBHnH zB`lq9?2prv;^b!V%|3jtxI%Y>x0NPf-jMskwG+bB@zAxyXPKx8Pf@Km`a$Ea4ul(v zdg!X8T&(jMO_uJe*#?v!&tJ%+Y@3)1z#W}yh*RNn#adm5+D1E7f&Zkl_=|4VQ9=(Iyr0Ia z1FJPd+eS-)^oFglv$+>Ct6KpyQCT^86i9>CaI)y^NG_9f*qssm325cg(PFGSQKg_9AZmVgEav^+I-zIiPphMbKWUgq?k9D5Vu z=^m`DSMIU{E~v=6(O#pKw~dcNm+F2#J;e!Nu6UGAYJcPL$T58yjp3LHR6tQMh~jEP(Bx3EVmgww!TUp^I$0LDM&Ix>i^NT`g1A@QYy6BBu|HkGbRFVv%mml1xr z)wdC}mc7We<$U9WNh8(|=@L`M>7vXT?8J)$sIMVb5}&y#^f1_12+uDdybv9f3t(*V5Mz z+ZdfI?%h%=uU)jc^RIwWGTdrUiw#5urjzw@rdTYWh?e4_zSLDxl#VO~ z-i~;tQJya8xkrT;?OQL_4?I&$-uvmkz1=#FT{)?x`y;)@=YhvD-Ul~j(U9U7a%0Zz zHh=pDYU3%*0g;mQ3(0$sNp_i8w23cTvzgkvW7=GN2X zXzdX_v;8LJ-wP5R46;q>y`OuK_uSI$R|6aQW`_x0rb!I8xc6ls_2y&Un!xJ!5D*liYcKYES`_#=%qj^b|w& z<#?d$xXQR*rZGYq1qP)%h9v!hZlII{es6#0?y%!!4qb(Svypi0keB##rHYL+<9{~M ziw1at+XzRPSs7NcQV7vxI|hu#gUHy}6CjO9DMp}Bpd32yFIYaLOXI@V^#(|~^^T`8 z7>H%z(!23M?`&Pj-9O-C1tpsXc z0yV8U`sl)}`!p2Ol-+ZNBba^MQ-4q$f6c`f+x2$^9|QOFJVnk$2;&m!orgPI}m@n%`G0*B$ z#ceyT!PF>lZ$J0)FS0d8(Z`XIJ;&>pY0jF%--rDB^K@mIxT~6Jntvn(+tqqOp@uF4 zQ@L(^%O6$nFSDoaoOE-d6ad1f<Q@UNU4^wZ$EkqD6UQ^;^4-0Jv*JO>mqO z&t0%(oYF3Lb--~TXMZ{m2jCNw@=x~993>uvAhKVbb*Dgwo6|9P<%k>!iG#V!SnDq52nDAov?RkLnHGlZHjGGE-P z55U5WWKFH${(nZ6b3*bA-?aRNbLk_7-^fG%r;Xr1WZ#1o^!%M5Mx94FDh~Z>jLI4= z&dF;VvX#|_1?0llR)d81CWNluc=DWdtAkkRaOx%$Bjsx6qs);^Hg>Xj3ml?ha8jlW z3I%KeoAs#S0>LC1E%7ruMd4?B>PP z-AF1-umItNT`w;RCs>?QNshM5f_>sMxpWj9-GZtLS^2^j5Y0DgA<|-%A>cib(O!si zP=`~$Sbql_CpZz%$&A{omfOoFSF2a;0{;#Ja!#)yWG^MagOD&Vn5UJ zP|(GqiFEi^oSz34Prh2dV@U?Vek8;6wv>VS;>XVlS&rs>>)c1$IpnRREZ(Y3ya8FU z-wYQZtF*hid|CYbs_ELYh4yd`Q;P7HvshlItAEetPBTw7HAtOhGl$O=W(+z?eBb2F zMxJ{Meh;v^G?l>TweoSycn-T#oO92K*>anAYd59=9zM(f3rQxZrLl~v^DJmzKVa5j z91B()-&?nDtqlaqOqpLmo?^y4lPdH?PeZ(ciJ7?LE4kJxq+Zhzo~ZI*ND%{xh6R*j zTYnwL&ei#A+HA0^(eF!b)T=r{Zvg}Wxgh>PPg$uv@Ah{p!H<&0SNLdFsf# z)BYnTgko0k?F9&1Q=OmsPTy*`Ho1#8TF4~L!#X$)tS1u%DAeWo#1{(0g%0r^1>BQr z+d&yOYajJT3IE=-f|)aqJgKzPI zAco8qW){z8;W*yl=!d5B)`+a=VD!ldRA&7RXITvA7yeQ};=_r}bnPTu4TYE9T=y$8 z^&!w9!SJ5cfgyzHp}JMklTJ;R-EVJSQIEV$E0r@a6fz9{l?@G1olhyre=S~ym49E& zGZe_p_-INAg~fP4#M^OV0|`%8k@hF@@dzsiZ-rs!*=mS=AWsk4uZdha=_tFPJiYSG zT`l~kHcO>xOSs$1heyDrmGzVM2OI>3vuZy$q45e#vO@pZfr_Eu+WR%2!@(m$HjK#}EWt#7V)?uNZ0_?lke-C*S;#s?~ILJ;R71$y$ zoeOUFGwZjMA{W)YSFiDzzJH+?I6rV*3QWwX8NVr)jdxfK`+%53xz2i>Oq1z=F}idN zwAnxMg>>~>=%=RLW4RtATy?>UrnzF4)Mep%*`0s#7(dFzjjh}5F1o{qy@Zj zpHih%nl+qYO>mgL{jNxk%o8kA%rNI9P~o53Whv%(N0asR$0=#T6MwqfxY9)PW>XXD z8oejgV~lokPLmdp4!57-B(Uiu11j)(xiuy=;q0Ot^L>-QrH6UY;DtkV0kRPKFP-MCFG~84EDT5())hli2!;iwEqG znH~_{Rr8&L%srn5{eNI(cxdQ`LCqpUc5gz9czA;*v;~^Xu4&RfAfy1HR+7k`4k_XF z9&NEz4SYEF)>qL7T)WK5C5=wT;CiwwEH`GRbh4&p@w5S!ju0+|+`aTT03Awa6~l(j zPLk}*AyM~=zYL@sId^wGY~sh(&st$1=&QRO)5J|LO)wmlc7K>ElD_^zeiM#I4gH~o zBa`)GXCoGl`ysOlbey9*~IeG zgXqOy7ao0AaDRHJkGLe5J4YNh#4a@RGyi$pQp!^k*1uxS;bfB@RVs!kylgM@@f&%? zInQJ|-UNjOY_++2FJHF*vL<6Q9-6h|4R@i_&dTUx0HIU{-tYGmSxd6dpg8N50gV3s zSyO%$Z^q*=x>(9HGLHl$<>a8`+f{I86XZx-tlPftdw+$Kv%yfZ_32|WJ=UexzB^@n zg-EjaK1*v@Lk_;9hqv<6(h#er>x7MdCARgRS!tA1DZ8}vtok)`Y~ml0<(#;VC3_Zk zj6y*MHcWRHmn=`?NsBHq?3T3{ zrV0b#CrhxCTK|ZxTg}HA{~@-CAe%*G3`x8*OMiQAi-|D{Tx2K2yLsPOft=chQ_^9Y zD7|VFm3K17GtKa)6sC^HYk}Ke z-7LJf7VlcKkQcXU1!8*t+?}bj6>9w+yE$m??xwskX_biuKqe#*M9MDv9pp`}9tnM2 z27gXLIkMJ=jpFt0PIm5@?thzIm7i5anmJL_zDz1YW)rxB{^UJ#=0LX(t8$csZh=0d z-&z>#S0ib6W0&U&6KCU;PP=vQ z*Nr?hC{e5D7!CbV^h8#_3EV_H=Q2xCNq_(CS5)*piKG2x%YY-l4lSoeQJO~QSG-YH zlGQpw7)d2aI~(2#FeI(ukB?&B??klVdde6)4sAZDHEmyUXvbeoElm3xlj&G0xjwqQ zMl#iqmia9%Ix-XJbwPh0ZjE}y^Jnsm6bBoos7%V1*ofk4+SO_447*3;;Qf@V-G51W zmFBkSe-#!o!TR~(h;tcq>1o&wEgVJ}gvU`hpatCDZqW7FsQt2=sQ}(yixIiuF5jCh zLDV%SbB^nVl-hy4&OyUG>~*dq{}Or#_Zr2+S{X#^J?x}<|AUAED@Up1mNU>ZznaAx zj=OHW-3=oV_N(X;{O0emi5i?jbbpWv-djJg3_1#9SRk;2*6PseHI331+xubU*&+rF zVwYKMD7ZiIw%jHcq6|s-5VXZHf^KHIr7n0t*9;^{H9Famcfps}qkmf&ZQ5KoZi5PD_Vr zSq$ILG@%XbQ<(Ye#g_29uA;Jt*%H;l^V8znxYb(e;*(3EaX;23-GK0mknPOlmFCCJ z)xxwVCj={-%;W9l{BWj zLa}xk5`2rL2yK62sg4=Pf-q*Dnm!M>b601)^nV&rnB=P;5z0p)-+xaDx==i=k5wvM zoE_22ooc~g>zMVkb~~6=Q?eGATn?D zuRpcT^$$w(v59CSeSc;KkFlTn7Tb|TsBpd@Zr4|$_s;JwflKpZzR=Kf7GQZ>Pb(h> zAhPZ>-IhKcb`Lhm(T6_{+jbNll~KC-3KHs@5QfrDb&-B$g>i+b(TvpYx}b}Q*KM;< zp*RHHtc~*wJQohS&D{DiGTM`0ht_JJuSKixHn@$ zb>lH~2B1ZhG1zi#Ggw?9Qiokmwjla~&|ewWhGm~tyRc4aRpMF7W_)@LE2(uM7g+Zh zYYmxl-M=-*n@znBNqDL#h;JjZlJ&rC=(9F`R|=27Npzc2^L0 z1v8=M$Khs(SAW=M$2GB8QBHC<4{f>O-qoBjaR1TLVGNW!YLprbuCe~ltl-Appbng;@q&#v1 zl3lEmSD^|a7wfl+LA8J3uoZ!;D~4{9^lMb}sW4T1Pk-?B*sj4ou0h};UfIUBlIr?# z#`Gk!`(AXryj(77{tZL$t=^HXAA)Bq^t7aQ7um=$w;1{q^;T#jNSYHCTq;Q~we?y zQTMkfX_u*-RC+75Ip|5AC0+HSG9Mh9`i{))NeZHqUU%{v?H%O{)^(~w0qWYj4D~(9 zjIIE`if6681!rlP3M&63w-lEzDWTMB$}JC1K7RyYyTwiYm_Gj=_sWw}kGxRn4s*tJ zOjuG$ch+8N@%*j<6EyTU6mjG;nQjE7yQdq9ag@4&S|afQI3|tvP>1TdQz^BlA=<;=GR7CChk?-?LGb{cOIi$zXdTu%#V^@*7 z(|?DQV>eM82(Q4ZqQhhAp2 ztWgnnec;RXN1Ma|{81OyjTCXMX>a)7z>_>zFzqr4cH~0Bd?rs>y70h-AuY8t9-;jR zYOk)VmGmEaY+rx(kOh3I&uMTrVX1Fbhkp=x&|g27t1+C%V+n25D8_%%R&(i43U4o3 z+1)WW$Oo&s!gmFu+bvGME4-*PGVH*cMr^5Myw=ONXWEUTI5`K9_y2w`7~>AWDr0HR zy6x(>oRJj=pZ?8{8tWivMbRFtg_j63EmX8tZ+}n@5k|6b!s6laO309r+f{sbK0#^+s0{O3DZ*xZ z4-)R0spFkRO)h`7BFK)$^)pZ#Qicfzo5QhdCrCz}Fg;Zj`ck?B=jSciiakJ(;c2TO zuI86dg~JccJy}Fb#q*XJIMw?^>h=b10Ttp2j=vhMzJDdw>=Cs7{)PE9BWm!eDi)W2i2SjC9$VjT-u5MCOvl-q8Yh8;940Z%s=Q+vyyZvfD~t} zLg@H}CY}aCqJtN~Xsmt-_9oY27CW{_=|q-`{3g0K>cXJzXJdcT4q%e^JMLOV-8}1K zRb2Olq`g8~gA0-a*}^5co`2Wd@E=e2K|J5~0lgAplK}Ie?Bh!&XcHvQ^GdDdQi7wGBcWthDL z#XmRf5sYiDbv2jC^4!sV^+$2}(!pD7T}o|60LZkTh!!a`lRF@pDt|ffc9Eov`f>XV z(;ku7kE7X+sgi$$u(kZE`tlr#EoaE+WLdynpu;BSd{-PbFJywGMzMd9T{}apd_lD! zrS);SCi`>OG6zb{*llK`*9p@rBI^KEKn5hLNkV}^M;Y%I=z`%vlAD@f1{*QDrbR*9&`$tEkW?r*zo)kL&5HK2KcrL_ zznT}Zo?8G=qA#uh_>{7a_wFfXmrtU~f-=7x8WuBLjt57tlmr$)!<<3Tp$d}@xeNYt zKZE);kb9@Jj*fS?YkSfqxqtlI4Ay6X#)W7^JLz_#>{h$PkAD}?+Pld@#cDj+3skZn z3uhJ^2h`pQY@E-hc4TBs-`#yda(oB3B+=MW0d{aOulBB_VBBd{)6tpCVY#n^AV69L zNyaPg6MsEo!gok;hHWQ_1N8L=VV#mnyandBgADm`czkyGLR=R&F&}HG)!)a5fy_W= zBv$Nqe=PNeP=C2CZ#VhAep|ci1XrE@cC%PV7ZC+d_FNQ@I(ye@YrFeLm#0_dF52Mr z$ntEgo`lXtiY}cZnaoM~n8^xlo6KncY8`}p)KZMfKssX}KD!~%K`N(dnp-aoH^A_5 zmv(fY60-;LFJ4sQ8qYpFXQZ@fQ#nLN6j*wfmkD~a9DkkM`um_z9i*r(^!KuG?@4rZ z^(W2Fo+gFO{3yYgqJ~J;UJEP0TQ6nKwH}4z!Wd`CN#OQ=GkE1Yoe@DWi{QhQ z^V@rGI&{j5SR)meEVOfVh*}F)og&$-`YjeWB( z)}C`dQ_hqv>y1h~y`xfSyZwXR{V$jkAAGayPL+5P!6o*{LgJTBlJ;+JdWb6x<;W`7=jU~(aPE_C{8J)qFF{+aM1U@gmhr%)<>rSO z^e!;mQj(>V@&1pd$pY0@^rluX!HRhg^5nvKB z4C4-Bq*zL&?7SKY<{*Wi`CVJZt1hU}Zp-`pS;ZzP35SLbJ(4p6#PUmsosPLh6Qgte00;vdRSycDZSH^?&P6Pfk) z#lp&VpnWa);`jRbp3q;tm?J~(lW<)Vggm3A7svNsiZ5AAqnM;tQg|zsl)^yNXAjC#StZ$TpG!GF`oRCrxZ6LE& z^jmj7!)n{sK4t}5t3~2JbBluZ*U<|$xlH|%S!&0OgM-)dTp9j(kgarw_!(%WlK(fK z4STTN>_O|a=b2@u)kp>D&Yuu+tb92_H;W^*ek@Z-Fsr)fS^;3o@>F!L|? z+Kq@C%b^*w#vLOkn3NxAom8KYwSOQx=8ah(HB zwc%IwX;SnWCsV!zk4Zi#Lno7LbQk-3f8*R(Wj@n>}L2 z=Oc(riL^qQFSkxZI%Uk-HICEYouLZgtSgfR?b`rXWeM)Tp2-`X`pbo0l_Z=tveO91WASai5!wH@%TTgaH{@+5Pj@da!Ys(;c`T`1gMN6JxG=gC)Nf zQFdXG`)}KeBjJ^SenI563Vf6oW@Nm!T=AIbFewXWOMTUMdq*sqovaoMIik&A;{!e>ir7 z_9Pqi%}G>hPPgsUm=Rv029{n5RLP#l1*=eVeKudV$s+*w>olnp+nwRwgojMfsVea| z5-tKs*7MI6SE{2HFa+Ko+5=hU2sUM5p25-atu0WqpT{?qn-2wiy{)giKO?Jb=+OFa zCPNuk#P0`VwN*O-3OJ6#<}^)JX#{r`3<+s8C&sxJkfsJ>UpL@1!((^s>iFXY&VjT^M{6`XY>r#pe)b&xCRv9}W;^94j*{&}Csk ze>ma!u3SdVFK=BEX&V0Ly<-_Cs^0~lGSWz%Jx{zy*rco02eR-uO*uxqIgB9mKz0*y3Mi&?g$3D}iUWIhr31;3QYzvUgL2McHZQ?iqo0NqJOC*NV^qVsn>cA1+8 zFzgqO<%3vH5V>gAWx8-;BZx)B?;>33juHF2QVjzf715g#Ghjq$Ss<5ZR0qfij)84~0YBKwK9l-0PP4YD-JTMl?Kya2!<4&V4y!!%^tOcqpDOF)HO_=7N5G z?Cn{GWyj{eUduPP@m4uB&Q69lF&3=)_YQ~-2OToeOCN!2)e;D)_^dz8D%kTbD= zDhKVvff*7cG-epLzW3PLMywujjuOyKn7DV!YR5b1G#fhQ3pvn5=&@$ zlJ!kv(|Os1X>rN2^=HTbfpIc_yrNF1cqn6Q`D)Dil8@Q6zbu~#yRfm_OarqRc{ipm zwkLbGM8C9RiqMVl9w?9GkBidV-|r8#G4l=Gh>>IPz9e5p1u~PWXY9S!>gD4X4~?c+ ziUlH2WgMK);w7^HJpu^M>)(?CS736sG&p%0a#IWKR(xAmJYZV!S({R?rxFEpsi)4+ zYa8Zep?L+K#P3pMUAFZG&%o#Am*dE1PT%>^#YQsU$Ua|KsoZqiyboHWLnR4@dTQ}` z^;jp~;b=8&!|C=|nFzn?$WRy+ARahC=8_~l@HHL^D3~>8={>9(oIBQcKo`jy{WDwQr&5stbHpD=q`eeDC)L<)vnn-f86TOJJ4+5W#~nV^&0--aY?{I#kCswC zfAk#^cu+-#APs1K1JB6IhW|>JLp@@UTD0EB9PxFi&cxj-7l{3CdDV5lvK1T~gbm1U zhQ?u0ot0na?Xq6Z(2npqsP{^24tD=*R%CR)@;y9<#dkfO)+_@(&m8C7ERhB|p7G2y zqRg3L!w#P0z}02c4FcFPc1u58OY!gT2DjOjX&(m)x=`aHLHZqgCXO z3{idE@n!{6Id-R9s{pDQGF=ae_z zjvT5Z&nbNV0;pKJN>Xr_KKeJc5X!U#xWBog1ohsKpnd~pW(ABk#UyV2>HosDLrkUF zSnmnQ?3Y=FI3J_NRSe6LiYvP6`u^0p4eHkcqYm&g~k~;INXv$tjFN z1Y?1#o|(9(5?=i51uM8GLKj(LP^KT(JzV#MYe0yXB@*x!<(QpQKJ;u9doT&TAUfS8 znQ+cdF*Qw3W$f-A(Sm~%)#z)L;r@DntB1PxAoEQ%_3u5h4gY+zsiu)A3h7xH%V?~v z?kxJh{p%W6G(qO+0-k5W+LF@26ox8uUYxE+n5oP!jGS0{oJj8bkEBqnIL3rCeWzBz z_zG{H_RwFXkeAAjR}M|faz-ht+p4f9MZYzrilkhaM_Fd=vL$U-8gq_?U$iAy6Z*o@ zIF+%1)<4Ba3q5ci?l@(ny~<cZX6$xz&40-g;%B58a_*s0-mq;Q1=p zssF~XeY5B1JH*mnL0^;TrdY-aT+Wyg4TeN_kzvrSuI*Dic|)dg1*}zO!;_9Qqt6kM zfqYkUbhG9WiRJ>O`WE+y3^$JW1Z5Xiz2d<_Fx)zhifrgXq}(d)bMoJ^uL!)eOiV}$ z+OW3)35YnpE7kc$aVF$7B1vp@;D89|>*{V`85`P@V`c0{y{V$(?Jdu!;@JFEx+IY; z{!)+`<(&5V5Yz-4*`p)L${^?cQ{L-n->P@50<47|RZe+?k6^oY0Tfi+D_0V0W*VEl zOtD=FHGG@ZEpm`E=)sBHD~Qp^4mVc_k7=F9^&6beXCvB*lf zvoGb`g^qh$w71-0zIK)d0vK}Q1JWSYPMrpo)(}?<4ZVH#6B$=!$H>wl(mJ(=<#B=O z`6SW9UYWW&$gso>BI$3DZy#boSl9y@#VR#@z9es2`M!ts(B6nSG{MXhp2?QYpq2X) z2b!S3zhI)*RD%$=vX}jw6AU>!MLiu5^2Jbe_0>;B(><>hbmFilhT;*R>! zK4~kLfPM>DQjyNB&TN9b3xmkR*Sun}gfdHh(UglD(Gd{a%&A*<(J6#3Qnm?ui|HV= z^Ofei{q&6*k-BW9%0ZI3Ik7J&#F~jFl-vv5#L#dMo@8+{swn5=^pwUpp0+wS7v6ss zm2B64y99LnK_W_lZSehSnC>0i5sR#-iugXe>VYas*ptox>YQtyesOdoDkf~BNP%b1 znx|S5d74-mWqjq#V;Ykq#SpOvZn5>l6&{!7iQmWd?`GNF#gAt=hU3^{#lz>as#-sFO5rq)MIl#a9JU zT3U81o2+mDg1&)cZQ>S3co^&3=uJ{#6-oM#cdD=@hF%1s0-p7y`zIFdQ$VvH6tl0i zOSRDy5~6&a?tJ2~?f6G7Ck^;sRcpFyON)<)ljAmP{>5VhBhEeVuW-ZMGxn z8_hk`iP9ACz8IoY@=E#T0rA3hP<(Z;@pl$v%2U6rkqQaCOxqj6 z><2tPbU&u9(Ojn=OiV)b$);U^gki42m+}{NFk41o;$HeAkvea6;E$DyOd4AbEG1X? z_-JZDp3Q=5Ki0P+lh(RyZEQYbCdSrZ07<>4YR^1?0CrPtos{x6NH^feLSOf;aVE|B zF|C3dG2#zmyCF+WG-`G!NT(4Rdymn0ADu954wrd})FX~WQsE)CWUN-hsAra7K&Ef5 z;jF)Vm}{VWWmQSvx;c_@b^FsmLxU}xq19M8m>9+(N0Oif*1_Z8Wy%Jc0=2pW;=eohX+(e#W*=#b0XK{hebLe34wcW~fc* z&y~KdyHH*Ly@WDJl9xPru5F+FG|CSRk8cAA?Aq754=2NmM#0dSbWdyZoQwa{kGMIP z*(gUUQj|5pO(eS9TW6j~O35eOsPEwJ#_-rgsLQaDP?i&RVxsTTf3bKrQn%_GB`Os0 zICXizpr3)+`LhGGCLJV3RC7gEhmTkXLDOoSq5iebtH=!|Rb!fm$ofxG<$`@iRS;UJx7qt0YlL{oa#ViZ4kPClb5d5 za?CdMbZjAZrzf|qLfJz7`JT@vz$#UzeF;9-aLlL0?R<9A!1;18*M&{daPAd-W?-yY zsdmegXg7Is0|sVN;m!R`9INfO*v$YGodr1f&h+HV1)-sP)-#QD6?V=jEe`BrbaNhO z2dN2;`{wrA84dz)qW5F@em^$oL%FoUqFc#CK%T=5;#-pDxJ-Y}mf|c?WxpQ2nGOCt zx9MV)y%Ip*U2ME#Qhx@oJ~i8W+X{AOVR@I7f#!SU0kJQCj@rvDRa^B@IEMxNZiN;v zOeae9yLM2dK+!Kt&+~#GIzuDP^vWmXxCa*dAdx!SLKC-f)(m5?JTTdx(U0kbL_Nu2u zcgfY&^s=`q;R;^a`(2kz=dhCn7GeV^%xyc5OMm7vB(tigX z!C7aB!ERj7{pOz-&9tE(5vEtVtFRxN&^l^Woy0!$#H6cq@k_Fy@Z&&n+MAz*D(|P8 zjh|ug-$nmZee%T8x-bv2kdUjcN!h&r-o{B_K>_hV)E9z|UPS5H#8*qH)Yy*`Iq!!~ zMQyu`&#$%AEleqUG*(%^AW%aMHthQ1T=_zFtlvMuCP^Si_WI<%Q6jnLX0J=J!ch*& zhs5|)W`fA%*3iH$MMwb{bwSM(miF+M_qZ?@2jgFAKh0?z@;CSG5H$!;csjX_@mE<9 zg_Xh-#y8BCZD8HO#C>CU3|khp-BYqz9{fcQmUe0NYj=)XKGUiub1cnw%53{I5>Ac^ zrGAwmn0tp4n~0`bw+#u2j)bmIvu3}+T=B4aQmh{Cr#Oc#t~mi1`QMB|V1A#0LP!C0 zZ+~L-I?8(`YFO^kF5}6GaTa z<1z4yKDRfDq>G-b!Wt7yBb#dXh$a~S8P~=FgNe^OgO$5Fdh81oD1U1{55`o#vyc%4 z?+MC=Xa2qP!7>0TFSi&ert#KAM1LgA{#gNLE&h)+bG=B)qH(y8k7D!Wfj7kk|(@Ns<&i9y-0y!r%1r7QpnoL0anh>(XU>LMW~OewJhdUjF90jQfr@I#>iPwouRx;;d%vIt{q^i?uOBYsYHd zM0tvqbHM=O!qDuI0!wXENE&p+5%qo-sl{ww5zAY6`1%`TqR9g~(4re=-{^Dpy19+@ z%Aj<=LTdK(8Pi=$gqz53c#t7l6@E|$+YF!aRa0ozlz?UOD=nuhIh-%y?ff$4o)31d z?~D<@i3eNkYjVQA?bo;VFwQC|07IwNV=P# zxXfT+{!!7!Pn}$1TclC55f3^LLlXCYQbahJ{=XvS)IdZ~JaBGi*2G(0bVzPab`IkI zrz6?jOcQUjo&lZaS7ZlUtB#Wgz0xK>1PlU%RITw)errdEY<{avzS3rtXyCp&wfos~ zcGt7lQ`gB%+q>kQ=@jq%^rW}N6q>iS8@)RXT`7eW;W>!K$?+~KRB7N9y`Eu)k`H@n zJX{Cm=&(4fJt!!jkuUbc1Isk=4=(I;VjBPy8W#LPNF78A8TsEEdw`CV6wGfzVsN(y zN2ra}eo#4{4DZRxO55-H4<}Gf?+hhkKoCbA z zdEfZ4B!H@e{h=lZKRaKM@JVqMEu9A)DhxEcFV?YFMcqy7wdW#uL%a9;Ff=gN5M=Rf zYyl3=^>tz1U=?i&4Xy=*w->}Qo)`E~WROMfg@bnq*7W2%@+Wn1h5A+t{Q-YzcwYmz z3NlTM_rrn?1_sLKuh;&U3-9;&e@)5lEsn0io*x(ppA#3k>;ZdB$b%W+zuzBK6o@}) zS`b!2f8Wn^QgdsHf^O;p8&$ga-+^sGS>Nr%#e%E@AF9D27>l6$ptWFHCXPV4@SY+K zsN6SiGWVAY={Gd_R~*a-(VypU#Z6%4w1zIXolea{=U|%K}6(YPcWt zU!x5OZGhkel<^+?OM_!??>F6IKOy|>OK#BjmJZT`$I|!E>&?F%nnHZr9CYK8_HCrYyw$XF!A+{6{+#+`X;jaCf)y9(OLq#hIfa?c5-rbastok{swMeSH=!^ED!Mm zlqv*W3L#q@YrS#10Nk%$AuNj%s-f?7D8=mWgO3$5kibo0q394TY9;bn1`2)*ebFrb ze`?F6B~f@*#G`dDiSEMNVYHSd4l<`1N^P%tZpf0KY5znUMkc!tK2umGo|Ldqg6mje zU6W+@<>!``#=)qnuEjogJsY`Vu1{os?^#&Ozu62a8#r#B4*`Gvo{s^fL)gcgkl z29rdVdiMgzvwGa!51^DQ;%Lo#i)6b?hd1A*;X9vhL#xkbj(I)z=tVwJS?qMU+4_S) zt5i<8JfPP`*S@!~F9CNOYQ2yP2oq?6kJ};3Gl7(lv?}lZcfj!@bn){3eE_q`ndxc? zs_YNK%Q1M)5`5?p(-4AJp1%V`Waqew6ZZV$(;T! z4qEL_kT-G$)$C8F{9^0sw&-$HBwrb=w&X}UDE5f=IIt9LP?}T}iM8c~d^5oop_2lT zQhq(yF&O^h#g;FM?vE5_PiGtEkOQ9>@hyc^sq=cnnMxuc)#^hQ_RMGeqf7=%azh&$ zctU+7|4@0^)ym{e=!GCnH9K-wl(0S{q|9GnMkOX2^eFd}nS3%%ON}C*O>*p>KJF?j zSNq*C|34d4`XnL~+-&z;!>`U~I=h5wyk%i(5k)e{$1s%l9(i znsyph@%_iOML&42ccVR%BlO*>>&5?f~Ws``6D~f-xHs|l&@x^fWgJKGG5JOYprA#{f;G!*;()zB4LXSH{c$&3l!-u%1Sz2 zQr%Ty0%_F7669Jb7lpnq^%dP!mcFj9(y9^}WcWAf!whNpc3#-sLSZ6pT|;G$q`a)p zf<@r=5)!P|9A@`&}7%%cfrQJzgq-Cy%zzMeHt&VbHupf*S zDNV+I)m5mGLe{(Ve@?cE{Zr#HPuHZ_@$d7SU|XO@a--jii&jWd4nb1vHl9Mdp2)I? zBWg{XzUHG%-5uSgvFj*So>SrK8i3K$1a2fFL>%{T8QBsH6F4XOS%g<|IQBziCvKm>@=qFLG_B}WGjwR_5TAa8Hn&;YW%~!d8RR{<~0LKOY z+-Tw#F5i#Fy_SMB{Q}a?8SH8i3L~=%4?c|tM~|1N79)y}|M9`4#r(uWXiXmDfV`3{ zrS|mi3*#>f33#8tihMsB$(=m5-BllbEL(tGi zj~1zuIH_29@t{>#Klc~p=>M5^sj#BEc}LhWwTIewpGCodM*OF%ZaMb=Rq#-9JI_mU z53;GWWo*m54Sl(`Pb*BuIBk2bZ&8|{EWVG#2S~BTJCr;c>)tM9u-(H(Kzb%4D3zvc zOP;4e#OaRpv2crT3(TJqcXsE>DVbrqUqY}tU1zw_xP2JAH-svkqN+*p#5N0nKCLF-&!`c`9Zn_O$%u&|XCw4s~J6uB4G|VAS17HYxR6 z*zh|ptAj}sdP82XRjOLr{=QUc%Q$L>q*lOtbS!kWHhhkxo& zLZ7VrT2QkV949R+;Ilg9*HbeUCz-rfCKfwQdjt>vcK%T_<2saC1eQ!HSkrPgVs`G@ zL>&F)p*Z&+nj%gkk^ZPm4E0$&OX*!{`SDI_jNh4oRjVN32Q|FoYaNZ=iIqdw^ssx z+T?*Su~+V~4PAMVoOBNliJHA!fZ^}Y?X&7o;bBY~GC{+i0F<-(oNBemQ0UtId~|Wa z%!N5iv#n-t-rc-3Y&227z|ugjz({t%+YeC6xhK~!0D_#!H*+(goB z!7{87cDLdugH_>J+F57EXUE%&uK}y*Nt|*ASeW`*3N9V=$}-DyF^?R-ETA! zH&T}k!8GXT`n}i143Ta{V33E=L#9Ar(Rw+#VgX}1)>cg(-g=}`GfMOgNz@!A#7IXH zfcR4TW9rOg>KVg7fsqlK;v!jAEIVH_ufi<~8E{O+Y$+=b>s3!21L8*i5CA%lThQFT=`QDfnOF-lR}d%JAyx zcK-#yL|v#UD7T}#`>1afv4<>B=CirMA|4eGR^zx~fEIwOXK ztDB0}m(Ul;^1Cl`6u}RljvE2U9yvUL-p)BOeIAR~Y^{|dAZpZ+2SZN$?9bq#1r}If zbCMow_uvb?g8?R9d;~f>=R9bvL&!xmOlc>|n6n1$Rsd6~a|BWPoPVM@Rs6V`qEJ#8HzT@z+uH@7vjzA52?;NyzdK6XB!c z{u33b=Qz$~JHAujRlKpm`4YJ%>wV_Z1lL2wF{@}JBeS&<*ig6)2qe+3}{7E5%$DRK7#`X2V zCTmwV4wCsWlDiyF_c5BOB8!Ap*A`udKC@M@3BsdB?jLbuTF0hcr26(*_9jN(PK%$7 zR`zl((Q{h`7f~O#ghiK){`+K-=O$)_RNt#@Dgk9mv%re?9-!D`a4f+}2r`)0h}o`7 zsJm?--1D*1K)h{4YW^q;>FiZtO|nGpzsge6Tk^0ct@YmHf7@qPDnqqsOSXRpNtJ0y z6%dVVFWu-^I=xd7rExiEu7u5uXyCtGpbiA-KT0DEQG_am_@3H@vO*mP}GJ+64Q zBj)f;a?ER7tV9{8XZ~E>Dn7QvEpKVL6p55dHAaM?f9bw{U6b(S=GzOx#w9e4lWx3d zXsCRBy2#2^GeQvX*b0vs)sQ@IZw9f=1(h6w;7zSpr9+yEEim+&v;HwBvahqt8{rMY znvwBi0-PB>RaI?Ax|@k`A@Uf=_IJxFzaB1uq3hV*g=coy9*BY!#6e$9b<~m%pMYqg z2Q=O)aGoHn_^l`&1^@N~-Vz&0Rv2-%NM?Z%X@zgxUr)KLxT0Vknm zcE*}t+YuB72s zfsZM&T4gy=$KgJNg3(n;rkuBn!40l_*HOMW#Uq{l5?V?+5^!9MJ?#pgWvm-Ci_(D1 zXu2wWCE|z)hOdE|O^Itb6UhAIXR)GF*ZvSRDtNJ*=n~J_Py2*fPTK-BAN?>B5zNgzND!h}oqVes!V8u2RqN%+ z!%p?_p$XenHFG{mPC3yA4ScjA;vBsFmR~;FEIb;$Tp{<uW2ZBjw>v~^~rS$kj zQ`MXtHWS6pKi#nBkxgpPzB*qW@=bbE z%~tCi%A%J>9`c%QZq-RQ3FO-c2i z(KUmuKGM6r&r;3R8NF9oYk^^h2?Sg;)nEN6=_l4Cn8^5_%8TWU<>r^l=_u4qgV*Z1 z5Ocn!IwUesQBd>Yny#8s%20$&Dz|tc=WzL7x?=J!cN~%j`ue#6VC4j>!05n>208c+ z5#X>e24Enluuumj^vhq=$rCmob!(n851n=uZ2q9dQM#U95w)dg7qOviefpUp!(d&R zmee52xL0&kcIC5Nb3kU8oTfu?%+DpxP!Gj+ugF{@tu5v(8JuN5Epc>^;r8P4-dU1E>-plkVu^z?)17fs;1Vg7Q%gh&EDNVW9paA%j|2#q<^!c?3-bH zIf%kMr~FeW<}b*^$hG2zRAwH&+2Eyxe1z>LhrPtHkj>2c)T8_NsLB}(+uYwk&gOE5 z$YO#5G0J|!(*$k_Z?7wMRJ%;JXnAvJEY+#ZVBKju%uI;8EYoj%>hR%XVdW z+4b*^>K@z6hI_mJdb041vRQr6498l4P-=PoPt#{TTn0Zkyxs}^c#M+J{Z;|K6LjNLt!&FCru*XB!kLU#6hi5Ko1miIp%W7_au5 z-z5xy+&)WpcgEkJ{t~;rQh*WnCWVYaODV2B^C(vl6E*HTV#(Mw?%gzaKK$ z1YnHn3~E*DfF((5PnSca?KgOKe$8vTz+}fu!nOMOLxWf%2i7Rn=ptt)03Sj-1wNE81(j#JT)eYZ+B6;5@3QM=o@^#pf`9E;Y{Ex=6DBcN9UdJ=IGsRBxpO=_Wd*+2P2DlRI1g9W7!Azn--NXIVJi>9m+%NV}{(IolzR>!OfSF z^nN9-0$ZQ&Q0`Y10U>0LdtfP4urlXZ9EUGi*8`$5Yh4}KVPaFfngl1uF_oFP&S zARq8)DZa9_Jqhn5)&V3dsc4m-3$)O|`$k{-;t%xm_+&84qg_1D2yysxtjG)AZ8g-& z#7Snq>djnmGo$HF);AioCt8AazX+UP;+aN@18&Voois<1#!xh~+-0fvB z^*uso;tCs|pM0*~g}U~OJO*$2B1sp4>7p&iV0P{nuucS26YRcP<``y!{}S-dN+a7! z3;qNVnghoS!O>&s@v`0LRv5JzrJ5szb=3lkR+>{np%>@d^Dy2JtKKlxJ z4I{#WJM_uCSgm5YTQg`z^|pvPD-jJ46SYkQN#`J8NYGwUn8i|^6?7}*6o3ED`h`DNm_Km5eEu>Y{=3}t)oEyK(iI! zh3&w4pcqc2A)r(IUS<3j>x}Umuws~EU$wZt)-hIbDC)eUFd35$c8ws!9kcc3%&Xz>{kg7E;lG3HcrbBzW!YI8#;T z=Gcf)PV<~9XE&Lo4<+;C{it#v?mRhtVmr*L%|wd0=GG+!-yj zyR(>QP|_MxjOr|GW8*&qp#Bw&XY?~n_*5R&pUjt@GsP5T1*;SdD4|v^P%lM(A5f&` zxE$uucnpaz*4nnjG=RIS4g8LzFW{{Dk9hgSB(KjHM^BkL#Si$U0V!$HS^dsH%2c`D zt2;8ofKEzOwk*F_2%~uw+gmX7QVJO zp`go=qW#J4q5*t454wj>|H62|(3a%3EqqSPfH*g&k<2qvYgUG;;C!!+o>96@J6zEZ?v6}Oy zThoIyhgM@5k#P&~XFA^~I&9=X7F0$PZsp7Q3G=`vf?RYek)(pX;)Jw+v>T{a)7`wF z;PkJb96A@(-7tb@S7k3xd;J*H0dxv5I2(aV^Rt4E*4gAoy0WP~NmVl3qLwaqBEdgW zv(Y>Eti+^r<<*2EVc{LJbqfqiP5%T(wHobO*GSMHk=+3>ADwydIX{>w!G!5@6u3&7 z3M?Ew7^;AM_;uKG%_g7e{_%G7_#a`H%uQ6ndV(!f7w^1S@lq;gdI{csG*S9U@ruv5 zz3%xj#3nlAuXjOsjg|6Q=97;BFlU6c@XMmrw-?xNmSjRlMU+)FHw`g^@;<>)jDnYV zX=d24riFm`i6EPzgLznK_1lDmhuYaDO(^bG1?N0ix2DLrGlOJQkJ-2l`zbv`>gl|G z2URbh1SMe@SwuTH63nLcAYb|E_1X3c_~A(PiFv+ZIlMs%THE4oA{$VDCm-Xg%;W^>U%`u<=m$;ky&FJcN~tSnZL zfGm63F<$)msecrD$24LTLFQoW4@0#Fw@S{?(cwjMLnCx#X2D3-8;NSARf}&E+)-AS zJ9BSaK3Wt>f(uT@D+rYLFy@H)ROMay?_euZHt{Txth!T*_A-pKefk5#mMhjdch5Qs zRa_v-Zd1)hvhQ5PUe8l+{So26=<9w3Ou@yHX*&zsTPD;KXH=ezD8tL=G(*+T_j&x+ zxlD6?=fKFmMkOrsj=tY&k%4+dkoVSt$w#$$@7nvzXz+dafi$2N>3Tb1C#P5_hd)`CtPg z+HKY%E{9G;1V8+mB3CVb;pD79p1c>-)EC{`y`QvhACTz5P`bc2;-3jO{M*`2(GjPd zHIqJfn+I<~z;YH}zFTaaCx+^KZV&{@-IAv#JJdIp#Z0EVE#t{Ns2Z>?Djv4xJ>tN$ zFFc)ZQS4lkvXw7I%F)QReZ=m6gV%~6hVg_wtS zbx9yGN}d%zrN@#J0$U-stUSgZkc;h4es;}DC$ssP3)@_cMZ4oqsZ#h@wQ`E)Ahoxf zEhG5LymbD#fat(;Ml$oTf_n^zK2ejYlO+D>>b#+(+9?Wi2AySDk>^AXOJL+8r z-fN~_((*5h#>$NUFq>~#VT+eu*{wS3`W5x2jeh4XJuTo_*z>GjqYN?%3BA~v z!BUyhD`Ru9Vv;jr3Iq$l<@iH5u{@29TU@6?eT|#bLPbCdcAQo!#G>@FlPR< zO5uQ2k!X*z!C;mVbP_y3yTWQs6eS~81(~G6MhCsS67^U1#+ID?pN6Zt@KwX@5%6j| z{#bgCw2A3%`>{A3c^x4efp!gHao3>PLChDgwr~%6w4y1=iBL-H6QlA*=h-3>h&=3{ z6e+&G_-6cAmlIagB4b*h!fkRI?=-*pc$G5h{w<06rz$?kqbwHac9Pja5~_B&+fw5> zYF|W2X-Jt&9K%$(6O&k@fM*|Cb=cu)2rVviGeKa1{#eKK_n_!$65F+p92euTeGkBD zQOx|iMcelh>F1w;tMfqqk65On%?(S%fCN1B4S7;dA$?$~!gRKt{cj8S)n=khl*4yh z;&SBR>Feag3Wt&f}fb{*2%7B4$uE+2PlmDAxy4#Dc=;q9mluK)IFLD%5)A z6aTAX67xy-FKtPKk8dA;#8_2rrqt<&Wbfvh2s?Ht$sB@+d%Elv+EK6cjMHuuSH2{% zOFutY;_ONq2#5>UVI!%T2v7D5R(YqBPb=<-Ue0d)R-**!xE8dVZEmQhc0K)Or1Nq>Ow%;l67OEpmrR+?1e@YQe z(mCSt98%h9b9_ucwdQCMk{yybsr~*f*|p}e{Ztt8pI1FZB9+NiPw6fu@;t0jM|#_l z4(R~0ke!^H5pM1ob9A`p%0N>~B$b<$K5}8huc&{4OdB$0mc0_I?3sq(H76!(L$3bZ zD?ch2$LtcDxC7$Nw z{J;3pSpQ#N8UY+19~`5SvxBLdiJ3DowWF!|f7x1kW(GDU24=3*duC8_78WKZ4rV4M zZgx&4RyrmYDkdf>8aPII2U9U4S2JR2F&-AC|KE{RX%A$>Tn_ zyE{qrLz4G9Y3l=KK0R?Q7ql*2my^9i^_EMqba3Jg8`9}rj_lL$Pd?N)A81+D9_9&m zqJ=P!Z{s1BVYV=Gwnn-oS&YO1#t4pEcAR=IGzO?YM}qk_Lf@PoL(pluzHRcNJ{S)e zf|M_3JhW^D^F~C2!D^MxRi{4TI%P@97!X#BzI>W`>f_z?@7@7rQ=Kf=)>HZ9?gC}k z3M@?0)2%kVFF?Sf*%355?lR+)TH2-aChxpL=-H_wK+l?&u01==iMPSrLebiXZ3XzxcTxFu~sYNpdV621C?3( zSwL#1!4s_IvMwz0G%wcVpjp1MG&Crp_FgOi9km8ixDmd(_i3~+(fHHYPlJu=v>1YX zH|i|gAF-^_h4xNC-Ny^Oy)m)d+un+<{G%D)KbFPyXwqe2tm-{7LG2q|3riM74S>z}zS2 zq3&(ucL@dDf}|VIN&e{2gZ8O)!C%h7nljfZykgggc8}=%%jNk)-npc_wvU|BAgthv z?Z7c@x4O;3@Tx)a-EOV}=8>BD_u4AH0{Dn0l;r{guMJn-6k!zJw z+Qhg!pJ#xw^=9ktIn`$f5uUSKhhHaA_2ok?zy9`_Dw~!6eC^@)ii+B3Clykc#p}2a z=n{R<@qWv91FuGdFCqpXXX?#c9vXy?;$37TdJD6h^KV7vPm_rTZlHbr@=^Dyk=R>G z4hD0hI8=qvKrbIt&E7C>4Qxx-BuAdl{%$m4l}3T7LNTmt#u4T+h{j1suFpG~IQt!X zS7tw)*Mi+|V?rx9G_s}<_Mv14pSbgkR4equk#*l-h)HxQT!Eo9qd5Y$OcLn}qJNNC z9Jq2`8Ew9^2aI0`aH`#bme?vf(=?={D160Raqyat8}$f6Qg#z9Dlq|t&|lR>=>6pn*2Lh} z4)Vt9$DSH)G04B7OZCpsOGJXyh~2LSwjlgBPiIPw?DkQAo=ErhLuN!DS95zLb)EV% zEP$0KIX zbx)u7T*VX}L+bgT5gTXe4tq_QE4XSl?xB%Is+=4Lm)uvTq$O=IM;!L3SVnLu2M@~3 zml1h_ak(z~^ltug3^IQM<(@a=03xga=69$&?+VZ2PgJUsybI2E59FIec(3(=oxX*N z*@@2qDjIjG>L8!iAc?Y@gE-`>9!nXe&XZs8B!C9Jla>+Fg0JT?MgT~t-_48H6^a-7f)^1f2XXD z~gG{mC%BsG9$yn-&6ur;YvaH%=v@_4z1X*cR7%COHa5#FH z)ed*24NUCo1yT;XZCYKuM~W!u^Nn~4?%hMj_*+^Rd*DJ@mtVuuV@#(uh@9Am&C#*F zhL0aFx%0X8F|{A>oi6#%tOAtO9i}Nj?1T&RU%AK&5Qq#bep( z*gt6VCe61yJw4m>=Y@bw^q_LFk~C%SEg`sOXmaDGOGbUSs_>#!!=mh@6!M1WB$^6) zVk2UC-xtT!In;A+RJI8hCK_&6U+I|BY{eG$(k00@U;*UPd}yd29FdhBCh7V;av?LY zm9R_V8i3fQRv2B%yLR+(NcA*tYO8{^EiH(V{ch-)F1Lmr?XH8a?5`OZC{n{o|ZqsS5Z zLMsuF3hgUl9`iO;z`P8Epjv`!l;~3AxL>GyI`r04|e`4_g%q2B=Ys`IZP_^xfuZK&4wEN+H?r_4%>#v>YRoiv-Deo*M z4kh)0Uo82h=V!Q`%1Xah93gJyehKfqOUG4@Z;aPpt}vFY73V!KXA&d*S_zP4)s_CR zSOR3_emf80nepgPkbS(WMRm_y@$&-lQ0v~qrOHm|83h*%-~JOc4^M(H=l!9QhIcy5 z_79t@lE_zWZZfM_@uY0D=)mF9XMSoZj(e}wESvWH^GRn>o+sK-j*hmY)z*GLOoE%My9$ZYH+kET3y#vT}wmTMB5mxhSorv znyQ;<7@-ZI|9|9U3(vn83)g`D7h})8(6cpm5XzwU*qfSiknsE+^`}zFqg;^5;Z<(8 z1xEyjqD0n3-*u>xWJ=jWIfC1~_Lt7f(&MeIq!Z(^dQhj`Tsk``dbCTX+PRR1gC?iGx xC>!}`yQUub<8$;Z_{!pL!Pa*95$ow3@iV2#daRPXaCNx4rVjAjIWs#n@IU{Q*jQ$VawL zD5kWEZ?p`6kO~xOZZp7aK1w;vZTRUP$f93s(xq(6G}7& zV=5(`BTbz!{VOZW5IC}imfAhTr1E!MfVW?MxK&8c3cIF3k@KhZZQ^PwuN#w2wNx$L ztOe-NTP_wkAqN*gg|&9Y^1=S|*m_mL*bu1nSNhwzW8ey4kygOg z8%&mtAwt6BtAP?Iqm`k?iDsAz)o_>!#pWQ3a|-%gR$t(w{NzPuSmx%_xJ{96D+ZML zMXeF*Da=I@8SNnmbm)?6FTP_p9@3k@+n5h|Lp$KPYm#2f* zFGPdrIQ;|>y4}r!ewd}^n*L!W<>ItwDWzt@C`zYDD^x)rjQi$@=)jVb$q9u;6nzd; zZ_1?MtAsvhfyzr?P4?$!U^tvh#sC_OAiV}5e{jt^_x1-xsDy&v6a`z5_a}Dy;^sfw zAE8_KLf=Q=8Zs`?esb%<$xx?9;mdJ&VI_;a-ad{@loDfzXGcaTiJ}Fcbx?yG|NF6< zl98>IDTnHDVT*T>kyX$V!%8cda46dc z;>)T=1qs6JE06z8asdWltQE&*93ve+(;6{OM`76JaP*da&ZH8t;lfP;nBX71eSX6WPKA9+*yZ_q~%Lb z4P!QUgMDOaDEM*;=UdyK4JT&44gM=p0h53oJ(i;$(Cq5Kg2g!Zy`_!`6am7yN42@14^+k z-?!b04qW}2aXQ&sDW{>mi>d@XP8Ia;K)g*4LT=889Mo`U$Iol^MOx&UHeU?(C|34<^9j`j$+$vEtDX*`ov}DMm0n(AhoByz2q$xcMG zsGum1+)bJaiQ#v`N9hYM+w$e4YY$n#$M|`2%&%07EluO@n&#~Scq=AZcNek_up$tG zB+r(LU&F}IBwF%X5|wTW`>DV?tQP)Oowf|Pj(`sH_bGnCO;ig{oVX&B1h`#bDU{X0+5b1D$aSM;|rd@^b~Bq6)ZY{%O7PovYvE z)kePog@HiGXL*chd09TpZ}eHCd&WEA2GIV|1-4jSw82Ix1pThX4rJeytPPd?CC~Ts ztL>|K1e{}5XxMdS=H+RB8<|vVz_jU0q*S)A!Bs)RYCBWkmIs;rx%{qdn|EmZQih4K#n@6jV66eNbtFtOgbZFFe_KsVhrA?7bXde%W*9+oSXIP^CYwIN)bcBcu z((nlsG^l|4%9p9ckcZtednX+Q9AI%E+2Q`gl|&-hO%WVD{H9fJ&(=7}}T%yYl4C3r_ z)rq_e0_4GNTr&*Y@4iT@njP^QEQK}<)wmM}`rNP($P&zsThYm~WI(AF{OO&{FPfEg zkCcnQY2PDr(0-I4y1^%5R3A;^>Ofqy1OmEDj%d5V^^1RJ@2wpETCH&?@B_Y@RsFMX zY8yl8?%ARsXE{~qY9dVca3Zbh0saZmp_>rS%%&^jUa6;ONeRbhi7EIspHK1(B zaOMtXu5K>o#`gcGax}4lV`c|10sa&Jn`vTWX8#}4G=-z@c))Sb-_sw*QhOX>Sg4hc z+%aU&ID~m+?Ai;uB{15&50gS(L&oV2^tI$#EXj}$ynaIRWa7q0I{6TNa~sfP{=CCX zOUxkCCztM@U%LMDurPCHgDkmIWnxjO&CfGU!rARi|y3!OBCt^@f`)b~H`kTbnUZrs2(1m)d^El8}Bu}I6)-h92 zeHz)R|Ks!W-;f&z0sV$jI@wAcmNL6{vLs@X(1=%cF)0w*KtyyToZ#(cB3TKg}#QL>dI7iX?<*Rn~`*h zTv@>Wh}H;bGg(yCsdFjFnZ?F?e@wh1l{qbx6~I)!eTLQB`kJ-UIK^>s#D+o2lxGRiI}s z@^AcYIQQ3I5tl5FI8TF+%On=lL3k2n0jvlw3jksL!ej;HfsexzC5uBg6ZOUtof^j#xaysZ1ZUcH(jgZ8&#A!R%e4?re7iGct08A2mxa2sVVbwdS^YVPJ~=^CiQP%fa!Kb{dttQ>RO15MyX5wvBb0gcC9JJ> zIXJ;&I2errw0nq^kP5m_Mo${XtCTTmNMyYYk%^>&&pryEDFIC;QctaRIKtjy9CU{E zft0Gmmz8T-Y6NV7+0bkGk$eIuR3b{%@+c&cEZGEZr}S}45=kX37IsI(qmS}txz{GZ z_Vgw;aqV(n%mi@xZPZN^%^rm{_eL7rA!KN2<%ij2=t@wK1p^y<7k>~aImG4O`c=(9 zEH*uIj(F|AEY4bCgmQC$5F+iqvS&m5Uu;g^Nxv__;R_(dU9|5B*Q*G zTIyRm!$6D;>PyonMKdQ$4qXNz4VkJ@7hT?7WEw|VD5~wK+yVo1OQ*u9eJ$Yng{`5j zYOov;ix0}aePNC$Cgx~Ee3BRhf(qm6KyzZ_)Y&zAvpD>qyFKjmP)GH3w~X!)OVddg zKCc23Zs4W?s1R1j$dgLOr_FH}q1-Pctt12OCvZJkXnf-2q?`uS^Q&ikIq!PLb{ z@3Uk52$4@s_@5Kd-|^h0%ES$Nlr04rf$vY8L11inmd8oqCCBKZQ}PwZ;+XS4XFgWb zlISRo z37iZYb82=U_(H6#kez6IHV_MK8F{w)RptV+hzLcV+XXd&9|)vOw6Zsc$l$c0TA-`U zGwZGgB1;3bMC{@#Xoq}Fkhw}*AxY24H<5A9bS^;4yu5pxo%!KASglhpP^c3|S3-gd z-&mbvsgf=Bq2+`SbOcZc%SM8w%ZdDYn)WKb*ai%POkKEGFWD)n#%g9}{GA*G+Fw5;*`I#69hnOD>#Wk zbM3UU-`)5)IJxNC<2N zy^#O~szgJ|B(H*(e6epEg69`VX#Hb|-YcPxrR0R~n`;}-gbz^s<6gz?_Gfl$?6jHm zkHJ;1h$@;Uw&}|5Ibnj{ z=v=yPfN(%4+F_)Wq_%n>>y4g2VQIdQ;CZjW*tj`vs;{50S(>5Vc+2elqNL(}z_2JR z@C=esBZTqx6&Eqlq*#%wZ*a~KqfFeeo3KVmiu>)GnN@;kgmqp)z=At*0SdVpzl7uh z8UkXn5E)br%W6xLPOoElk%1<)W7iN@N`WRhfLV+2n{nS#rj%Gdc93U1U;g&xu3(iP zVv~wpPWP*AR9=hc8*6NdncWmiToa54=(Min+pPW&cm)!00ds5a;N`B8moxfn(~~*H zw;EUO@djGsMH=K{u%sccSnnA;*jOv$_ia#fTAqc;M5_{`f_vXR7=4r3db)WEYWH|2 zsiTj14ys8fR~Z|~Z)WmRV~hz3&DUkM#{kGE3P$5~LTCjb--nb?t$-6ufQ0or@R6Jp zI~SXW3%=;0=V@S^{RXD`>yf2O$exP70^-p@@Mg^A-f(<3jWhNq1utB$U+h&VI1p(q z>-;gZGT@!dZw@|%1~J8Wl4TaQH8e&r zH(^5c!DPxp?b90Z?fOQfY-J)!^Z#Slxc-0a8Y?^N|Jb!F9bLzbVKl#&nq6IL!20#q ze9Ln_^*l+)M(fGnD{%Tb4n=Ym;Z5?PyXNt8WJw~V(?-@=UztBzmlI1mLD8Ql^%WXqJKMiHmUO7)?|-Uch&|^t zhK{N)HEdaR6>41MyHBTF6e|SMIGjRAWP|%f8&nGj;Q_uhVq%pRRq*?~=t6szC_+gXps5&o% z*7Wv5pM#HWoJ(+3`8J2iQZDO&zzPjElSO6>f@pPWIz+o*i1#mo3M^O1fJS8nqXaV^n7kB| ztPkp!)$5eALJvw;F*xQl|0$rm`03ak4*nK(stFMZ%;H|$Bu_z46wv9Cb&LqsUYVTrT#XU+XP{j&K8Ucn43el3*SENNrC|2#~6aOGndiaQe}s+rN} z8JfZ{$YUE)#1ulXFu503(ZilaE-y=Zb5%A>BTCqvnJHM7ksB14ld^ic$2qhji&cd- z0TlL83&Yio4cHQsNta-SNWOJ`Cg#!g1Qt6wa(2MEROUXJ8oTPc`-1XkY$QSG$yxvz z1zAYvjp;Ddu*wZ7qA?|8kV4>aci!J!3o_wSSf$F9oQoU3gF|GDtP~!5>XkxjA3%2W z{vyCW#4DA^Ec3)q#yVNGm)B&jyH+PgcrC3vGtDKMk|hhM?;D}9WUg&*q1>ZsBT`58 zu`wnt^(JLG4c?5m+f__?c98Hmerp09vgIr3h1}_nIe0TZWkd^dX8sCBrwD^&h@;_A zz*!i8z`=x=yU(H$gaw${iHXcsXnR1(v$=9tD5T`b@s1$5+rmrNXJ>A!8riNtER53U3>vpodgJsT&lK{e#7Y`! z3rXy6hUW)N)+s6Whs)2_Ilcpl&C%jZN-tcCKM_nzjHBUs4+QqYKzkXa|Bf&p<4+bu zB;B5g8C0@OUv&u%G7xir*g#qkH)MIVIJ@ie26;Twb}Bo5y<23Pg5|`d2thd9+0uT5 ziuX@5`u|iq{sc?ATu2M5eZ}m2T$`9%bt^Pg-E{j!`AebJxSQr#Z>s}82CCcJUwGXY zury{gi>gS$Q9{`EkWE=g`al4xnZI+b_sH#ct?c*GjDjl|Hu^{M^|28!r1k<1Q2Om} zczk8uORqQQ8Jw=O;!o5_A@5k=AKI;70LP5BWGj<5Q5W-q3Klm8Z^fOe@}UT-<8=sqf$w9Nt&%AAzl4ys%b}W z4-zdp4m=MeUT9_Ws=d@Mw?DN;N}#v%dm-&*?X@kA%}3M2;Q!u+Vz7$t?XAZy#z%TH zMd+|PhT-FhCp*InUld9I)Q(a`jb<5c4=jQat}rzJ@|63+dM(d}kI znuF>*yW<+B8UA?OCfxWqWi{rn0;JKBHpIXh60n8sW}#D-{gV&X1sC#VN8@q#&brS9 zh(!YXvT>%XmbbJnQd;Rr!g#^y(&3 zGQ)e3GV25X#l2|2MyL4mkrr59?+=aN-t8AR56B$-7#I;NX-D&=xX*Us^_C3f7#S-n z%5Uoh0uo!47Kl6TcSP6^|1`WPhLpIR7yHMN^byARpfm-BmAcn&z$sara+JpMZkHyC zipGpl6T?ySi2QLjA2@`A^E%0R4r;DpNM0$BGo$mEOoha?;{0=^SXSeRK< zWXVO$Y;fwvEP+wPA$H^e_KA}wD;Do9s?JN;e27T!!veSH5*KPPluE;{+6Yf3#AQDh zY%v824)VDqMf_<=-t3kZ^Fu`8L&Y86ULz20BsT`>wrjm6Y>+&h5gL(GV|6fYvo$#X z>(jB0a1sZt@6Xe1+SO`oaMqd`q@Lx|42it@N6hkf>`fhIWMf;T-_9}-lj@hG5qGRw ze5o3P0`7j=agXpDsGxjz5TrxPsPzwQIv}kD_j()VpTMtJ>r448G8X3|_BmL8lP=-T zIi1ys)WYxu`;*FGUs79jf;ezkowc6R2KH4j{6BakG1kumv`J?Lg;$Yd_4t;`iCrAA4^b+w8~`H z>!SNx3BPIXJg)cmdSQ=WF*&dE`4icAaqj4d#&U z7R%aY(vCIIsiMh1v?#8TIg5`adW_xM4Rv$Rjg_`T7{<~ zAdVfvU)F|sCcE^{=dZ}I)1Pzb86luO$1v^nI2L|Rwx?a)l~+XYJ3BD7O76RH}1(tpnS9Pj;n(9V>k(B($_KTdYFc4rR#7dC( ze6G(I%CnMo$gd7u7+A0lM5JP`q4|*9paz#_-lpoT*+Az<&~m+Vg*mpX?UiPt*fBaX z%Ar}^)l??C6ni2pE_45ZbbM-F1}C_{k~ItzjL@Q>(Qb)E#%h}Utt$Q2QS3xZuV7E@ zR!Q`tCG6YF4^bfmj9$ctG-x2-jg=W9LU5WfM?tzZ$F1$GUdRyvMvU)nsDZ% zP2b5f-gXiM=6@p5MhTFZ2TJJ!8r|ieE|K;m%{QV9>fd0 z4dDXwlZHAC?i&*Z?&AspENG7~7oY`#ag5*;*e(jr!bA!j$9t^-AeeGVbq z1EahRFoXe#xD9|P`bK{}i9~^c;1cPR@&_Npfg}C&aBIZbe_X-U2SO|o8IcD&2m*vo zR~~8@@!Z0=`;D(bfByY2)a94I`MR?EZVM*IQ=;7;PdLAh&!5a6&E%h^pC50@bAjvY9_Q*Fm>*=Md;fOmPvd;Nb?68} zBmyokF{2-O_MlJpIUW?r(zp>|k&YA!&`T=WX!`nxN2;`iXOU>X6j?k_|NFeC=fWT9 z1}Q}Nac_Ip&;!Yzh>Gmd5Zmjr*WuKA2v5Ii2L*y({YS103VeV77?W3<&IJ-IYGl>RIV=1cezS0;AB&3=1+Z)Wa*{nK@56{d#SoINGjv z%rJL-C`v`q7Z8-bV`;r`Ar$~9q_9YQjHPlewklxkFdG&;uV>zwY!KnO=|SkP^Rr}c zp9A!=3vv8Z+e;SN2Bms?9V=Ub1a3!|X1Ld(TcK;Nd0n#;l8I_P>GzY4N&`LCrT1SK z>2LHwS3GynVreO?pVAZ&%X>!+m*PmCu8ox~@t@JJd>E47EtZN3J1Q8RZN}X{;b}~N z1f`1+%-blkeFU&tRqW|5w`4uyrV~?9KZ5t4*q~+JT#vta;Y%aymlCyssb-Wjc!-b{ zss~QRS&9rL*fE540wAyM{WAF)o@(5thByq#0>by}7_q=&VswN1r5dBS?_wSCkvmXA z@ZShwO(D#YQ!SZ;rWmuHvhs3;`lN@VsLYPR;Y&)|kE#)32?cz()<{HKBzQ;ifgdO? zh4W*!J5hcN|8=oiXfMpbMyaJI2Bix;$k#X}yS)88!}%sdmYs4EIbN#UQ%IEKp}wf)TA6+L z2mJ^~Lx+A3WSM5z+;Sbn&2MIeP+nWXKiM~(Dojx)J$rOGhhF&-vAnuWd_c7mQc zLyj9!fpz6`bTS)%yazG#GuoIXaksYn;;a4Z2RGNg8^>zXZ#-#85^EA_@8?AjOasn3 z!VURK5dpVk@OZQKdOk#hUqhy)(&@?dZ{nZ3)S_Fz2%|m|^|F4~1BK1%iNvDa>@(i2W>73^3 z>+FwM;DAju@_#)-PMTfLdeLL4%v5#PCh#5K*T4rMp+t~>#Xd?wf0V1J z)NlB6paQJbii}CXa58J2`tjVj^zuEpAL@K35B(gd7jgzI@a<6--xoIag{ zE4D$AjaIPe4x@+P@#cbfIBP6NF&7zTd&;^vaK77Hpevw96)3OjRPyq+74gJBZ7{^e zv&;0PqJ)GFmT!)1<8z2w? zMg12zI!fK0q80L0iB5@7NXwOBs&lMLip*&DhSSHp+-LAI6|0tER<9ozl|^+-vYz)I z@S5}}Tk{PXR6#29f_cW<1TiCV)rDjM1n(At?_N7gaXXN@RPtT)?42jom^tc_y&&WL zM-jYJaMoheMtQTTC%{$USrI)9GFq7h7^){Hl`ek09zZ{<RR0*tr6f;bJ4^Wu49U1& z9u^mMwYV9vs+sHl8p}-;4$Fks8XHy_$?q^rp{Ue{(4jX(_8IH27YECFi48rh*|@E6 zfHm`*nua9hzGP7ky*_e0v|cM^ut3&ScllK!#-I7=QeKW~>t;Kr-q!{ zdO20n@Q%_+s!L?q3Sgi7!#n5Xi%Z6O|AD!^boNy9@(PDTy0IJ!81u}saj)Z@ zBfmjDpgUbf*CtLQF*_3lzUEX?hI+z#cikv3@08H*FDH>yl(HW}YO4gwAfJbDEpT$s z6sDjadBLsdgC(djVyJ7d)P{CO!?`Y&s!RY2(HWeZ9)X~T5?-*6X1HZKl%HI%qg~tD zSSHiVXchn#r<@jpn5z5)tlbdaVJa_@i+T0A7)%QjfQ$C$yN0x{Riz(Oobln?zD zdrRiN7}mL$3eK8$>Qt}Oa2 z+8ktn@4yv7TSb)6=W^JK=+R8DbZ=W!HWslmu#`^cT3^P1VakKezi55A*6r+*iKKh~ ziA;DSUg+GV_FyrrGbHs$N@o8?)tHS%|o`YO)wV zVZF)2WlFbu800TYAT`(NpTdVW)u*m)7EBomK(q08Hv|KLH&DWF!p%6+Y3Ru8BM^uf zgq;QL@?t*V?6?ulVW}Ivu(H zs#$>Y%pw~ce{m>Frd1@YTK9-*mPYYnr^M(o!?QZJcz0Nf(HgihF;#E1uIiPX|2EqJ0wdX3+YieK$ zjJ}UZbTCj`K#=*LwWIC4J#nw5Y=vAdDa(^jVms&A-4*W-Mc?}$V+lL7uVaFy)#J56 z+_FXPOepYz7&D4UBY{4XU+oEe?7|H~m%R zY=JL{Cf=(`Bdh5hV1Icp3nzCzzadvaGq7a(Y;cbSQpuniq=bE36iZee!6ce=y<2KiwD?qNp8g# zo^g!eRq%stXs+hlxw8V8fEcxEb32&Nse1M(ks1`!wO; zUEuuA6Y(2iD-guUtBm_D^zVd4qZ=-2ttlpE{|z7_qi1F zQ+LSL(b=pc1e*sdndwpW5U&qPMESb1!^=n;A~C6eIs|U}Y1@9T_`b=abHNGgPK4-#!>KVSAzTsv=9-_P$+ng-wm-2O|B|Dpn zMd)vW(}`|uqN5Q~pf7^w-2s((k_rOU;gj~Ikh{nkyYX9V+uTD)P`OkIIrQj0;*!9L z2%DbIprnQvA-i`tw2jkI+XR~8<-_n1eaMX?tRA=sXRvK|We2j&d#VxKmcjElSg;Py zu+-bgY^tAnkWaHC#&S(zP;CCDT(te|v8&P&pFIosc`MixYBVqkhcFR~jGF^msSPPA*ZcJ!9~$N#*ds@__ndsE8H$B z%nqxCFYM7KZkv$g^}lotFpyQpZg>^9&~jk;SG8${a~df8`sarPhjrV2jZnLM6d;JSB2E%Scts7ORserq*LSo$2FpeCByaCZK?#d)WPW z5))}^iIj|rZW4VYJ^adTaHZbXY3+6=IQj$U-)id&DBISY4vUPysD~Vg_B?nW=7z?m zVz2pwkxS;G6^UTTZ(f1=-tc^$HQ4@ZnyxVl&LfP@g6;HU^HN^1*5y*fWNo_1b)2uL zXOts?t}z?ak&?*Wt3whm9qSagj*6~2eKN+Ni(aYZ^Ilmi4R91=XDJ0oWm_ZxEaxz@ zUgS6mo=)ZY1ky-9>&Z5tl${A7!j236tj3kX-uG(ES+8$}AW^`GpT(8<4HQvLZuGV> z7WJB|Q0N(fV&}sTsVlu*xj#p8<>N9ykj6#w_!?VYH`s7D!ku7=0L~icwVk&OHG00} zzOt$_yg>?q_Jt-$9;+!1gm7wrr{kM~7lU>0m$J)Cnf)ub9dUegvbi3LvvuMtg6;KM z0o6-<)OHjb0UwZHqz|^f`KodD!gHTL|5Umm|7~ahYdhadhj>{O|8IHMd1?YW%>I~{ zZKgL%bN%(ztB6>D+4iGM*H8(Hn7>+}Y=3+|!>T#8VA7E#25Wl!IM|7*NuvRY_R2@z zu1aLmkx|XYmPsq5cE)m*AZyz?__3CiN_Fms8i>S-QwN2^gqhA9r4>Zxth1V#O9p7QtEy7JH&o2O-ScYFIvuev)2 zW9vWJ53N9ME|cb0@KH zwVpftOnPs@2}MVZC0u~1uYXu$tU87ei5`c z*+Qki7i&ivLgrJEp7F!XBFtqH=F)QY&)K+}6e}U<`PoX<>buk0p9;*=hYvxUiJ0g4gYuY^<|V`^(vlnNt_Xj+ z!I=pwFXsvej6z+{H5^WV?7DTustq7(70if);Wy$lG{!e6YZ@Jgo6N8z=!sPO*|p%h zD|UBqiK;m+>)PP)7HLk613yKx@U?$sSPolGaKKD66Txk(ye;(G+0RhEpNS$7W(B%> z;CAI;%niO%FdR_Sxgc4ebhGj^tEK6__E1Yenu5i7cuWSEfS z>)#q0KTT?`rFTPf%uGpKoxouwDVDj&XKEwDs1UQmOo5!~(UW}ygg_!sJDndV3A`j| zMrzfQF^vNiml+gajhaD7)EU#tVt}`_zjU@BUf6ss)W$0n4P#gHw3aEL!#qj@%s9>? z%u%Bxnz@Px*#P<|cBwf+6o%wdHV(QAI=VwINy{f@E$IVNpg-4Ne_9c*_*L|^0>(QfQA#*Y zDD53;AQYnMFRK+RcKQzACOn1^cv791uVjN?D<6XRO(GUTq96ZRg_U_lDX(egz<1EfX6mW#+Pff;| zD2^+v5*~?AIZTLXgy*<8oeWcIW}4=Oi={qA^BmLPH#5GK%zwqR|H{p*wtoI;`38OK z(=|MV-t7K7Z~ik@E(L_6_|Y)O8q-E^P+Hm7x-1X2DtT_2POD_+0mShsww6moX{A$S zydjL#zD!6q`qli2ovDwUe;?sAKlR}3YO_gPeN0Jf2W4>LC-eUNN{$5$1l7s2j#iyl z2R)lOxXEz7AtjY|-~!<3Zp&@E+x#8SCCOjG;Zv-B@^JN8@C1%;+T9K*Fsm^Rwj^Pc zf3=7&E8VOa$}N@oR#*jOZa@CoZbj;;Dz&9mTw#nbn}2HY@{)NpKj*&mrfU1{=LL{v z;cO>6YR4uX+Qj`yFx@>!^IV4>k%|$8X8xMs6BG#Otj6FtiPcq~i&#-TpO@_lTa_%- zoEJzQ|0jqci~#h~#pyQ>P&B6V6?@Jlm>%}ar;0I;xOl|mMhna7)xTLQo3EaigC8m{ zUN*8T_>;W&_rBn@tFCg*MLYHNFlafZ3AN2Fqe)7q2*qi;ICuUy^6kI)j@Y$*5OHaw zntlJ9+XaEs@U0But(+M*y%Zl&S1Dvdee}&H^i*>|_czeRomIC6)+$NMX~h}-yebB} zd+_}FdouU@62-}?-e({{6C+$#D(+G`64}#i!-u(ZR!Kws?-6;O>M@LG%iH{Cl2nfK zltwyJp_`27{9cnr+ZuCHVF6ZxZaB}$miwkpMBD=P7J^$q?ZUS5vFecG(^;vSL2dtH z#wDc0(*m&KxJ+bffwZHO&D8y)IHq7xIJ5IMQ}I7skUdoYuuxM&0efR2>s=5@Xgd$1 z1uvkEVGO<(_p~LI=fu{u){sp-D#gslu4aATRM$)nuIrsF<3`bcPtj+Sd=T^ZO5sH! zf#5hfK0ck2`q5X_R--GMu_nlIti6t(<x-umLKze-9bo^3LUIKq{_r=nrl%K5N$xl$+k1m$=ZEOs zJSYBtgMR-P^JDw}EF3ZenAuqVAK=FVVCUlE`d|3(|0RJ?RsaqzcIN*_IYnq(7$luDk(@R#idkTFg|tJ z-ZyPOJ?kRJ^TFa1rQGQT}HBH^!)!(QGvxid`rUlaZBPO(Ua1gpPf;I0iA~;^O=y~z&QPL zVX{eQA!0*J`F5Fh6~~3Z!)ZT}*-=3lXD3kuzOIq;r09qT31EXv z{e#biRPFimiE(2;5tly@TR}fvxrJ(BUJcK_#eU?1g}&iJg$k%N*&xnhgm^%%P#K)^ z3qo^Yrr|xnVTAkrfMCQ7S{THH`=G+DLYFZ9hLT|*?8z|!C}0DEpS4N|U@-%cMyL#e z+>zgMqOBJ0WOA5C=Wvqywf=c0s-i}_O8s5lQQy|ptY}9Ok8j?VaYFr3K8V+rDbQGOng8|!BV}d5_8f#-u@;pdEkRiwfoz{?=${L6ySpbr5(NRz z5V%f)!Ti~`;J1Aue7i#U!vxnS4|%b`YY-zQlu-YD|KCo~5NNkImk_L*-!HkdK!kpH zD@c-2WCVz>&re%(c_nOw5VyN;&QHxKarG(pMuf%SZ>8@vRdL88$Vb#)Sm1C`(t-X) z@xg4j6vlfmz!|=u_JE$XpL$$j6rjQj5l&OWGu7@4nxHmH^^GG1A+Wgb$I=19|A)@l zp9BUM>F}rJ`zC-)Sg9ZD^@k6#N8}s0|C4b9T>1g#Neyfb9i`>{aPI!xiRz&;Yy(js zggXvk1`6UxqG9fP3Q})((5sNch&T0rHY#F*P(sCkIA=mA?MzxC5M*~7vAs5c&Rr%_ z2&D5@T{)mfkkSBTKrmiGZFn9sp$G=dqoF|mrEm@`G8SEdWsg1zoiU1Y&-#ZeGG+9- z;7mbmaG{Z)rHY&i988}PU>hWm42D-aA32?=lc{xuaSB{qJe~@l7(#0I61q{+7(@_{ zo*EH|A&%Z26!_H${+)n#9@~c!`GW>oaJ%ziIDj1H-B;j028*G_v06sa`cx~Ev8DRQ zTq@R%_UX1c{Z^^ZS4OYpJ$%Zf(^}&=`I{pL7P`M|(9i zvreIV;wOxmB(vr6<|g%|wn%iNu}1Nxle8|U_lOh1TUf8HAEk7oRyIvGv)E=41BzsqI* z8ERmeOk=FxHXx5*>^YBRuALy`G+;CU6BXR;*j1@A+b}oLoU#n`vWLMFbd3F^8^2W< z#rJZ2i8=?hw-t1=;C7OA{|~m#sXY^5U9fS|v2EM7?R0G0<`>(xZQHhObjP+cz0b^? zb1`#Qzo4FaYt>q1ipm^Hgx#mebCjib`^N)@_PrB6Qw^^s^2J4W`=#blt9kXpRSfMt z~Fr*{s$*QF(n3qwN9G)@QL+l4dnTMDuw zLx%K71`{W+KUCm|SPFmua>2{J%vdnhj7o5Wtk~_gvoZ>qz&Y7N(^7^7bs^PB5eh0J zKZHY>36%Baw-xrBrkjFoJH-$|yr!{#LP>*5vB3KZ#wvRwSl~5bzJ}3?1K{pdcGquZ zqmVIb&G0|}HL{NIAuIum*OcWkbGVP-t#7z7|7CF0Y}s(g*~%%hp$DiO)KjJlTzhf~ zF4Wsj%shppcytia9Ib$uc;mUMgIZ%!AZBaycY&j9**!wMHrYgc4Yk1}h>2ORks4GuSdF zGEHYc!r}$B1&0F4P9+%T{aUN*kS-*Om{;VPWk@79yHVe-_N-U%wH-CHDsK8*q&d!_ z9x>3k3-t8Nc7aOE7H2vo8IJ7dhKsD-oS7S&Yc+AF!3MEw*}%pJN$>Axpe-rLOzmj# zycu=F&iT=^Gvd((`+8&@c{&q;6^>xL|78KVZ#HUx94`P3Nm{^T76cp!XNz|sl!JRQ z1j7?y_UjxR#&wUn_;`m5DM2X)2kNi_5D-G0#4jH2I7ZQ=%b z?g7y@vg6y~5=R@@D*SF{3=rB^6CwhB6Lc>T^EexSU~W!<9`|NDTbA{k9ei$E{PcvF z;vKCzW@!O0A_V7E5$5lwg|LK|RuJ8uFod0QXbX*_6L*Or8y|mUmdN_{w;8w3m#@0> z(XX?Bx9r;Y!9R@q;6qmqL<1@nEtOT07Ph2z)iM7tH@F(fONG8@V+3iPdhpQmv(H)m z(!5o|j6#~BtMaKlkId8uhPz9B;}cTQ5AeNrG)V<0hMR;Jx8MA8-sOJTb;EQmi!}lZ z^ z-faO49y<_79Ej@u{qr}>A+idLRu#ca9QBP(bo`)6p% zr$y$9s7fKlqDr_wA&CXIW~uKE_{{0`(RcwzCwBJZzRR5`Dk~!Ae+O;@7Z?mQMbasP zc!pxnu>WljnltOe@D$ox-j+KR`4u!%8D1OyuKI;O$vTIWw(h-d$JjO zu5f681&WP;erjWE=UM~R=ABI(vW+2m)k5uCSAIB}Z%V=4xcH*=BH|IER7_Z4~1GItl66^DzNMa5b2@i=Bq{ zkLl~C;VYXeq4j|cSHIyGc8=-@dTEe zX!>?fg}FBbn{ehcSu;{<(QNDSwM+nvhGkA`_hhU+d^TJ8zKoH~GA;)s%}Q8g_%3nk z72axZ{hb5@3i#czdb$4X z)M00fuxI!(<}H$xw_Q0Jb@Z`__+#AC+a zz6ZujSz4c{dcZWZAc4{y8)MlOL}Z*!a`?XyXs2t*?X06A-?-Ii@4lZ=Tu9sONYkWO z{JM=m`DY29Uci(E_IxG{y@F(sJ~f!a6TQrZJ*&NUw?cjn5_dz6+u8vq9Xh1i#|^Oh z0(DBR^{JiIF;L8T!iZNU zW!%%`E}z=!HCCJFbEAL}TLnI+xp_(1_%|_Mm??9t58^z`8>pkzMdh`sN$cTT&7-}e zK$wU@Ag5AgPKO?uwdyP9uE!P0!fbTnE4gDsd7OaiE=wL`b_eb!nNrS7VdwHcCmfYg z(n<(QJBcnmdR|ucn<*+JIQZFaIH-=jECpcaV!jj2H+NcSDn|eXKhE&!nvBfxZ1L$~ zUT>aHR&1Fit_^II$2$!$770x;Cs&D`^9n|(4a=jG9vN#PvVd2N37R-2G?Qi=7!uwP z>bdf#a4`~NfeF?M#v5RY1|MKzHYBQxV$QWrtzCSEdS(Na@~7p!_sDL_0uuBu96kzX%0+r6nv|!k z1neeYUwfnt%IbcL<=14{V(sMXM2|v7aXmYz=Jj7z0Q&vGYa;uj&xPOQUvf3onL-)h zUl2D=mH4hRACn-iRK3y*u9R~G(NCM3^le-d;mRobM4bTb56=D1fAWO-tw!Y6ZdeXP z%F0M^1!u>13|f%|K5K-Er=Y}Kr#S_^D3lU&SUKgqCwuD7t1;~BV0XRuK91X!yiBS} zxIX^=E=_joImC$C&%z3;lKLRf##fz?rV*Opu40qCuFNhs3t!ecpa#QNXk59D9d`WZBc6f{FK zS=EHhIv#@Edb4Zts!Jvyb~S)TEM&jylgm1e>c=yg4Vp|~xwqPnl2`(EuxuKZOr+n7 zZbgn^((51U@I9<^Vu!+1mK>U}2*OJ@;=ZnxI*R}U<}6EJ3FjclMzmowW?k3l7KQ35 zhF6C6S!T>=kFy2{_yn)rr%> zodQ7Xf}yFmtgNKacr!1ehd_g$*Dn3{zY5iJP8;u--Gpy$n0IEY8^$w{dI`)Tj_2!1>&JCg6pLDC$y&^nE!|alqGMXF zce4cB6<5vz$_QoYG432JrE@HMt#o9vf$3(o_l9Z9FtxDWGG%A;+KONXX6jscG&F)+ z-2l}?8Aq_=z662jhN$<^W{>NJsQQ+}>k6tuKA@>YtK0 zL4=mx-Al{mA9|KdmuOz!5l}X`b(6I2XIlO)@MP3CM`@}*T24X#hS!x-SIdnkgj}1o zoErlvF6V3e-xECLep69ZFxjfST3bGGW$`f$4e}NvuPEO)mSn%h!w>xw-LC=FQWg9? z6=%2QTu-NLU9eXPk)L$Ae33UjS+u-ZficRC-ebP8n43M;LceuxnKxPjWPnLhcZkUt ze?Vtg;=Rrf5z&+evXMPH3K&OWl+Y~irmu{)4OC1mjktEe-jhTE2EY~UFWw@&Ggvg3 zIM(XSBR7Z%pj~ldUrc?UpQiztWcZ6AZhyMHbZp|=*u>iecaOU}=E1dZy(+HC>GyDc zigEmK``LL6t&AOw6v=~T8_e#%xKIM{6123Q2(@`z zVrXYQZR9ygtVIHo+S=O#WQ+b-(8N3)9$cnjx5AK4hH`zP6|Ap4uXKO1P@EFASkl=s z@i+c9bRliIP6en2?=057vU$2c;T=5SrKQs^ZDGG<ai9>(N6pU&^vi0jW{w|)T3$NCTUuVYv_3;Aa%j)JD(C;j5#YCcs z8Z$WIE|gHg$f8=|}P{LZvx z;^z5PL%(#qk(a_ZT@7!VFF$@pdy%}hs~tzVde-vw%zfADAF;No^XWw^m4=b>r+z%y zc*1oOosDiaCR+-iNWj#*`(w(|B!4hcGGAKLFO0>Ze4NWKVZXD{$pWX@!E?fOBkcF; z{%)7XKC2S5z;c}#VYI0b)lS`(+;z#W<^6CWpQ=0Qp?lkv?-DNXtP+@+P#F+>-4nWT zr7HGxu_qT#0x7kP6E(YL?(BAyBI_LI>sk&z>)vvm(3k{ZdE1f1y<=4WorD5~DY@H7 zKh8<_n)&#t?Xxk~;X32q^T>cQ9*(^<ddJa>*p#N?yRjKdrROGE(RvWc5~* z^Mf($fcV?VZ?Zt^Rgrh5aO!t(X4jz(!dju>Ep%DxP(q z8sORHPUC_t#aU@GgnQ`YS(iDOYS&m!m5Ct6UbS<7^2?=6m@0)Nv`tMoGJ z7m%Unb)Q%wvb+Rip8n4kx7u{$uMf@0>wJ1qyQ6p*DecDfd6(N|dUO8`gIsYLo0=JE z6kMLn$8d2B3a5&yYIb1x4Jh&Y?UYN2?G2iZ zF1%}sK}*i>A(eAZqXWKDL;|;4!$MLr_ZInbQ&dJV%WJ;IV+Pa1rKV9!<F(i@>1Z_hY?X;#tv6I8!`Q9%O3cSSE%SKL9*;jrS;XW_KWWl8ImF_kcOgX#>h zYajTD<0%CFr(!p-4Jl{3=ORL2jG3hlx5&@~u4%UHhT@PVf29@R_zlOgc z&|gFv^bTzT-^NEdTz-oq_L1ctb_c>65=kTL@K|g@&)6$=ssaBl&n+inC4I z}hS?OXWseR}JLVr{qKAJkk+o;0Jb zc-7MXYni@xocVNXA4s?~ZM#v`B8ye5t+nNAEEuceq^wM%jj^ebeJo5ly&}f82aF$U ziYGz0#?rB$EX*AI$%`@MG@Q{$Hxd@R1m*6|TVD>&q&V*n%gQoji5!O@|#QsKgS>q7lC zg1yVo;y2^u49tk?UG3LVAkpP1bACG-(Yhg%Tc6%UbQ3*MU-t{6IdK6He!SugQ*PYK z76r5S_=yrTtC?}E?h*=q!MpZBOjTDgk&Gy|fD&>Gji|yXq>;+}*n=$p;niXLs2q#N zr8j^H7H2w0E~ss^%F**G&?fnBLXR%i2Imr$(o!& zg<+$n>K6+xQ=AhgsLKIVG^*7vCXx%B{c<=f+d9YUJ(;s2cF7nkLP@DsOK1O!$gSXc zjOWpu&;@Y--S;Xr0~Dc&vW>l6*MFkMi4P%%uLXXO=K2ugnq3$B<$zKVelGCGCeK$L z)2+n1+@WcWY++EwXO8w_W5idFkB1khBZtbbSstDYg~#q4ZKW}f6Oy-w{#rOl~IS(YILRx-?#Qu|WwG_FsVZH)Q_PLZFT z)Gc?gtC*L>RVYf!6uD{4a6!FcfUPlIR0@U;!=m7gG4h1^O6!4BfjT?h#@iwMW7rHw zAQnY`8K(Yry~GYMosi^Yd{)M>UF$m0Zt!LG_DmCU=CoKr+UKtjRiQ>WEKTSQf(~1A zcy^#=)+LxTK2qt_d^l)CdU@SCl*0Ma^76&3X+Q%+FT#4i`CP1bz4#!YuX<-}TbEEu z-fQxJjDHF{$64l(t8}xM^=*D4h#bnL{tru||IhM2u{9R<|1V5q`EQYqnUI}{J*~kQ z7!8briJ9}i;F${~Yxd42J5r%2DYp`Sp*UWT7>Cyl878dwC@f16il}b{lyITA9HtPI zQc}56;fp*Xsa5!HuaxH;*Uj5cORxQm*4(A5 z75KMHjNqVueSLX;eLWNvMcFS{(6H|SDXy7(N>lX=lTs95F5fKULpQ9rZ zC`SnxVt^9;efOt70_+hqrqF_7GRN|-S1HW-pmq@e3kvC9Fj*bL)4g`4MXV!GAt7K~ zpfE0BBnzEjjKN=#AP!-mqnX_Py^yGPTbd_rpaQpL>_C!;k9979LI8Onksr7SE?&Yl zK4LHd>;VYp(7vJ|K{ZME-N-E{V(^lJ1Qc$}FknQan~0Hf82IG&;usOA+5}3_0qkd9 zgs0E|AG4Vd8{$Vw>C_xsCuIduo?6n~of0I7{L5276%+bAoTe*p{$_SpgwPie7{ETu z7@YK=fGn?vFI)6YduF$ZoqQQFjGW%r6YGhu- zfI>t>fdCU74gsE5NRT>27y6NXr~~sdt>U`>q)Lb-vto*>*9a%t^sCmd&NI{7$DvQ2Yu7LeV0FR zScmXIA776BQX4QqI54`TcASVmS61*}e3PAu6zORn0BtrV#BC2sBAxvoY7$sDKsDmi? z7cMW7<1e5!C-o9cus9(hKm^x7YMHpb5Bud2sJk-D-!TGs* z?VU&a`cU%x!uaiJAi!bV#@{i4fbaaik2jR>F+SWLMNX3AG-ZdhPw$@#Hh*E?g4kk| zB1wr2hqlPu(4jSH4qvd|$6c($PowW>bwUG>r`e0w%@mW}#%M_Aa^I3av&R=pQC7U( zkxA9&z}77(>V@Ztuons-3RlR{5WUMuu`f%0ms9#GUQ460gQNz9?YJJt04xi1uef~l zpCEMe*0Qu^wjiBKkvuimJr3LTitF(OhR`WfESl2HeagHm*+6bycgYiE3(@Jh?=nobTEyXC|+*tyF5=*;y^o-eS`W!bMp0~OZvGo_Rm>!zw3Z%!XtCK5^Z5;$#$3bA)f^m4;Iu(?^}Wu zRYiAs<|h0|t%8c0J%&sO6-E!Fsh;mmHSbcr{pz2~=VVJ|uiF`LMp?VFPIToZR0riV zuBDA9rG3JC%N;{=*EJ)R_&1plc5reGf_Ymu^^5c~stlLovS1Baz+8#Ab2<5w>$lX6 zNrj5AWUx+u(9Psnbbg4Bp&<>`Ao{0WsodRV|4m$=bY<()?i|7%X3&S?E?gH>(tMZ0 z>#d77Pu_s)?-_oQL<$PsnzOp>4G%k!4QPuM2TU~!@7`cF#g_3nRSHKTpHFWdiGcJ{ zuc@?##aYZONIyFXz@lehmKj;;Q{2b{>_+OUF}Rmnl`v285V2OtOO6`Gb5vA{tz|Fq zOl+%+PhkoVfiHUk?A+T$kJ9*qc(Y$+r}AY924oZo9VvVpyKHjL#&*>a)wJ9-F2gfx zFXz+2m{p~d6Nc<*t0f>M3Oc);r&eoz@RnON;kmBo95Eph;Qk)Q>!Hq4JI8xCt&vOI zZu(N&w0Zf#Rdg?BoHVqp{r%uUXB@;AWs?Vi&IPhh#?COJWeucx7ghmw3r64CFcROq z)4{`wU_6^+Y-J|rn@mlSF}V~bAbhgQ)5$=y*Lg4hJ6)^ST^Dqm;czy6g=)X37gKK1 zN&9y0H?LU?psqtDvb7?;WH%{_ve$UYB4UoItP;`oJ*F7&_M7 z6qAr8)zu&@rn}Z}OwWI5a7S^+zZX-)1u{i1oDk~NL(`)$F%EHg)0Z-30{jaD9Jx$y zdjz?0o8fY>Dk@2D2FvXw)W-hz2leI%Xv4IYP>Dz04-KvjW>3BCDJWRAtxcQZa{ z$#T+xW~8FtMqA2oJY$w)=bo>b_ThCQw?Q>CW;&)Je!z8nh^JdavU8F;Sl4;f14?>) znisu^+X|GXILF7cv@V8qjf==T!HU(qjGny;DE(QT*cw(S+bzKZico7%R-5yZm>j(1 z7;&Z(&*Etm6V>+^zqG6fE(L~!{QPrqSA`uw+Ua>A{@!9}pl-!#CCNULk3aTE}X_<8CWeJDAGS#7~8&t zI9RF2>f~B~Q44UkSFL6zh@dT)V{puK+egjy5cl|4=eNC*ww7PiNsNEclOg{E;FSer zO2)!QWgyozG{(+1;-c#0=298taq1)6S%Ha&KfH9>a)(5e zMW<;fRu;okY5@DmrCrd(&=yT;X>9?syApJ?`K$g0mKj`q z?@R|D>W;7bGjMmdb8V3J9YXix8e!;?*$E{mitncWl0?}815h~jMrw=+pk8M?YbT$G zdj2@N4SV*v1rk35Ek77IHRcgB=l-Q69>WD1{^BnXWQh>7b8*7AOi&XkMBCONbLE(9 zde`Z51&>dZ&;+N%O{BB+IS&4eL&@vp!ll zZUpVrV7Tj5d1LIlLRP}X>S}PJBPD%A&mlmvkL>ra%t(4?@KuQi;IjQ!)P~@Ddyh*_ zKJDrzNeVQFJm}D&Q4LGgAEoY~@Vc9(_~;9EWIKiqvjRPVWwjJ$L|z}x$A}O?H*SKi z`0ZWQmnc3k?yTgaEHHp~VY9axf(0u%Q3aOexgt`bFt0^B=b2T7ggDnn1Mu)xI2jzc%AP|x+& z^TQenA!B2K8*o+8cts>*KQ)w+hZ796H&Im4}NQaxE#S)c2GZgIH9q9KsD8M z)IQvBYjarwV3WKCz$Js+YhXY*1_Qb3a<4+N{Vhft}tXY#@CdR zjwP7A6rfjm=0&`(6e=~*BC>~S&DNQ-=0qJL!rv6p2fij!xkAOJ+sdhZ%!v7GFJyRh z{`eZM0q(LZtH!$jvZvo)N6*7}3tWl}IVGOXQm}^tCT2JW+8UM^Q8sTJt6IJKdy{l? zYkf8RikZqLaC*3HCtjJ2_=}boT&;f#y<3L;)x%i{Eumm7FYw7evl6--Xg5tBxIcksO<@# zuKEiL(5LGND-SR$zZ<-0Wf3f7abe+7vMph8Imvg?g-U5*?qUynDbvZ7*NOc}b^z+Yk1XC&4 zPN8RCm{^`6aCb*ka|UZuxwt{ab18UfO*mTyz()fA@+&eKwxOo3ZUAK2r`$)1p#IMFzp#S)8Tf)C!kkZRqU^*g;?EHs7u!3L%+0<^PD=_ z-nza~KgAn;->4Pd=xe4q_xyu^1b%Y>VN@uy=Z5nPOXO*z3`_EMT}-8-^hnPS zK(SGmj6fjk^OvGU`-;BV{lUNcRJNKx!mZ$ae^N#MWi4IGk#)OZc5md$EJeDP9 z<&1c73OO4F(Q8D6jkLiUuveR&r#2~H(G;z$-&Smdq54h4-{9Tp^Qt)%>RY~^d5W04 znALeeS?f+2^AwMfuw1Fmzf~g)gJd%b=ypALQ~D!gJPv>(vDfV+TuCa9wX6D-V#szF z-%BGjgXVjAtv(4;WfXpQ{dvCHZLfz}wPaOnGi6f@8vxLF@HI~3Gs~b-A*%goyu9DO zKSq60n?|dYcp^hp0 z1*m1)Jitwl8U2h1g>F@PA?FfWA@sqApz@H=tRlz_+Yia*kfhmQ+g8XNKS$nXON0n{6(5a50&{B~V z!KX|`G7UWIFU5z%)TGn)U7gyv?y}3U z3hU~=bV3)QjpTMW?34Julv0RUAOYhBZDxwG*p?d+nY4|cA6yhOU@z>oya{*X-ly%C z3O?uKS#I3-ljb;=qzgTn@6}S&vzXgcVKNRG&Gu~PX#mYoHTrR>xlq}M>Iz$GjjCg- z3DJ;owjJM<4fai&(GweeIFC1e!zNx&Op0zy<>}5Zd5!tXyV(vkBro@ObgHpoG};l= zw#X{sa*s-#cBU^Zfb-XA*_zxQT9WiBi_{`v9kmEpxk^ePo-uLXV8ZchN+&PRohW7Z zd0JcP<=8t?DzKf(b78=(%r`Rc4v3e zhu34nqjxryZ{*LHbemn%^ypFfXYa4@RjOR&e=zh^-K>7&!+Fk+SnEw)uj-)&LMg_kGnH!vhsZa+rCLo(PNHa zf2sVtTRxeU$o^8N+G;S;%X7RgP+ zm)_J3{NRPQ$lJ8s_+V#X?Hj*{?D|F1biUgw>$6>qGKE$I5{N}8^~?F_JQL`dNr3G} z7!NFKPxGX6p2C*zbMYc@-6KR#izk8TQ@kp|4QV*gcw(%C<*ddp{b`VFZ#^sb%Fxp< zjm=XTK##p$8+Fk=Y{ky41`giY$m&G;T1Bsz@ysUhT+tSN^e+TFDP8JrUDCqPM+f?7 zSO$&H3vAoH5o>?rTJ90SbbDXrs+PHMcDgdz9M_tJ%)t@T_z59@Nwme4%)mWvTs`Gw zT)TzPd!sfrY5ifsP=e@i?a@2?%{vkGhP;e^Dbvtx`ki_! zeU2fD`o6$oIDBOdyf(QHttR%})i9x(+;GoEql{CH55f(qgXc*BroH)m@9%3$WZvW} zeSJI~CeNx?F#GYZGN_%k)MrPr7@dpd=1afq>=3)3W#u7&lN(|}5s~F#DZRKaP=9d` zm??p5d^~MXC*$-cRILq}JY2Ugh4`raS-iUnmBFL`z%YVFCw9*wh(fa}e)>}ycU8Q> z{^Wfwn1F^gC(Ge>qt8bvDSMfgtbg*A-j`Jw;F0ZGQClx6mH1`tZ&jR-9S?OZ+g9^6 zhV(ua6`$n2n29ccobwRL3;~5s|2``Zcr7Q_(L%bs3#6@PnEvshrQTb_G3u??|`49>DDB3m&u*{yNwpDaeH+oXJsf_UpMHjBRIW)b)k)aj!)VWCRbGeov&2CSC*0I& z*Zp}6GOc^Ka71%b8HhBpnS6rHVs&Q?_4a#gVy8|Yx1o#;YCBbXq#v&ZU~03@K&4If z9M-t!a1f9|`%)b1z^K)@#pEI50*syhVefPYL4Puk0~D801$5gI^&;`5y1<{JOaJLa z+SzbKt-pJ`-Fd*5|>!hXl{3ve6gv89u8Jo@s5{6+MQRzXb%yi&KhRB6IW_Nwi~Q+%@=5MZjFJ_ z5Uhzh`D#oFzq15&nf(%aNayPX&KH@VUttVdj^f~>JrI-EDp`~Pma=FngeZs6c#ifS z8`Y$pXab$KvgC_iVMK<@?=dP*9*Y%fp)-#-TB*pTcv@pmQt$CgB$0xJ3h6I)`2lff z(lq4{n3;>C0gKL|c62vpezvQEK8ZP#;k_nJ8)I=Sl6g6$IHBrV3UiYg?3&|@x_*pY zCHv!Tb6ooJjRore;I$1cJ)S4#zrKV3eAdV=^S}7msOicd>!Iny8j%D~9Hs?Sg%Ml$ z{Q`uAsv%Xq%=9p+D5Tb9FPrj2beSKJjzCFz?qwBCG77nrtY_hc0-<6MJD}d+z8Q*F zc(E5v+0a(ZqpMs+Tj0w2}#)iYy2C&yRNj+Hj?(HAyEqMVB< zEl#S;aSjOD{x$N}JLO-9UwNJ{t=piHxNN&G%@Q&_*?stKp_iY}B>zD^?Y931h3ewc(zVY40kypXJ3BgWWe& zMVll*fGbyYny^+|(bgY2g0}?XJSB~*4cN%er|WL2x;^`0j_8SPM}+91upHKn3TVy5 zV5i6^(hf;iJyZ7G&8%!4nBCFy@Xz@>LRtZl&9LVx`=lbFUQyrox7=Tm`z?}gY%44PWM7XhRj)I1k_KJ`Dlf(?TQ~R_h_1G| z;%r<7`SgIW+K>?7hlwm)hnrZ3_IAd*@mcYL(MMb04azEvJNt(NJ(*P9Tbozm;1Z>P zRA8JslVqFkkPhE+Irqj?FZ8wjmVq78mNHogkftfjRrt~7lM~~>p3Sn*F3p!;FLY~S zGO86j^XK|Mkf9#?l>Y-2|C=fPzdr)}m!QY?f0exdFh$1y!xaBDJO7I*di-x84`i{J zqzAls4G3h>J83s7IUWou7)R=j8iG zYp<r{god($zNaqF!fOzzG10hjSNd@d30FiN&L&Cxe z1GxxUn3v;}5@UivVv-CnQf|HwPIGopVSLz!jYkYhfP`iR#bPZ)iXX67uU#R4^YONY>TA zAr)S54=?f+ruqRx5a>U3PGVu=AL$p0cXeXSLw80fSn^~t-(EuTx2b(N7Z~)+l`keyd zJZ%LP4!t-77b#d2?)NXwc?=A0JiDX*s^F}PBxxV~vqvL=33B)v1u?v&yN(L%efn!f z`73B3J^b6&Ij|7;P>|}^FGnPxMi=th@iY!K?5dJm~x41pt2&2#mu)ynF@qpKhSU zWWec?nh7KRz_EpWv(0xZLQOAS_4R03AesThlM&@Hb6_I3(Li>;rr<>?hJ5l7K{2r} zKhsjb?I21aa6|pE36<*gU*O51p*|T1%pUt|)4RY!EH~^iP+2s8s;feQNQnBx6@Tl1 z0NvjLy&)T-`fEmjeu^fMgj*5QNo&IPND&p zAW!sX_uL2t*Wp5MMZefTi-^~khCo@8`$_^fX7?`kIDk;kLBUaGYSAR`{2r&aVW2E_GG)vYMm`%u=+D2QB<(cw&eMmRRTJP@v zJtu`<4oz8x?}t`*yZXT4BD}74$mH!fx>neF?+0k7)LPFlvVv}?;Na`Xt z!88lProffVRYjyx7KHV&Vs!gyr-O|Sq^CPJsIVhtB6XHg0{`q|jO(Y^o_>|a)am>| zp(#aN$ZqL$>;09NM=L$<3=ZNzXbW&o7_xNF_;d&1#O2=gI@+9+^BS=KjF} zPK$@tq#CuvY-}B6dUzaKmeNetg}t8n5sI#afGR{bF-f`OI)$k(yDk~v@gqxLEk%E& z2gPV%c)1^1d9Vg{zqz6vs=H^uNzUzo3l)XDZgt|W!L^lk>bNJdCl}0iO{!-{tt}sn zFDcJ(OrxI#v89v(!8h*ib5HWUH7Yga*Bhd&+lroobVXWV^ z)v?6x!-_*M?}$*23&92`{@5Ui+((P~bx22@_g-!+Tk|2vZA&2shOc{rhojJo5~Yzh zv8@Z^+O}gezvcd;^sT6gCMY$^_aP~5(<03gEHg=v#<@wWk@9DYPa1h%LnQr_RTye& zqancpt~Q@fL8aYz=B}M8weVVa=xe_@>kLIzhA!#$%TM4IOI`_({@z2N2Vq1Y0Hb{> z)BT_-?6!Iher2_j5nHyLlFcuOLn0pU=lZow$?@N*TJRau1FsE<@yxKalF@RuI{$UlcPz z26)gmB<2ZewCA1x_^=VxqJU2&2jmoI96`qgVGINzu%xsjROakG$7Fg5ck{Fs`dirA zez0ThXtTYlMmYA$Pa~CU^bYZFU^V0d-C6-gq`6X8n(LK6RsTA;d(o7&SMy27%o#a1 z2rTb>Xr9-}MQ^)ligLTmzNtq9_3u|%hJ=zfx;?0|Nvnlv zE3wj8+g%&S%S_P{(_6Q8tj6oJKy{hjHItCq&fjVo%h_5T1#$NvNWN8MXm|+gG`$?9 zrVFt+SG$kQ%2HW$gELIOUC9e6a(*|Xj9-*tO%hqVmlS&*?nCV3!kI>gmJ?2go zQioc=S-f`u?)~S62YvlW8;9Y8{n+qX+2$*qAJ_1yaKxE-iFa{YtLpr@#=eU^|C z^@>@VonRn{%llQ~8c|0uye1A?A&o4V$S+)9aJ7j6z_7icBT5G|@7+jGq$z?E6AUQX z#c@z1tl|1Pq&RPUW!(I3+xKzUO(lx1-yXzWYNvS_9fjHK&3t$sccu392xRBuHBOgZ z?aIb$KTh{0g>dPA^`z+nh3<*mIlt0yHW$*|b)WuPxYyC3mdOE6ln@+%Esn-!=!gtd*P9hKIKe zM$pi-c5B*@U+@tTCK_M zTslE5q-rL7Wr6cibl1d8jbqqtIIu7Hb9&bc03P|AaQPmS)nr`6Q8zW159cv5Fl_O= ze@F&!Md)c_uJ*D}oO{2m3gH7)d75e7fXl6KdX;Q^Zb||?D9UN4j!jeyrTsCzU&euT zffObj$kQa>D+sPuOw|L;o1c2+sTVK}qKxaO%ufBpU)dAxsy9RqtFLNgm2y0zp^+dw<{ChcDhV80 zX14G3!$}3iBtdeq40Ty0fL6dho<*E`7fY8W*g@^3-i-;WjUA~UMI_nuI?O(AG(vRd zg-LYQm!!-k`(yd$d167CV%X#EX;u=TgJQqnC{*ds71!nDx((h;Ap+edfkG_Kg9l6R zfxz@po+gm?d+8H=8~R`KJ;K7qC0_z}Q-*SlFoa^(p)R98{1aF;csz6>IBD?Rgh7-( zl`Z+BC5OM-U;)d{$Cc*025)BSzG`kNT=n$6Q!RD{IDiR@G;=?zWi^-7B;0U7jf>~g z3SA)@ja{$}4E{cPY_`u!%O!o!fftOcs%U^cy{e$}U^fQMUw(k%VU$m5?(Y@|htDu| zXU>UEUmli0)v{?;p3@Bp&a}+=>Txd6ly^FYo*pw=*)CZSE*RmDy z>!puhfNJaPhphRt)<`IeSf!qUMR)c1%MWHn+qE91)Pc#@!ZVEu09R!qVdwP@^OsH1 zqL$UemK$q#k(=m4Wk2>5=`ti+q4xOaIALhrHx}x@>;6lP?SQ{m+yr8PF{fIpK^iH= zOdw+b^J)*lD6mOx4}4ACDZ7fltFrRwE1v!K#Rc3cZDQD`%N^T<7xLzg!SU+P-!tZ~ zp~M$?>YzudF{zIxd#y%0$+sOFU5*GfO<446A;=ceCo|DqS|R3#EB=(oiwDe{MK2wH zmkRcs75>V$^;B4*!WeVnv3ZtK@b~3Y_}N21oNC5)7X;E21c&!e;Ddhv^vY zR@!ZTpuSk}oYc`j8|3J9dH9AmL=>-AaJ1}Wt2}wiS?8!6<(;b`M(lx4qSZid*CpbM zu>6I@#l7949oo}{p+J3WYyNBr0}DS9TN-Pq~T%Bd@S)V?wbUF!||CN%*g zifDfdGy)k@qRy_%ysHX%Y>S0^`);MR>^%^}Gn2SHpjh5fp3uoR!NBq}1DvZFpc37z zcPlrlxW};Xxs`|fbDRP-N!s?ZSMI#Yjy?5+hj-6TYdQf`Nv*#lucwE>a}vlFKX^VQ zv|B6d7ilgIK`oPQuE)q1=v#-jqDqx8fHySG+;4lMvcxVqW3xu>1X!Wqc)PNp;yWuidWWBs?>#*)(eKFp=GMeTGte$mpzEmz!x}SKk=tf<8kqW#?|pGOCGdO^BqE{gqP+Axvu- zpjW5!M|S+uYOD144#W0(V=gZ&D3a6>N98{E0@a)*BlEcJS)g@JfqXORk$-yjo(!aT z&jB;J`56}d`O>8D@hr-_V7H)VBvUuJ(YClm!H`&!5GsMBwj`24z?g!59l*qYnrWZ-yA3O8Z?`T7pw59?Ci zLG0{({KvkLmq;ot_eHSCt@a?^BDZ6><+atsaHVNM;{vY@#V7U=8Oa&1uG8_e3p-Z?}iz9fOji*Tv5WkoE4FA;nH#uhvL;gsl=c1_?4KGaB@*J z3MmmcoV1Z{|5w&|JkxKH^uM_L4qG#S_oZDP?bq&PcH6G;a~7?Aro6tLCGJp~IYd+N zjEFF;M@wG^okZILdz{DiZ@bs#y4k&bx1YJIJaO6giRh$0k)!O|9U$Q zIE)YBPK(x6xg@?(8L{&V{=0BZLFW#h}n1O9#*I_#d$~s5$31O zT6N%TSkTfS&gpD;IaPQn-d4L@Xf{y6dfAkEW-!)A;n<&^H6yVvh{y3=-0xXe67Z>N zX=Bb0STEFxEP7>PdA?E30(ooN5;jxtcLeu8kJOXV(**prE50TlHUhfTe8^Z5dJ63N z>%nNGi+@z^Nb`~h2xDP4xSpA1>E0G^soZH=!%z(MT^jhWC)VW_Y`qk)N#s%Mec!Ft z7gIC@Ny!YzRG9Ywi5{Lk@l}VO82n{FW?2y)=MYab%3UPQ;b5;MftT)m#Y_iWI_L87 zrck%XXKKma?5S)FOUr2-u4RbRMIFvvYxp%g$*{jjcxf{)^a@-k_DEw2C8a}ppD9;W z3o1tXa!%)kjvEUmVa)toN9S4?0z*$3_#(CI7NP^Xg1SX26M8wwn8S`y?hUZOkrn-8 zt^rX&J$n2yn4q8;!(+fN?%6KIVr+HG$3W%;K!Nqm!VKKPhQ%o5qGHp*rm5JkDWdY$ z(|SBg&|+x@rqIw+9-Z4Or#(#kYAGSM$pjU|KU4+=tp1_Zgz0|pONuPab5#dq1cy#( z2Ie&?;vCvEJm2NmC!+n@KlQF+yltH+knPt<{XrI17!p3PX`6|hsV{o*eB}D)!6Ff> zU{fk&FK1W-9|=dxV ziE8Kn1hRQD!!2yf1wpS!-H_Fs8W`Sm^BJiL&#e7-wSQ?Y#qygfPvU=B|7lC32#ao) zU1~g7jNaA0-(~W{o3x9E%um_VNUY?a(HS5e2_D?Mzi#4= zbg`L2k1gm~^pMI~=0R1|12?)U0Bj@hBP`PW0q@DP7}rvs)iKlYU+2st$-gv&=3<^& zvErnw@YL!odfa4`V<%&9PqSH9q6FiWo7v@N7-f;)w?<2SWh)srP-i0tZoQ=|{XOh3y3JFtNi|*zWxNY)SO6BxltbhH!jK~PZr8_XlUUsxKj>1Ra z0bpvHwOeQ}n#IkAr^DvoUz|pJ3ewxhY$_#PtP4-CF?CZ3rac2zjrq_>e^<+0{R6sU4~R z&|M)IGM0Ti*QavHCv6KF%JY|@o@f2R2OOlO^@e$)&{AEC_1hKN2C$=R(m#I4=FM4< z?SQMr+^y2jO(d!St_U^Sd)aA9In}JeKjrj3gEwft$ zITzayc0De+oD1DJpJK(j_}!8RH9=q7chq6A8`5Py6=+VZAaz{6y?B&{Evxiu1CmVw z1lS(#ZRf(0H_=MX6_C~*GG>;PuIwpF-|xGz{D(xs5kAhLz`ROX3V4-F`%^M(Y^{fU z^}5|hWLN=+UGx=4b)dm%Ue80!;N+B^aje7WCaRF&94z&wI;2H+tY0cZu5ICYVUO}j7&2G zH!TM!sLR2KzreO}9l0vXeL2~M!R+)?#$R)5w60xoxdV?n`?*F>X7H?cz;%6h%IXRJ z+*WXV_JA5e_pj7p;Ca%EYIyvdhEL9xWaL+bGpFC=AunRV@&RK)Ij1jr&%>83hh8_) z%V(-cONpG|ir}ZvlE$iVJ>1mLVd9LlqiP-9*?>RJZ=#|f9{HOtcJCnS%S=z0PtiN9 z_S0Q`Kdd=kA?gTw-zXb50lR6tQvH&-TLm-Nx1J?M%j((OZX|L}n#*#^d#{!@(Ow+8 z6r8d`^y>k=nl!U3Wi%7alU^H zRLhwb##Y!jSAAHGx2vfH3P&?~Tk=L8gUtQ46Pqog`;wTl1M*#aSY9rQja&=Z$q$drwW?~p)<6p`bV+OM!=Ww~`n zr~7@j?m4F?;MYS)4~XoPm|!|uhmbEH&JC}wDwhY>tUL22B$cJOrazV*Un4X_Bn=`5 zY0I9~S@mg#IDO6YS@O(+_=V}x;NY>E>~80c4F68RqD*hGa_=yi4$u-g5wj4ZGp6IT-PLZX zQ5{;lt#_y_HwY+sFcg9iZ zOANnlb#sZ*`@y$Rzh}9^*b-@Su6f>T{?qL_sy75(Uls57$EPK|wmYv#gmUn>ix7_z zO!uat;JFt;V%v=6Q?e%DM~4ma5ZrZT)QuJaJ7e`kjn;H)fctf|QOAXI?6*?-UC1O^>H?3SS66-H;2s`57k=hP6FeSQxoyXiHIH4zii@gh71UBm zi&$b4LKH&Maa}*bev+~>3eAp94K8Y-o0dZF#ak%-$j|~2IKaC>Lo-$oGQp&c>uRn0 z8Hbq%!3Gu%CJ$0s`2)ZpARzFB4Zs@dn;#wPpMwyp$}blem6ZHe95tZ$fja%Y;Oohw zqqPD?B`B~F&`boyo7Xii8UEc=i1S}ht_~b@qRRI74`y;Rd~9**A5BRGkV3GQh^{Qn z5L6u*E86Lx2UT*vpQeOx0=P$D4B!7i^`e?kxZ#vJ&N22G(wr1CG zjv(HxAIan3&`iL8C)Kh)eT;k}PxOtRIbc;!sXt+SiwPk*f@)*&rmuo#XAAcG4t`be zepjO2Y?pJoJJvpatm8hkECNQg&Q6eP8La&cwf+ZeZm%PDMrMf956hJ!E15w*=qA47 zGTV4QN~hpY9z25nerI53AR-N!6Zz;U24K(N9^aGcRj!NfS-Ne z7~bFCBcB?vU+XB}-&glNp((CSO=@h-?^prA23GHIJaaRY?*?`N-%gF_zV$QEhPAG> z>iyM|^|h$|^98Z7fJmnSSR8G|0vg2zxAuZC%q5Nh=&CI8D!u^oF?EKLlpii8>wo+| z>6dFc0Wh9b?Nu;A&(DtHACMU4N5E{Ej&}Om%D4EBVZmQQJ`F&~xA5ZjPWl0xtDE@X z$yeC^TTA}kFjDJZA0FTTE>s0g$o%{9g*N&x)d<+mWN-f{yrH3q#p_BJq7Yx!MEAGo zSPxj;$9pd_z_PsC*e>WsUrq{8T=swiW%7F2 zSpv{sKCgo1U(?Uqtcc*=Kje2)F@;KeiI=RfPZ`)(xP$ih47@wEh@eFA{TC`QkDz}2 zZvU9?{@SJH^e#g%vrRkjdq3p{4sO~>WjlB`V$5V0lR^2$NpHvtPeN^SQG*5Qo- zmY3gY{*~yLegc#|AjRXOm2Dl|)dki{A9oRs^)Zt$PaioH0Tc9sKY~7{Kt`w8nivoo z@QXp!9yjy46L@m$GxfIU?DPxB7@H@^VTN#n zO61N27q_JPpp|%|sv*CdDE#pv83QS{JqiQxIr+nOItz^WN|kuFyHXfH!{X%ufhshs z)Y}1llwm2hM*8+WIi=UIQnUN9HvzYqU$;DA>?P50H=Ne}=k4b&`&OZ3Wm~?W%j6 z(x%LY+%|E$^!E+HKa8-UmH!z5(J8~m$zV4jxEPn2zYBHmORaK-2rjzaDs6A%X~zQd z7aBL_7aBzixQ7Vj%6PO>Eg;;-chghEUt%(9nVD&hmm9b+C{wC}P7jT2PSJqMQU^?#rfVEb-JAwN&#hLld0;-KOWN{bG`ePs={VsHkLjs2OS;oh=r6tSeJ3j*w@^a($mrwjAUndKX-==bm~3N!fn_-$YPJ7wuzqhbT@s>KoU~<#npAuc%)Vv%@^GYX451=r4#sNbDZ2 z|FYmiTM=N}fummMHjHZW$Tkoj-Cb~vo<+0ZHasG^!yhJG9MV!~`Vyvef?9mEvx-k- zyZeX8%v%0yp|T0!XqPZTYnE>#OgWL=LX38~Nps&or<>@gWuB)0&6u-vdcmia{+2`& z+Xl)8j|I}xSjEtBeRJQfhtb=nv`!#aoV z99ynO94ZcoP%l0vw`UTEor>u{84FRu6M{6Zq8CCh=t?{kEPRvNak8b0xWpG?QGG3_ zWl!`Q9m}VClT$xs$=b&JgFBJ;wAUceWCsTMNgz)Ac*)8?K zEr{>UOW@g+`QTWzm2VQ}5!#BKM?=m3^BmXUB_glZD6X3GH<`+>yZ_oYvER z5|eJ0Rt6wqgA8qk28s=7i&8sWoXfM*4eZ#JLNx8zMdCw?5$Cn@6ZFVSZknfR??yRn z@OvzC_I(*cYFxw{z9UKP;kWk4KK!JGr1wiIUPNaV?4Z+Voj(;WgWgugAZXN99foHN z`6UHlX7jVwE4hfp!CafG-guU7RS7S-`hlwzb!BoU6h@~y;tbE^YbW(wA!?0*Xt;t; zH;J>!YSAJFDfsv48pqToR2ME@-!v;>oRlB^obn=A=L>zahz+ga!PoeKSk|ITX!ni( zhv3rBQ%I3@`0p`&amFSS;s)>Aa#GvHe~Cx{SAF5s@NGE4rh)i|X8taYKr?>)PKYID zG+vg+Uny%XEd{Bv%tE>jZuZ4cJ=Re~6Jm}=PjSVPpf7!+U?n!9l$M+#;p&;_lujjP|dqCgG|9gd2 zESD=fMXa;*KNLH)g{ykhYSxZo5F8Y`O3 z*sm+!Fx3XWyp`W!e4JOx-k8D)35+3;GWx{=1N^<*7Q>j)dgt{x#$htcXz^iyZ$Q1_ zQ$|ED8-GPWkXC}oAamiPkQ8VQG2}^EMqzQ(`i#T@1}zQbl?I^?oQ3Auv*LP;)%v9j zttmW(jkEZ^H@A$hj^PyntGL$NmgfKusc}pTpElXNC~+#Yvk_`wTTcvSe@i_soRQds zzeSFac3i#tS(32Pa(Eg$_Y)6bF_@jE;g1Y=aEHpT@0i++ue#x>m@(v;L*tz{vOe0b zJ0EvNuRg!@VOuEmj7nBvKm5X@Mr8MGSKvUt3Ma1k$vRg3688vhWCQEh;7myx`nkfR zp3|IQ=-<}sQO&gNfD2j#!EU2YF{crDc{UH~*B48%Q63Zd>ewcFj@12`* zH2W|f^jrY}=GQ)5oe%S#!+<1CD*#Yxs^7gQD zosAi)_zXzwi%k*QjcLI_tA@OK+H9o}?tWD-!of$qPd)(pDY2e zFEVmBRR~~K419gkG`+R|THD*daBc8WyEF~Vyz7m}+(Uu#w1m-_YGZvr%4CCpPIzg_ zL1j8`8RbG;?Xnqn{m?c<-w_wM`pRkF!;iMM8Dr;?Y&aQT$SX4i^-x$u)cAulolZO{ ze{CHHz6bggWbz7XHI`X?b(dz!zGraKPjFhD4`c&D=v!>N8IG~1LUUBF55oME+3h+Z)|Q)csOBf=euGZ%br)*MQL{H#VLl9~hlW^I8;saAgI~Gx^bu~{BE>4i7&IeSl_SK32 zIkK3*qUtV|BYBc9@9d+vpVDT3;KGXB5xl~G;K>b3veo|rIzv+-&+Bm~|B=gApf%!L zs-TctqMvcBm%23Pk4Js;!iX?*?lo(oR4E`Y6FpWhuhTMxz5N;ZFkl#FF72pLI5nE> z71{Bo@76h(Q~(4|Yc)%TzKYjWaWvW6gx-R4AMYI(9jHjyv!`;3Ykm@Bu5 zRTZa!aA_!iDb6Z&-|0}R=1bP7j83*L!u%%$OUGY?aApT!ge`~b^E9gRFFXBot`+74 zRu_+`ki$3qFM}_{!)_iyW6Y`BBzU50r2zw{aeb8_vWAz#_ky6g953kuzcPsGs{;dZ z4p7_hBo7i0IJ!SCX8nHS&=YM~Ec465@wr-^bM*Y$`TU}5jBK)i_-)QI2|$RTg~7YA zE8L9MV6%CS-AtpP@ihq-J2w+3s6(15?>&Cifz1n_IwdBH4ArL??0J^{A{n-a0@y?3 zpgoEi+70#}KS+3J74S2*#($kmZ0pDx6`W#QJDcAIuLDDa9^S5uvjUvtO0Hj9wY+_Y zxMROf61YWOEr|yZ12-rjTzNTjJhGV|Dz=v3?A!(mPGbb$9z08~IED?PN*Pp4Z2Ekj zUjbGqu}dQ+o!Z7ep&m)d<@eboVE16EM1GKPn%v>E51PmrpFx*%w>3&eORWImCcA%j z`q9$}6IN%)C}sXGa+yHK&F7C@>fe0Qyo}u9YAcn5xBlqWWUm>2V`V`vA*0GHW0?* z!u>byn5DVuu!(B9sbi)6!`#o&QRR4d1EpXKFV*B41z)NqveFGvtJwuBHkkL(J(@ab z-!DVtY6YDty!1V@Hx~j~k|zC)VxfO*L3UA=9G~2~3`g3sqjK-ia+`!PhNh&$$jJKQ*D!=9a`;6gyx2DSoy} zbP+5s#o3+{R0<~2{2Pp5qTQ6F!iv2iGpY(A`nJgjWcv&2{_js9Jzf0BD}Bc9{VR??qM_S6iRtK`;dAEm0H{rDA+vuv|K|ABrTAfyh@5@IVdhgdf-0&d^uuh zY5!T}%HE?k4PO4E36rFvBTe@;!)=s9o~4y!1fstx(8A#BIoSSPwT_>c<*4HZ-aB zbwg=`&6cDWqfWybQXp1%3pY^3 zYnyOo83&Bmn>#|dMuV(5KK!*=*Ahwy!mO^$q3E0F=$|k5heIF#s$TJp;+4i-SqAkC z%#)phaeDs&%6ku~J9KIPShhB;2Gfu}I&ijM2JNm|akcwCo~9&GBEYGcm%M8ALA=nEVqkU#X>`h-Q_d^+c{M1w?$-iy zLa`)wDE>W%Q*+JKTv^Y1hHm{)K22fL-!n9WDV0G$VW9|#0=}{@UD92!a9q)o)W~H| z^TLP=cjoZPD2#oN*%WeD0b;Y4eYsvevfs9noy)F@w|$tbV#}{3RXOq2nRA!HUY_B) z-*9?}OHGQfy7ScB41HYC++*Ghmn#UCuv~%>7TQ67jWV!<1XJTS^0=u`W>)atoz4S} zYkubf%geg0RQ5R}=}JaX(4sMdZn{Lfp%g@8O&UT;CtQS zpZELPDS>7$NnL^_wO6-Yg;@jHwV&YJ6+$6RCI4#TQV2HVh zISG7{6R`!(XQi^syk}mtsGj*BS_RLb@^Xd%WQ>d|9Wrd{wYeWr@PcT&x5l7LzhSYp zUOL03ui6|q8ky9#4-l=YrVHHEwLm1BNByZ$`=WizXY;u@u$cyJ=kklH9kw+K|H zuosD^V|{Y|XUniP%9kXBLG}(2`7cY&Rr4Y*Y{+wiVleWYW=8A}3kAUrLBcEhDTc=h z+-zy9Z0bj+ISx*Mz}s5(sW#TM)5Lcq%M-=orm(j`8P9O5jXb@<#D;pgFZ4!oP#|=u zC)fK9?+p)4A8iJ)B%DvvKOPE@7Nn`XviG4pOLNk`9@>=zX6GJ0@3+$(DIJ4e zFHLTNI$W~Af=pMXny&JEw;4%WXW}^l4l;}Vj2On~%mujV1kKNOSCB)2+;fdLvDNdJqW$qb z65+BxnA~GeF#^yrAJw|IH(7(-_ZJCV&y8WmepTVgjYZs&2+Ls(cZqZf7+u9cOzkka z-izJtokROLlHzUpsQR8LIG^U|^5%@fP)?)PiBbOi=DC86_6JgOW~rNrZ~>c&yk_Wn zp>&}rHh*c9$yk`VMZ}tISU?gQY>eG{B#XqZ>DDA^dC_US0cKPl&zN&aZ>qrgFB?^+uV3y)n79( zC8K1Fw;UqhnUxGK4}iK!iw>Mqb2Ep6sHPu%}@Y`%J#P=&Y02whYgwd|vqW7=D_5 zH75a;9h7PtS@=zu?CMFZB}9SHZe^^NcR79}xB>$vt6^EXg|Vn$I#y0(xGeqjhptO@ z?&RBAA%h~=s{^WKVy9$zf@7A^Qs^MC|7s8aoQyQ8(MQ$c0g;j07qcMf!oxsuYw}KT zI^Ck!yQ4wn17&!wIlr%G1?3wVOjJ&)U0)2rD~UBF(>ju7>@k@6WmYTHbNQ2PZWq{} zAjS-#hCldwF=NS}gqKo&r7@fpQ>NAO{6ZH6?5bG%4Em5{by+bEXq_{oFdz`ZxeSvm@bMvq@>|h?vz%9 zxZ?LZYaG*Q($OL%1Ce?A1&gi4l{}JGNXD2v99hwcv)V`{on6^*qlh(n+G%xori0o% zRLt#`-JbV};<=(cBmYxOc|a54Op-#$e%Z6|6hpn50LaGXdEG-1tDgObWM#E{!bH0P z$3wct=)SRS_}ZxxD{vG6F&a4D`5l(Amc9-lrla>KOK#hXn(G&^UIS>4Y5{~1M)HqI z`zj#c-~BTi$>)NG+ex9IgIl?njO);{bv3}S7rFr-^G(SYt0X=3gW7fb_?ZG zMr9$pKtX-#`?~Io#u2=xO|0ip<-afz5P9F4LlVpus zc~z68kvkn9!UmV>HWnVVL@HgQ2u>}u5`T;X*pqoMa7KS1mJM#^#HR9B>VOO6TzxSEOdhQkKc4K&JQ{{ zS{&tP`oO+r;XoCG?lMjDu3%(}WDv=pX2jhP6JgpG{%^2q?_|d;BmR<^nmaD88qm-t zAP&rGC5dL>)pDNuH?ccrjr$RCk;KZrCi<2{`+n9Wi{r@IzK8NvLr+W58jh6q(uXAb z#`1712R)N{>Bl=FO?*{g=4%cE=4y(cq+6>NlCXqW=RG){I0fplD*1it zo~`3hQ4C~i*DeH)TG?cA!KXhJZ|MJ*Bn`gtXG;!m;ADqQ@$kbNLYn9MsBkm`cK$su zro)37E*{J)gI*uSrG(sg+5YpFXo#3GDeZPhjnwWh8iW%V%byD%%=$@B%pV4$6=BQn z8JSkZSWsEfFsHoY5NJCUQ{YDI3W45AAekn6UPTxvA%g zR-U)_OeeR5n8N_H-xH#vOi_IsV42u`d-vMST6z;>OJ$KIuAUF~b5Vv^mppjnmY8^( zieMIdAmkpNHgZ5jnhIkiB*OZYviC6hQn&t9N6siCgH){nZBe#r6&>=yq_MAB2NL$BBWtc`QBb#p@FO%7`O&1@ViVt$CGalw0aL$ij&;ySNqJBY3{KeQ!i*$p zgf-{A+k{?ah|rm3v%2Giq{`Re+)0pGCgg`%JSl`^EnmKBa|OYf!{X@tu&cd@N6BQS zGw3a0cmfS_$X&26$C6L;N3@V-i|%GC-9=->QVw71_;p-<2bCMK5>{Cho7qnRC42XE z!1S2~jmix%IuzRHjT6HUaO7uED{WFiI2Vu$i9baZQwgat@(asdUBHw`Iug-3LGy}G z%WQ6B5JaNM!wTuDwNoS<_y`INd!Wgku;P2vib92RqLi?z`k_l?BI*3Wdr5gd6R%3f z;TlhgT>95qb`rFduWHLriLsnLJEfrunp$#tDD9z>(w71{lrVt}7&gOEr~SN0^*=)l zKx6GAn?+7cyJVF=^o4bTQ%f~z}@u%4KBcbRSP*7+;p=>&q; zl*f)fIA60`a*L;#s2uC45dld#kS+IEE6pE~5Z!;`Q1%q>e}m~Ee`HTj@A;{kpF zi`zjSXNMgn4X*Zg%Z^N>TAiymY< zUVsnDD}OFis5v1a)WaiWs5W3-uwXXUZ=C*1(npH|k8RJNyCT*sIQ~)Q&SHA5Tuh{A zopd`$+f(rC*}j7#SY~Fr;DaEL>9*r8(z}c&{*D$;-Sk}g?*5r8Yzy%{n{&#! z6G_-lsqZiTM-GP{#B8kMb^F){O4?zH*0r5)WQ}4bK(ImZ`p5FqDl@OF59yESzTt17 z=A}KNZIS7WvYnAeTjM2{hjQ&PQ;TPZHB(_1|6rvZLH(nnZ7&4MS2WUQJT&kssvaUv z56dWN%2SL#F1xQeWXi%cusx2@;6YXi8nUd+GO1RPr_E{-=34Cb7G5#G@jb_>k`Y&H zB)nL^0FsrK_#m)?S-N@+4fgWk$+iYzEx|hI1Lp+h z=i%}R%9FZc=&iLxe{v`wM2?Y)AS7V&g@t*hk4)fWoG~}&)fB(wEI>zMFY?)%k7q2H zDsyobJk-SWZ&<+KgM~Q4YLWyA+n{U5_WcJI0EsdvG|DAUQ-1uAeu(oJK_rIOg(T-M zkiT*p$fBr#q~5%n3*kD-)Z$BLe>~kOf5CmRz15yiHj5DZ7zv-EH3T2WSz{c4(LSwg z)=wjgc5fNf;x=Ivzh~>&^-}glMa~k29i{+MsvEBED9r2w9`c6Meb}_nxx?nN>c4FO z$mE}Ws#D7d7#zwlH~tL{%XZmz_iM*&MK6cMWcz&@0Ly3VwEGVqui3q1xO!@WNL<8M zIqQuiWhHR74s%J_PJn%-p2ZIs z(-BwWccj+mNHR_$y&3ZnO*VBEk+xnm(9CozY3NpAiOHTgU2qxbvI0-yz>L&zLE$BL zUx8UDT{)i(;Y>_&4MY-a%-<=Orjt#{#D?Sb3m~^UH8%+!H+wsCh zR`P8X{9Il~25WuFDkoSRcQSvRFU#$~(E0ENzsj6o#ATVm-CD!1buZG3U_cw^J>tV2Jl_jVPVp_Tgo z$on6hu6Mc9PTSZ#Too;zY>xk{j0st9e4K>G`%ywTAG)85tw2Mt_&DlAr!V@nUgc!; zLL0fitam0}7I}O+10D7kxT(P2b1tL)|m@jk^ujVXCg)vx?KJ=v<7lW``*YUDb!h1kWdFX|a?UMXf&z zOg$TH;cS?=FJh{QiTxSFW}hMT~w5s}FAPw-pTma!+!4YtTOCW=rRv z^}v+%=N4`;!};4AW13xaF^UY(1_k)GTCm#%?&=dV!-^5psr7EXyq{2$@WAW6y=cVD zXB^d_cdUvflSdd8?G|8lia%v&`xHs?Uiu=IZDP8RCMH4h8ysCp$=N8ZzV4?qk>tAG zpN?aSi#?*6aC@QwS4aJ*EEOAtA3u%n%r#BSo;`$c6>}HkHRwAyb z-Lx}IJ^qvo@Kw#Tcke1#9_LvZBtP-37>W^<4+#4F54YjB~6(AxgClUKzb!}YP#f8CZn=B?Zie`&>Q3Jl+2l+E;HK!6D{ zhojkTSO53tM^z#>y4Fcp8w*<*c2^W~y@FyvZ-bEwNu6>3F;!{F6_*=nFL+}{{^4vH zY1324whBrJq>X|4b-f<7bXA&L$ZCcPd10#6DejfCHx5PgTAE%-&IZ)J8@|MeYZQZ4 zVl9Hg(zz)z&nbV6m8K26l?$UTTkY2+WXhUF58hWy(VwgSDI`eQrz{*0dKB(P?JcWQ zmFvAG6A~uTG9?x!ha`>}c`|fyx7?2aAST zd=0Le?WfT##q9kHzVc+Ao$t?SxIJ|@2j7yHP!R8gk$$hb z;qNF}W;zQ!S`KePYOaDzim~m+%WrKwa2=R=_|x6`7B<(}gqx0a+&AmrmD|jDMaJiawz0fKH0 zxX0MlO#oG6MAwSOlL;X_uJ)8(PkdUCgNl2yuOUxC|}~8kfMwXWe`SK2=yu{>;9Sno>w;IUZ%kyRn~d?k#Qb^vnkQ=7cPV7KuS-k&$+H&1cssvwWqU&hW+h^0kbl06kSNECr`Zh;Sim`# z8-ry|;w%uw82<~}A#rAs1=UZuDYT-*iqD0J57#Vv4pvBVR2MNFo;+=sOLyln;!&z4 zX~^|rT;g9}oGxuln25E{XHb2MEfcR=Ib0qCwJEdEF!I;OQc>C#JT2>|>{SU>weY8@ zs`x4&-Wi7bZSLW@_`iMn$MW7LfQwsL1C7^3j{I$_-J6|&WML40KMhW6^eBckq()(((#EBm6P?_k5{aE`0=c7d}bIkG(l29#W zA_9CKq_K$Dh@;7tRTDP*JGiduPSPahDvHh z&T2W0Jt@Us2nR$T>SCsnuD(XgyL$4CujAT4Wey(dKd6@5I$@nUIwG>$ccU?X0Pl*# zx6FUg>o;zb(`_a<@Bm2@P*sLHS7OjWJtDi^KxLz`0K60fwBa5js&KK=Q)l}2E;&06Wo9KUVLpNr*p?VM7@ zw;|?Wky|rtzY2udi+Pooy3wdrC9F=bWt}I!xKFw%?{UaMJb|X5c(t=IB|DQk!?^jgHRELjy&|ukCy=p6%QPPIi09lOUI;L2HVR2?`i64bwcQgwx~a zVH30DO1|KY@)XUnfOsti#9na>=xgb7k*4zpal)-viK)M}p0YYsmWbC?J!fXe25LOd3k?C3NntbSfBA2!c3RU>-CZhuyG@kM%E;#FS z((Xc6Er-mXl3I{awga4h7dv!+g58kQ>a~p0P zAyszpQnGOxG#45#9C9PGPDwXHJ$|e2uqYa=kUWzfVQOy$ zY?ng;xLlEonrqG~n|j~CQNezvA6yZH^Jl%**(<2QAnZ*B?`p1?i~ks{YsM3k1dCQg{)MDocXlfRj-Yd= z)1VV8>o0&2R=FLCwEywyy++^R$12j|F{gn;n^+OQsJCqjY}Fd^|Nd={d;{kSj2$#a zEduGn=0y(y1w|Pi++w~{q#%jN)!DG#jvtpt#vt>5D}^~bmRLX&6^BaVS!h{wdMDN| zJ8LAZ*;q+%Jl4ayl}w_iY4B}ZE{I^C-GTh#VN(xK<^L2g)PYuhOpCs#udJlzei^1J z2){m8mzH8_aoS(iABIOeE5-K#OvdNnH<$6nf7ba8cf>9GvIje%zvqr6S+H7DH4DxE z{Tfi%FK~RpbsU}Mi^=2$laRy|eUfyQpNx3?vs99sEo~<~|B;w@(!J~^JQ=eJ5m-Xa zqc<7GsRKngZ#C}hb`E*5$xCnjk(iy%Z>8W&CZ(A?{Gi$bMN#$#k6jo7usmY2CWmfM zaH5dYxS*F>*)iR@&ahPxCkfz^=u72}q2#(=QJ^~ts5ygG=aZTT^kMR;OoVVtAE=oB zfUAwjDZ!QtbSB}pKx1@l+jht9 z*tTsOf7G#U+qP}nw(Z=0le^yF*0d&7qgr*ov-iH?ac9GYE&1VDw!=gnNb79kZ6LBB z5~toP#V9!us=amPIeZd@eQV>qrQrr`?I9a)eM6&}&&nFxkf@y!LgmX{3T~~oXj3n* z0dpC)t?axg{bl=WuA2`w^93P95IE{9NR5`Yb4CTDq3sBOp@R{(nW6jZE6X-o<9L@k z&|@wo5JfH2L0R)Q0qhd`^aLd0q}X|V_xIBh7_o!jW?JMYcclnxjj>-px@>NUF%L?8 z>>|8Y4G`8enowU%<|wSI)1g1|K`OI$n8gb3OfTp#*-n!(MFkVNg;bwj7&W_FLCp1} zha%>z>jppI$#H`hti^oa=%1;$G?VfqPXcDIJPvLKW|Mm2w*zsi^QP{TJf%??ozo&6 zf!(;_T$87|^$+XnD5Vi{4;(O7wPHI(Ax2ch3!P9Aa`eN1$<|&gYC(_GHDP$65fY`h zF2c#D(0%r6x3Eog!0MTkef28qEar*2awINl%Dg`S*XG{oqn&qu_BgDaonXz+-zX?j z8ZYB={p|-RhD?q8e_%+g{}V%EVf=rf5gRM}f4L(T!vEg+$0M;YGZOya^@~B&!rIv+ z1rHAx7tpHYTx8Qio>^#^kz_p7d=+k^R%^J?Y@=+=UAEe6Q(^e?aUZo)-mq$RwIpoK%hMeZqT>zCQql-E!YU)7XJmjauGJiCZ>t2P56 zB}%>z#A?sn(uBlj58?>A=sygkkc;G(hSfVb1Q-IBfd zE;%N^@XPxEsDF!crDv=IjsEzy0##XGRr>$?a1edhfF}J@8zx{O>KodEgN2ULm`jd_ zfl>|~DgV>-;p7JTqY3n_&5mzE5gOToH9CMP0!v%t0jd6=1Bo{O9zOnQJQn}KkQznO z2LRbOf?}urz=5`70bhMH&4FC{!7m?2M+16*kE4N(5J_ba`eK4fZo;3x#{uVFT3j=eOLJ7AL@a%xy|86ewtix z4j>sg+{h}we-C5uZTQ2I^>c}G+v9AfZ)SG%U1Poh@c5d+p3K7aS0#U}m7WARVRL>> z*;v|wPTbB^i?64yf}~>pRI$4@e;{PQ%9!yXxCz_WZrA5G#D&%*^<_~CUVM5WPTChhs>ad?*149s1^D~uSAME+v*<$aiDi^#Tv9@O_R|jjvIiIKn?4{Rykl!;{acK^zIpgZ=@n8`eRUab zS7Kyv8amhL*!cb9`x||5X!884N8*ivu=pp@1TGVIatml3@L_8FuJ!`>Ie5v5zXtdt zH89n)eVe%?X2DuV{@8B(D1RFLc67CWmAdbN@7<~X5&mA;2KBcUAX!}^(;~?xjA)#6 zF43&q%!5|A>c%g&6Yg^*gQNcY=DXCq)oo$Gt&PUNV-;|QQ_{-6v57Hr$p>FpiXi66 zSVh^cr`Je#!J;u#p4iAd?D2X^fvsA!SgJIm<*R+bY1n)+Hn)DdHLv&Zd zrH-3hlT-RBu6_SCD?xCD=o6`UVZ`K1!XA*jjGmd5K#|SEs|Xtjj{xVoBlL*BJ9jwP zAA5(X|3;dFM8?_n>BPyZn^3?048aH3@(M9Uf-QVr1Ff)^7n%35jW(4oHh}lM( zEvh)${1lciN=3<38(W5kY)6|nJQ|i+U0Q}d#y-`j8A2mKJ{*HdrGCM#ncYaEj#{;{ zcPIliwF0hK6u%76OYx}|U>`L5j-pRL8)e(y&Q4K~mtP#HL-gH(60T_HhK2JcN^;!k{hdcR5hY&>`ha+v1B%iI6%r+^pH8 zhK>J{4HyE%5T0a{<IK}eqx0Gg&2+0>wxL< zF#P?gg6N)G;MmSt!raH@=3W(&FO~;*9(Pm|YD7O=Fa3jf!s0pqSm?}g#x!we{qE6f zEf)ny6K7}jZqYwhla{M#A^iYh7vWd8EP|OKXZXU2KFRT{Uuuk0puzgLw%E}hI^JzS zQ)(6<akHTqe`mERKe^}`*65p-3Wl{9`0@r&oKl1-jfSZ+Hj&RH}Q)Gv0^)%pGBq%eoS)3B&;c2rux09|Yqs1qn;Sn0^pn;mpR*w$5R z-uKP{HQ725Ki8nQmz$EDRr`%+DIc7^T&I9;2&GxXz;g{BsigCg6ET?IX z@t&omv$0@P({v{H04lIY3v?pKi^;;TmeZj3m_LZL)a-fQt5BKj=JS26a06(tRedE( zQN$2kT{}XMmWK%6^)vvZJ9U#BIfW zqEz}xImgr1pF=>CzvDcvykKs(*JXp%e3EMQ_9W&#&Sk2N{k4{NQ}Ht=u~T z?;gwzA?6)ZPvWwhcFUtXxN;sKP^pVXAbm{lwf?N+CulaDBWw|IEU!iU_qTX)evuUs z4}IU*T$8T)Mm&UjTwuREJDKkL&o9?GUBdxA4 zMi8aa49nVzp-o+Tj(l2C^&8r2m&R|3<~gyMiw3QG6e=4f1eM2<9b1IAJnd=iD+$u% zr1{WsXKQ5agsd$htLa^j>R9Cp{G*6NdWobgk$^6iZnlVAbKB20$>%mr#Gq~&7s;4D zK5@z1OrsE83|21m$PGZo%v7P6kuCxT28*Q&g$8Mw?{hGm&eeq78Rg*s_}AGDqU!hx zzd<9}>V$E;>jZ^}!OG~~{M7o~OLc7L`cp@29kzZM42PBd2GG(8zT%%$OvZ;tEc4;r znkFH8=t;Wti1|?NXumQbZ1STe58p1MtB3)Kh}s~sovbogOIbieC+9lB3XFMaoSx-(gsoEqU)9@$Oy z?ZwK6^>@9g3yrc7NUg*53#j^uQ5ovb{&Je%bCUhEva=gDuP(KxivxAp^Xxip@{zFM zx7Ft|1JCQLJtRPr4QU_Q_17dv)(eTsz|3xaKWi;tUqJLMUq7%h4!W1p1Sbtq?T8qX zpcZ&h<2wBL)^b$mXe~)Z97#%S)N*;g(bHztf}X@{$I}#ZP0ZrKpGw=1f41CRMED#7#?q2-L-KjGbuu zMusBzD{=UYptdl9F1+c9;T`svJmTq!Q2y@|_$;m$Q6i}_XYwQw0!<%JvW3A{)p-_W z7g+7-Kr=guxoZ<3kUVZ^_?VnU=OohCn_6L4?*VnJjX@oupmPMY_b^-5?yN$=l|a=f z3Iriz8DT(RUezcGE}_E~TPi1QC~enA-l3v8Inr@kPWly+r3$jRgdyVuDi~RT`rZ@ac{V z#rZu}prf}WC-3NwkdtAgv?+@!)!t9*c*_JiBMcj+${CDl1oQPRmp&QkoG2Lr@CPD_ z&t9JDd-imhcd!vr*5X!^mSiQUT`y@96?OnDd2ODuj9p|%D8w@)a=9QOy$XvQ?evzx zr6)thQ%-F&S#=E-cjFB&-4nSju-~_&NX%UIuBCclE5l;J|Kg#2s=E&fN10(ew!&Si zU-7CeN~vCmF^>odKvJ4UAQY-B2TYBHrJHD0SYevkJ=f{9B<}^(9U=T@idZF;f6)M$ zxbz5O9K}0Ry&p&4jxQxN8U@hsixRALQgq!>$gf!%-iB^I79wNR;}2SVDirutK_G99C$P%)kboraQ)ra{F)Q>tV?qF+Zq~Py$?>~Vc3%7}6025+^w)-}8bLJ#55d{zpTBr|;Hr3)vnowNQR)lQ!e8M3b7R$G9K{ma-c zaNy8FeB3{7iW0~-Rf_ZU!2|41QN1~=(z?JWmy`K}XFbt2X46(G8Nqtq=&o0VIX{>^ z_EE^zSLra&HrbA-eev87nR*<#g){{_QKyEy9*&Z|0Lcm1!Xn3hrxieKZH6Hx2jKgUUz|1;w*Y?r`JX_7Skh{HGJ%E5}_-Z zEw)C(29@Fb*QnHPo?H&H56Vgv?J#apTd~w>^ki3>Ue74*Jhg|;kQT_5b| zIG&wxG_>7Sua#^!fl>!8|Hc_B8_#bj+_t`*!uL4B6|L*-c$ACi4W`0^rHu>W%AB;~ zc-}Jn7QVVeDG><1>^PW5NCDahA-7Rxu5&C~)n_&PiG`h%#somYc9?e{LA3`I)+-11 zTBym_^J2fq5!h3P1oyc7fdTYvb)=)BT*mL{r(kU{%@h6H7(Lkj zIgrkJU_8`%kA5a`6>IRxdG2JI;VLmp2!0e(aeK~i*a?pi?u~>3@ld`(&Tf7u{qoR+ zNZ|P7C&0!m^{{OHtE*;!zQ4%hwD$1(^Eu##I*Bwn9t*HyBE{_g2hrSzo4^}gBfk@P`Wn9^)NvlfFbjk>0jOtm#bt+IS#qQtaHtTvacXfXs z6fjqK>;;I+nJv68#S|xoMUxTT<0US<2?G$RmeDG3pHQqV47& zEe{Omn0UU?HR!6R-6q4-OAqSWQWz=8-l6@g!}{Jzh#{ont?4o?HgcuJqTz1;P)pga z%#DBWZ;Z>ZgPgNVq-;wWC1UrDit|Xt8mfe5DhSYB3lzvFk7K96ACy&8M1CCAqnuEi zAz1K2t+hJ2&pcOM>J1nGj*#L#q9z!&Zs`s&JaP6kuDy$^VtIxLB(N3U5ZR9k+*}$0 zH0-Itk7=ngN;NMJ-x+OW1Esu6O2|n`MoS^1nn*9CQ<$gQ!Ps=Ox76KMzwYO z#Sd`yG?b7>%O~`G!Gb(UKCMWQ6a^@-4ikN`^v_f#X>!4;{1Edo2Abt0aD$$x4cq~RVU!2*hAunx0zte=W1D~e3rUJQ_bR;&IkW85g< zBlUeYwIx$@%-P-a5)Hdv2tbIgllo`cm`16D!nKONyGGGkIQX_87aT*zBBU)REXvUS zB<-Nztl6Dv7CEra{WkLjQ)KNR?WZ9ed`~^0G>(w#j!flhH#WZI!m?{x6khZbTL+jt zQ^$}bAxnmqm-qRFg(O%k7I7@V=HqtV(7SU~V4+0It?zn5XEHvYQcCtIJz1*PyLyas z#_)KLM;cCm&N|#J5!}hnJL^9+eP(@!Ai`w%M%q}M6}1@zX04dkEtZAEW3?N7tOkBH zdA>H74wkXraZ;QK1|H7PxZgC*QUdNmb-VJV_N>!pr-Zb4yOWt;cIJ+l`Zm+QZh8)G znLtrc=Tl?hMkL;!oqvrpU!|({OTdv$*#3Q5ayvYRB$gY&N5+SSgyL=H+KsUzA&6T*RV@d|R9Y>8=2wiE9svl4Vz<|Nwi%E6Tp9bu z()0W9h3yxRy|%}HPz(IvugVgGjcIdyLKaZU6933>G>Rda;)x5WqN~XKbK2z=l8V|W zx#dw9jhSkvI9$SG1i8bUBmp+EiFpReSstAr8~t%3Vi4{Tf^YdC&>dlmOr%eW(Qa5& z5wqGuVSSlOU>zzJIMlTBzgU$f_h?hY#rN%$O^V^K*pQvMdI-HreA`c6n@bfMSZy9f zG|(+@Psx%3V!bny9LfiEI=AzTvo|-CZqdgU#M#mKTRF{twh^HXkpLFar)LD$tVcIl zZS(wu%oHIEYbsrVWZNaAtd&CyzsjIFpw9S^|74ikl3Jc9Qv<7*f&9gUy{sho*zZA3 zuvCe{0=Bj3*pnKfd#?qibNRYAQ2irO2FzWLxe11uA9=`Rxv?3W?5RY1HGTT>-UcyO zJ%vu`70FdySry{dQ}eH𝔏~ekChFp}5tED0&`dFxty^vU<&mPyV+j9eIj(%i0m= zf^D3>Vc&IWG)arTcd#YY$TL&7LyPE5Cj`-Tj6|f6qXw#60#)G%pzlL~`Ry zw2gL@s@}z~&9FMU?2*M}jxw(8mt)^SWHCnod|`mo?j;TDS1q7w$yMzv5PT|i@EwG1 zoL=Aixl{^22n=RDcI-61I;|@U98rH7L{77Hrv>%J@a*~$#g_rOLb0(%x`V6iNHqu) z5(#wusLxJK%)4qAoRNR1+|i--`)k@VuUD`_5H$-T0Y-yWWfX0>rao`&_^m`GwV%OG z&cOInY{;l}{ss_vD-aS289V)tp_ViSDd_7~&^%Aqe5~FX@W2kF?whHWji8+w1=haZ zr*|X&n)1-*g%|%0N1Y@fIInh?dn%pF^`TzQxeW09a6bm|IBVtWAeQb55LO}`#l%5| z&zzR$w6jFYGH-M3GBY@acwMVce`EvA-X6ZDT!x&3SOM5mJh<7T z+oL)A$1}yyTPK|u!Bp~BMnY&`s%%O_tCAo6_V}-cjv%rcO7w++sKF~JbuzD2b)d23 z-TO7^(sj1EISX~ocMKs~6fibclHhtMknHPlEyx1G^mhBre%KRo8)Q`=<0WZNxwOiZ ztYd(%I#AQNN7g@#E|i_MDvV#{?fr86;H}yBjo-qkXAR5AnG%K>)kM(HIji|;tp4&3 zwR^hyyl%ANs*gz!usDyv}ypP z@tA7^Splks6VGFf5>bq4nF-*%Gx1I9IwNpbyvpB2xn1n^FIt02#vEy? zhj^7~p1V-#{(?L1U9n-rC8j7GoQj{=1#hNXU3dB$+xG8l1z3ny(w2o(%B1frIW)`* zZ;?lwkDN`>guz|^&k$@TWie~sR{z0^n2zv>M^6?VWly5YO4?B@R>L)H1(PB=!~+26 zsqi^C8_tdrCARWuWHprC&vaPqo-@oKGnsI45Zxw*G6|N z-Q|?m@Xc$$h~QiNuL8Rfv|E|1K(>Dw7+k~#%yZG9)nCmz|JLN7JWv}`7(iuMV0Kra zw1m&ar+9hP+Pr?!VS;aFAbZH4>tq1y;0)uiT797av{nICyrYmNMrb7h5aXCKO{@W% zpiJ;JMs!}2m+OeaL9U{m&J~W48r?*#PZHZLQezY~tEV+667*Gmu7E&6CiXKQN1`8Z zK|LC!_tIYz{UpDyW5Od2lG_eAlyEinIct>MLij%0bXM${qH^AYNjRc5+4Z5cf2StK*k zF6iu_VMNA0=cw&%ZI_@Vor*WH$u{pcMpdH*)Pd-6=~$*7yYGKP`$3G0Vp*}&v$S@u zehSNkgs~IhQOcn4rQO^2hzrm+B_2xsvAH$6cpy)8+LC+uYEN+-V2S+N%DHBi4ZkQT zv3Qv(bh4Bh7KXSa*0;Zp2&&vDH7YmbRmEbeo|sH%p>belora9(U9C_S5Oo*9{Wf53 z*pWRYdItA@QT)MU9pl^r|C#CuqM_tiAY`+%j0>-Jz==KJV-~kEF938bfo3>@ktWiH zwF8mhmEQ&t)my+KXExo^q#!-%%KY=NZGE|`zjMiIn?tX8>OuVF{PuT(`sR(+YeL0q zob!^te~@XW6O)6PbhO8MgsfZ7qWkou8JAG-_+EUjQAP4GpP^z^S4D)bT#iNNfuokJ$?U+xL2;Lp^8_Vb2KNGUjzn0q`O>FnPt_?y~w;7xY`ncI#*jXB;>o~nrZ@o0=JwfHpjl;V^f9HQRd#yc>Z~)||C%KDsXhEa2gkd8^GP!o($$1fpT+|0r7VR?_w5c<$B{dQHK;L?Y;zx7nH17 z!e#n@uQhl7sP`;tHh3-(8;@SfTv}v_*_`W5 zDGr)fpCrrh(%Ds@6ea@P1{{l2P0b4i3nq1PA^_a|BQYRQtR@kXN=kpDDzF|{n!sDZ z|Mn8yMq|zx9dCZnhF|f5BV)XK!$4+O@PU_$l~KLKM|JN5d&|bxlJ%M?^vY%W7_~?< zW$8zfw8tLu34sTSq*fqHk%kO4iIieqtp>ad(J5n=WF;DzZK8Dj#WKS9@@H&%;a4w; z6$WUykj$TBSb|c(n99oyhSq@>V@M8?E!YK7?=vf#W&TOAyGLiTbk}fdGq1L%c3xz?$urjo2vJ_Mqye;05SW{GcSH%nMWv=&{CmNwK6_Xg2w$!X z`maqCsr`LsR01Tj;io|yX<>KX=3)5t26uOFbY=xYPM+Y0lq(_(MQj)LY5T_2hu;sF zda_JE4K5V1#`tPhDtBUAa^^H112-CFP;Vhbd>yf4paWwqx&$_@d|$VggEvVRE`ad7 zZG@pPfGoAWU(V#kBEu$tCuauQ2sCGWyu@ee(kcC91NnquE z+QFW3g)QmK!l{OM6$t@~hBoG3ei0SGz$GBh2LNhRH?ny2yzr&^$ELtFTS?9?mm66` zdyO&ch?3R3!ewZV-yU}47a&?$EdWE~HCc+>&r~qjC)boa*LOcqiYa^puFw-XA{<WgVAgLBB-)f&-WjZ}Rt6 z11+NID;G%OCZQ3UGYc&&Eb?0IPysP#`FhBPnI`B({DLZX4^i6mE#v%!l{SN^uZi0f z;ukZmEf)QQ-doH0wy;7;|8%H8B>Wn|na9gqHvmAVPdRQb*9=0tCUTj5yo zaxb0C0pYF03@NZz06;&YNb%_X2OcR$z0MQg)EOL(bqcnH~FTpo^O&t2SVgR51WLD{LC;9Jp_B+RYmhM-GI z*GKpsk#pxe1&cb>-K3W=gW9u_xTw%cSQpk*SmD>Zfi83LfPK0RK7dpqP72r%{FV%c zt-1yLXgcEr>Sz`*>anJtEi~_HiPQ^pEHNqUsvRWwG^ zdf3NwGaDr3*Yar$8rqzg8A^0RIJJMfD_0Bp3TbG=O661{mb`q^j~E^U~@17QE6J?+Gomx z#=m-ZQ;;_s!%Z(s{!xIeIS4~7Yc6T-!biG1HBru8jqtr<3j>gAJ@bYBK^>tzFsA>F z)c1Fb@zWssY59eFxWS`WZ+@T$v$0ZeHr@co*ZflW?qF0zt6+i0%={N5HuU&E%HwjS z{BMNyUb@BcB5i91_EO{LnO0Hx{P3+FsP6CJ7U zm|DhXroqD`I3d7-_7UC`wxamH*S$o-I=-L|1$7vJC1H~ZO+|poG5|Itkunlpu$<#)8S3jHOAQj71Ugi?c*Sf^N{w@Cr zSycsC14=8(@6U@>tCwN<=_7oDZX?uQXKn(?#aiiY_SwCIcp6kcj^xpa+oJF#r+Ca; zgKS-|jx*jks~Lni9WBUPgEF(gepEi=1`G+DKs-* zVBErxZGLOsd@4|fQRFBJjFD?=Sm3*X(s~0HPDVU4od#g(U=E7~x z73)lg|7MgFX;6c{dcIu|(z^>{e9ObU{P18X-*o4uVOm>zEZ+$r#HTLTw@U<$=VJg` zcMxGJi95ndG}+$^ns<2+cz3tf=dMe$cUPdbSbJg{Dbl7nQXhv^3r?k}ya8aGk)S;w zk5D&vwt-S=4jAV$VNF$n(uFLP47Gw2b6fXozi!h8{)|@uY z4z@SEoulWWB0?CtG_gG&lMH-}c-7q_n)JZwzP;^R$52TD3+786gFA6!62j=H9cL4r zyfQYRm{}7^iRB$g=U2JiD2$4ODIesizB&@JYeRF9xnw&gX6pq5DHso$;&Fgvp%f<2 zyo2)g??orfsE#x@e=^$6EE*_kZ$j$D)ua|?-bW6B@i%)SWX1`7mQ zig%JhD$ND#(vSV{k%<03X|fTyEKs2N_m{D@hd1h_{Z=}LF^=z7sv6yW5tE~fk1%S) zjDDrNO>bb6pqz;q+5yLD?3{qy%|EM28}cfEIWKIT{E85;PBM(Lq04dmop+q%a)?A`*6zDSz74I|-oA(Wl6vS}l3$`OV4O6?NKdom;J-%^0OKl5dWn&?81 zAxQCVv|8@@M9gM6`*N7R^xK$If1KX6 z+^N*^M<|-QI!-RjotF=~u{|qjo$Zuo0pN0IM;;aE?R$WZ0UFdFbUr9OsxU1fn8l4> zXaUF==OhPr+`RQ*cJzRlza)3!clnJL$BmxrB5qHQlnwK`(988COmNF29%$fZEY4Py3du_$eHL zK}?bf&%#|}m$UcZ62bPu*x{^LZ~S*EagCEfe#fKl5*vK$7Zn2h;qt*NzZj7MhMiGr zq;llt*d81WreV~gH_$eW7}30i4y~smLh$0z_PE4PAJL774?MC)Lz7zHO-bDNWxD`;r-@so117_rB>=*=U&0oOPt@oa-(niAw6@ zw@kPP#`i+bDUSe)+ioToh7d<%cfkwYPMJfQ@L}eTx^1BueqZ57PYL|_$T!}xh%4>H zc9L^jkiEg>FPFrom-VE&SP+6D5fP~TIQh4`FG(nGyODO}@Z;U3zbz2$AfbKNFs-V! zYh>z21aBxK`SoT14lkyKxW+$@bX=CF4}HJ9;Sl+o1qA^hmI>@60k6$C=~0b8;ily3 zAoXMO7WrWNN}|kckFEfz3EUMSMK#7$Nb*gX=3?#l`U5{7s$_!t>ijt*Eqkk&w0u- z7Hi;VzSsc2OamKJ78(Wvi9v*WM;k3Wk5ee&w6(3L*zVkiZMzHt8kzLI>s-cYaQzpk zlayAO1%h*X%t@ebA2r(SNxAE5c>>??EIu-nWfL$NeKO|UbPl31kjyVS|LIZBWHr*z zy8!#sX1UY>&y`5G{h(t@+YlLcNkMP%1+@9e-r0bQD{0nMkN77XX0q}VZ(pK82+>A1 z*@4d}N2oKx5th^zw~|G%(98J|t-GZmQ>Q&K5fG(dxzB^en4Kucxwk)k3-46v74ji` zdC;N6>Zr~^HuC64yYwJ*uSTaq!S7Mh#WZhLVD8EHB+bu!K4^=hMCkq^WG&|O;X3N~ zKB9oLqRxoB%Vuow^98W$?4*u}O4dU``JB2H-{din7PHILWxdUSC**+ViQ4J1gn2*es9dl7c+L@2m-l#YR zC@0dy>tYzKY$z#XcCckK=1-fUTnLEZtUSP%uB6&jYH)LOeBb7gjglf?Sauj&Sukw4 zr6_zGOm0rQ>mF%?z0=pDnCTHy*hY2KSpn;ZJ}UQdX5nRCawi@Y*|Aps4TMz&xTK;d zu1cZ;+1nCI=iB`RC$vTN361yaZH=sd-e(B8NZ77l4NY2ZJx`&QmYvEkOfTe55LJLU zC6ASBLf5=br*)=8^w%1rbs(?gbcct=oI+iA5z>HRRTZ;&IIRtJ!Z&C8Sb$t%J-umU^nwMXoQ`$d+FJM}!S zTw(GG;mc7I(Una3*Dg(c*;Tcz-`s#0wN24Y<3EHT0ft4?!M0D7BK^EYPo2|`I6+%h zk2P2!xU4N;&tb=zNN9Gpq#q?@u4?I>8MYeNI&!$Cd8X85&cuK7Iqlq*_ZE@X^IrM} z@Gr(qpWWN_CA7j}I87=OocXD5AZ58({V#6LS#y@RIH$#+{80{A9WI>iHSz(!$#qZP zB!=XD2jHz2S1lj%(4gz>?7S7A166408t1#zU;MZ!%^_~in~o_yIg|Z&2JWWBt?pE< zOq8ZLD|}>TtY|V2jb}+zTIGJ5q^G}#^Gg;aQ4ALcar^O&P^emJr#kn0p;XluL!$s& z-?Q51GJ*z_1u=wlCqySkSs4MUqgLNju#0|yUovQ^;V|QiaciVh3S}pUw)-Elw`1FI zgLlsx<0U_JOU|!PMSomT-yiL0uopCi0jA~x;OqihJulWFGCgJSO@cmDc-a-#yv~1G zn@Vl3Hfm>VVH%!-T3i@SJ!+3Kd}(`T7`!g1aZZX{**H*(GxeA7bYlQgy&_Drm);ja zVk7^AJ6N87wc)cg;zWX^?4SX#it0++fu=H(T@F}OcLkOa7QOLH!2=xNm0k#o-~hL6 ztAujE6p^c*U8f|}*$}COcEzt`B`t5AomA@B0ZF%v9-%O(Ic$2`oG#dH`RtUXE{cez z){XTb?}Q}Ac-`C8oOggLW>4!y(rErW6xBwQ3c}be;op;i!|M~im<{YA^1(4PUzt75@*E3uHD)4@D0Z-~znqUJX)8H3L&g69hxX#EsXD*lfh<-f`F_v*|56hoA0 zrG8U`I*jDbOa@@esw7!2_74rVY{oAf4X6!vPPU`D84HXG{p4*J?9i^aU#-JLPNyG> zc&Lp2x-??GwG#Z%4>@FI9D_PXYc&0o0(`Qo#yj)lnY;2+RR_qQmI z^60LSh7rJDAI$*c)$`kj+#u1yI+TUB`HaeFwtBTjI zq1F0Cl638IpUn+{|H8cOUsg4zZqL_2lOk}y6rl^Th2w~?sn9j%74O@i`=C0M49+t~ zF02a?9CMSBZ;jd~(Z$#mSCPKW2m@cdG-mMAC+mws3@M zm{mLHX{tjOLV2e>w4&TMQ)Bc)9e|~}tHM5G-uD9v!EvEsUNn-=I|G%(GJCAn9NT%- z4;?^byl(~l$|hTOG*P=JG|pSl0gZ-&z(dn4YSIfQTj@Qe9^{Jq`WS-opc z%L@^_+ca6%-P6TLd+l*7jSL|y{~BE!{3+Hh?(RqOQLy*YIIewH|PFsq1>i!=hLAiVL-m>`U zKzreKj{ySLl1Dft z_E$nKt>ScR3yv^4C&dyLq?y4CpmeTAuB-vACE9z%LouZ|O9>x)nDY36lTkdda~42w zR#)0ns)u>9B`8PBJ2yd@N>#aa+@ECr<(}>%fvkUG0dhpT$%#mmNAbg1fl^ki<_4R8 z>SRT-SBUGZl3!@d2K&OQ!KsbvVR=jFEK}WLAn3`RtH-my#^^xJ!cL6^Jt3O1q@O*L z;!VPFpp{Z<$)d)q(tl}jdy4yBgVzFhsnt)F-{ho*Cc@TLz!IkF;|~pqcI6a{m!N>X zj^b(m70pqM2ITtRCC}9Y(S?du2l1wIpM(m_W>2cy4wRRU-Dy7fd%_c;Cq0(4{LM%` z$^phG#`IdCfV?w`N&bPU=dFcB^(MnpPo$m z!n>+9P6QJB>IB+DFk<2NXA&t^TtPWS7+v1Ux8d|zeNGmtP#S3iuuwJQR|fUbHb!2E zi4CDJ137q1oo1IhO1xD zwhfMqKB)KL@=g+K>MQpxYm55$?Q)Sevike-W}B4xCD~KYSk_vPtdB4v9m(@MZ<^qlv%me{rJ zqI0D zQrL78syaxacPB*4A7X%2k0c@shk!2byk)NPQ>; z$rM1Lg6^!cWKvQ^ka_L8_xb!3{CAM+Gz`b-PI0<%TE>ZGZ~_1{alk?MrEdMxe*{kx zHB{wjd1wie3K473D?lp+7hSol)(8W3I)?(?v+d%oV2`E^g#xc-*tlkItS3g62&0p_ zT(X0hf6KhSWJ&|jr=_B0l&B|7X{C2He3}_*au)q0o`wC{1nD>Rgk_wcvWb2INw?l_ zo{E-}`Y5b|oCgrIXR4irzyTqJ`xl;aKF2ZG6)d0Of#1WqzH1Lvf_3Cg8#M! z??4Z7$rfh>`kg#Oh|cV$i=Y+KI&qvxEv_qd0#Am}T@29M!ru6uiah38+e@U|CPJcc zbtkLA&t}ba8Gtp;0B94c-bt^?Yp-}9AxXJHUkn?Y8fyV(XqI4PABQo?bM!ICY*2BT zxpxhtSg-Q0ZWGDP9L1rkfQyvr(7V(hVYLbe7aT4mfkgJK<=Yuzxm-tH_W+(i_$tA= zycG8y?*Ohrp zca9T)@$YLiVn#phWeSqG@HpP)xxKaDc=wpkY#1qviT=JS}$$;DAvo17F zPCITwf}YglhYy}(gM|Xqu~f!2bdqpCjcIu9X#m)VRxwwNJbCtG>dp#s>d+K(mc|QL z?=`iw7p9$rfFxHa2&e>tiNI~{3hlciOk6?lt9Avgn}Q3~iWg8MEg(K6(f{AwqA}ZBOvu6MHPkhyjO!y44hn5`W^n%ZGDPuL}N@y}_ZL9ou#A^~{@@ga=^6z4h|E#yIDoHl6%ZfK=V~f8pG8 z&JYc89(XGxyFO~4BoP{6Uu>=JUk!Fy>INiW9OgtuhrClI%frf>S8Y1T=0}o&g;|i; zvq^9Eqv2WsRpDM)i>wE?ogHO$>8yQ*C?Y7ZA4~|0fGG49`C_IbjE2Y`Rm&dh>tyX( zmr#?pf)!Ci^u1J*n2vp$n`_{qkf^AJ;bL4_DjG{Rgv-hK`0zr15@id(VL0yjX#%`W zP4tX_DPIbUpc1_5lr%c79v=mWyTNyZ`}xz{a)+ywU)y)Jp+7OHgxB5v{csnXY!-nG z2VM8|VTq|uC3w5GXh{MOfvD>NOLVba?$lGBhL2a9`_VlI_xXQ#zevPw=zN2@KcVG% zoq(zRYnU9Ye!jbsWX4=;tBZhlmI4IXH>%>cjvmEs?q@Mq`q1`p1Ib!SuXzc*$PFqV zbG@AzBnty&#D$uxAw<`FM{ChN-p;?$jw#Id2z_IW@<~^M50R!{p(0y(vT*9ue%}zdf~ZexwuIbxTai7)#5V{wH?|&KqL2tArSF+jXV-6OaRShg>u0*t zYrbbcf6abWa%8Mb&!3)q#pi z0LDG{vgi{7q+ z40T~(lq|R7WH#N#|K5rA8URM!Niym4Z_1ObJBe@J>5h^`aNCHtT*G_uD?w7r%6^Yak^33?xFO3cP6I!#7P2BFRG}nkUx}6%|?AWN0 zf`b0g6vHwHp~sXNbN4y8p%VHGImIa|Z`M@E-pG{|um^LuloZ_XjsO-&qAEJe`O@=< zc{o0Y$oV>SUqt^dD+PccqHsM}r?LRsg<*_JV!4sVBt7ZLic;!GWQV`2c|C`!$2<5M zjPanx_)Yr$?zH*Fy$y?hc0#L?vO2s|*h2lhJcSMpWhJAJW)NkoqCKwsh%yL#h?Ic~ zlkHalA)TZcm@KjqMF8xioCYcH?{8>!1|UNGJqRqMs9Z5@ZUW`k@X&oN+bsP(@zqS~ z8a!531&_@%<(47WcnjV%GSMzp$IRca7y`Q*<$t^5abYGAWRsXrUa#KQjV+5gA1CI< z4VEMIAa}$TV5iYFVz_G>nEkQaH1;* zL3lZ+V|u@-g1GClApjc+L| zzu@8Ju>GZzArh6(Us}c|UsBEMeB##Y=4G@i zHeS46nH~%s?mUgNh|oP6XC$#dH(d=WA^kei75qYvZ(t5JO3(pXu;0SPh03&xEBJKw z2q@1vh7`h4?D^T+?s&BDD&*4#Qbj~cE&TCe{2!AJ zc z1{x7KEzsRUCwD!W)3JZkW<#)zAL2q>}WOKUH?q8z5_RC{d-OjpEUY9Q$@_?vc#lsPW$utoEUpGE<@xgK7Ax-I@ zTIePZ)!^(^NFx>@4j&&pt3teQf8o+OLmfebSceFKm?*cksRFknY{_}ckH zsvQc!s0g&?g2Jp14A3c=HM#ex?ufi0QSD|Sv-@kCvcNpxE81n z8zAzZn?ID$;F;h6B@x6KdE6Ng#PL0>86*#Q9+3#z=ma+y6u1t5PEZlEC)f|Dz&`9p zrgR{JSA#z9r)FYG<9>w7 z@}DJP69ws?e~he+R4VY`kibQP9A|{vCxJm=@@Ru&TazD@Pl#D5?8kL%1^__)gD|}b zBoAZ_D3|df2yGM*g!ojj{$f=S__frXm6Fo^W;`4J&wW4}89)PN?KBiL47y96hj>k1 z$A^;Ie`jZwGohCT<6hqOkjE(pn$(IM^)f}COi!}(elxW^fot)E)q$v);aMas0y5Kr zD}3>%@qYS~eGyQ6w!*zTB|UvnUH01EZxi2qJqUi$H+RK!cV}k}On|+2TY)jh3?m_V zt#X24^%YorcRECRZgdvG{!*^Uf*jrY03v*9JNfTyYkpB5_5J~tCqn4=(hN?4M*5#x z@t~4m+rb$*MN|+80@JcSCJsIf)tNc5>9E6?8nF0k7E z5(aiI0AawKaC5+maMShp`BnN66ZuwPrO95wK8kEII@CWjgzWY59}Ft6{OL=K9Ja-| z>78AAO@+PwVB+{AV;9wackleY_}O@U=jRx|+!ohTDR*Yhli82O2a@Z_Djo(1$Sk#NS=(pr64y2~dd#*j689sBqg zawAENT?>iOW;144f~43YcQE!jKJG?z?gwOe=4OuFaDM-1&(GpR}XD0hfk+n-AJ4kzMZi=zotYxMRaMxNRbZ=v}>k`bZ>XK`3 zNlh zRU?NG)IY>jG@{2Cbu}<$$Q*jC&7Lz+IJ(vBbHhureuq(li26`Lca$8})Kp&G!InF` zVlGb(T92v*xSToF!EKv=MhMkqF90$c+s-GD)x4j2_~E$kzv@mb!U}BSF%NU{^?93D z!aA8!arc3=QR*}Bk}q*NKTU+Ly4iC>S1t1@H`AQD&&@+Ws?^c=PG^|c=XIBY_WVyc zMo5(}j{;h9BF<`G(ZwUbIcA^iN;mjSS3Hm5I@UbChxD({So@gBdX)QWt{qzwcc12l znpp1>6l}2jPAUvve=yK3F-FW~BV>7SSLs2hX?6fB9?xw^zs1+*D3qiFNO#GU5EfkJ zX7J#^3@W2f3hb7CLN=$-?RRD*x7*vK{X+YV*ysJF(8N;4S99VhXPCNn7QGdc_9Jmp zO!75|$uw)%QTojgr zV39qrnXpsT8hXAh6e+;T;<`=m&(ExBa-Fz-fNgAfzH#l{I`|#z-g{niVCaMxC;COI zzTRj#)^>IJ{QhEVM0f=H#WDk9(FK|I)2ct_17`6yoRA}>!vkt_R*jRgb`-U)@q*;u z@Zt8ny6(~)e8{@8rupfc<4v`GiB@+SjI}xN#j#hid7rm^IM0(++M5bWo(^JD!Xwy# z<2&cMewm&))pxiYZNd{=JilNi+kK3Pz10R1_u)7;g*5&(bxC5c0W*c0QXjLoeU$00 z=zYv$*hz5*mACnSj)l3N3|MDUx^l$YC|V8=8hdRJCIBA!D6;qieaa^8?jFb%yP%3W-B&WG>g6i`NRkp4Eq|Z5 zb(5+KyrO@*V#>JlfLH3SKBDL79lTYI3#r+DvASI9r9RSiv&uF~hLM~1XlxN;vV73T z7@NrO$(xsisAy4K#7Gn)lVEB&=|a_9JT$Ppdr26SEYv2opzobbugYK#+N;_F_G3jo zQsQUvAG7}~{Ie)_fdW(dGv;T1)wTsq#oMQ+)+c0Yk{<`0k^Q{Z_gIGWf`cK%XN1Oo zZ5GOLG3FDH#1y92cD@{Bg-3Niez6t~=yH{2 zv|JfV16yWKc2D1GFXH_r(yuFoV+Q4H1D6yXqV z^lW!(VlfTNI%-sO+it8C0>vaK)4a(QZc9>>5>)n!%J=SNPs{jE2vk41LaNC5+qv?J z5lRO}t9=u@J^4PbXTd93>-(*Ttdk5!SLH4#0Ut0d6l59V{!xW=4?<)i} zsxe>Vsi#RRoY9=V-EFnb&=#LBA%VA%eYO-h`%EU>y9q2+AV92Y06TF7dvYP$^eMNA ziv-y}Fy}4{W3RBczwM%LA-tOee zy1ubi9U0Ti?58HFQ(*!`<4{D)UVIjz_ese~$wPG1c1b%Q;M9dE+(vO0^qQ^DnDx-eEATetf^sKIEghJOXKNchRz#Ac1D7`?9-FzS5|gIMx=q14_sm5wT393P;(!_GohnA z5MhhK+fHy>OujJB23RzPKA~z#@}2*mTH$O0~R99y1ZdnR$?jcGb*36FS)oc z>W+FEN!}_UgXhapjdd?le$#Cj7mDuQ!DOoiEy!pXn;^3NE!ym4E#8cM3zFuDR(z{L zN;7ZsN3GX)u8fsEZuFBsU8+lRGV{50_>uc6-W8$==Zj@mI?Flhe^kwZ`{!-|JD(2>>P4NUuQS>#trVOD?Kr#+!+&^Dgv!2Ba|OCBM5{_;fPHa(pq?rT&A)@kf7D z;m8JN?84P)xP{s>WaG7ir^px@;w{by$#hJm-L&h@&CA@*7t<#yd@GUCvcft1554%( zNMzb0bT5s&P5P^Yg3I`KbFs?K#<`qzQ@V>P-vb+LrkqS}Tve5vX-WB%tc3d|a9Tet z5bzyCMmK5$E+H~#c@e8~SPK%IXh@T-)n(6{JD5dLp?7w#N;VkwmxCb;^(X{I+^RCs z$jxprU|v$OQ8V~idC3e%S91OVw|haet*sJ-Nc%)R!C&+VeRdyPBwt;Ajjojv60w~l z={m?choMK~^~^d_wJC#(=85Z?j@WWa1w3x(L`|`mar6GvShv9YeAQwL7gILn~hm(9ae~9$NWPklsUsI7-wiN?POV$ z(cEheT?$f$aN#|;OmwOhhm-JYS>el<+fc6P571pDyW;&kEDvC5a-<;n!KNMlG&!{C z+yq)2st~j4J8MkDr{O7$swCg+1AgnRYRI?1_RM&>Zeib6cufC#L}O--ptLoYvsK(9 zsN8K6{g~x6Se~Jp0U5q^VHWE&l2y>6eKO5u;H|C4*N$gOuVBiv4m`$zTknFt z@s27cr}e%P1>L+8*H~+ph%gZmsKWY+;v}vYmL4ZO_V@h?Nh_UP^Fk2j_@<*FAR)c+ z1Rl(En*xJO!HBawoq+cm%X4u}RW0mZGC<;sMbeS2&!IC5;E5&AVf$_KDy5I$w@)*S$Er6o*C*3E@HdA%6rDz7#K>LFG)Ijlk*(|9Gy1isqqIXtCgPca8D zL?zAa*+z@Ejv#0jK&~~|Rx6q=iR5bPe+{a|#1m~FD!-BWK>dz6Ix@CGp^iEe+UV|o ztEFiP9gi@Hh;TU(!qzOf4lH)2)4FUL@Cn%*(T38<{E@bWjKKaD_sAM>#iGA#B`8~3zS{DB73r$#wZ=fIK7HY6`>ntp8n}Vylk4sS(M%S(Y@NkmEh!v z7d>0{o?xHg0D$kFpioUhfUlB%CF3IPfiWwNKO=NXbHS(@3iI@5ZG*t^sxrgtL5YNJ zdb3ypjoB$T$rOGmY zET(C#u;{rADUS2y(uLd%VyxL(yc(qEV%3ZRw{fxe96vIwf_34s>FR7n)wT!ZE|TWl zGJ031H%JmG4sHWXp>XAq>@yn6nfA|!RrBwS%9s~5MxGbK{@=ISuM}{RZW^WNRQc>) z6e&&?;n579f$ESw=o-s=d*D93qxKwx znbJa71G#yT@VB)j=zcaUDso$gdwflhBfb7yd~ zQMDC&g9+e_`T2!;abZ0~0_z^ra>ik)jkZ#SnELS;2u58jj zCjHP!1fId+ZLP7pbjlU~p5<*yp%WjXyE1bu7FZ}^?{+w&N;G2}7pqP7+_{DweO$wa z=LhED#5s=|he26&C7_vY3wTM+%*RDN5df0!C1vs=ud1i(eX%)K6|BmFMf3Q(Gy<$wze47?(MhW&j4XcKn68C3BjB(*D;^%*tNfBFgbBhqXG`g?M+3&8fVFz8Sc(LxqB+Ss-`Ka^wNgBk8|B(WI3^S_0Xy0o z4q8^{)%5Ym6?yu7GLFi#;1l)<=gEy>F9@WWy7N~r*`9R;jWkhjVgcem9~P&4^8Bn( zSMydMJl5T@XS||1W1McW`htsqcaEF%T1R7!Rh9(Wwx{7s8z;Aqg&V0~5#-t@D}PfD zxEQavB_YW$>}`_;X^|GRk!3rjfh{~6R~vY^8)F%x9{kK0d3v$;cqntZ?9Wb$@tad; zVDTmN(sRwdJA#QaCjC4cLZ*T;yt&%{{5I(ov2i+hur{YWm0jtgAX!_g=F>DW-|0D=TeDnzLP}MA z9ThuRz~Pqc%@E77SR|Q|5v7mBD@23x>30Q!&Rf@0ssUw5a7x<=E3VIKzvbpDuj6); zEGTJH`!-W{-Na;i783*-;4>Qc)`DT#y*zqz57sv&6L0GhPk^ZSq{WM6$!yb#;RQl0 z(Jkj7N!8zFc=hnriu)=86VH}sEX7Kt??I$w7}_M>4@`ZFHTN;Z?IKOV2QX)SQq7tq z@L9M7X8$Tg?uj6aPX!onz5|1KL)TI)=wI(qdBI_PPY<^e^BH3zfe%+2E;W%H*-s^v zwB)nagug%;+sP*-YubMyd|JBX-$71?7kBU=(W4Ccl@uMEhG+i}=<7B|Zep<=)s5+) zTAAX+`|(g*XM&-)fqI|PysA%A`Fg()f~ujFP!zH*PmWrJM=UO>GZSSa++Sa&bC>y= zyiR|IuljGRo0d0Zfv6J=gOD%N2sb0*Uy^MTtba zA&-?9bfuR1@#q18k`j-I-T>I%RcL+>8Z)fdjMrtX0J7LA!B6)zyp(Mx-`iJMo+GuH zOG~?Hx-3^2Wd(Swuvj7(Cg&fWUP#{;ZXvVvTb-m%XFNzBfpVwiecP*ME^+!!uBJnO zquz|UcRg+UYvYlKV71I7q#DMyfaHJ#Jh2(NE1M;=(QzMs_ihFPBv!yi|82Hs34GUZm> zY$2D=GzzfNq>+Ho8PS+TT0Fj|C!ASFs0<5 zO@QwB{iQisT~bY@33~`ArKy?8mr5;dGD{z~N}FE_DBSSSsXyU4JbC`tX?=fz$&T!> zlK!cAA|gj>w$P&DG*h|gNw#&$^5NyrfCW*1xI0i%k9f|W;)+5X(jC6(7e+=0$0`o@ z>^8IpN?2=!wq#3r+_VePw-ZnR;fAtY2GCT_v?}wE z$@pd%pnFR1$f8+09#u5LzPuP2)(ZndtirTGX7MUYmc!Kz6bwhldPAt~G5bv!TpCk7cSD_veh0_oER4(A2k6$_=_MHXE&^GG_P&bv_9LCQcT4}EnJ z2Lkoa^}K35qU7DIml6nH;DYoL)JlJh(W5YSnw0g425Y}dUvTrQ<9C}vc4I(xIqMw> z@b+#A4*jap;cY~o3UY>bQNVCo*@|pCg1X}R+7FF@8}w58{3?^-AFmrL#shzednnj< zdiSgrdA)TWacJh%%tBm>3on)SR;b-;^mY8}K}2U|+fE`j2Mz6AcWSVr^)v0GR0#}7 z#z~-kp<|j7;}ctKUcF~ivYh-Q{Abut;N8dXF$=DtRRd^{*b4;q*$QCYum`2)0G_O_6k1_DEpdww1*LsI76z$}7fWjx4Ze8yg+_`_Be%=!z$fy|}{ z_|xG6AH?)@M@Ix)YTK|2MB=H7ni-3|C#XdK;zz=$*`q#x9y^NnU06<=UglA)J^RT8 zrjJ6KsqMI+)cJYEsKR6~^iMqXNp93#qh#Av$BG0mSH4`3?w;EW;bCa{q8g#hk(v{= zKTD5%$rF|}!9tFj2f25uwV>uDFqtGdNs>T^R5TsG&RO6Pf%di>%I<;fi@_jw`=`uZ zmqW@j%?HiBr87(y$;+rg==>7dCc#Y98q0n_US)ycLwGG)zqZ|Xrt{x3FZX6eJQ3P| zvl_aPG4w-M^mI{l_w#$>0y=u$^Ogi?=hkY%tUnYiz};5yF3r;og|)@8jqjn}8iX8a`fs!~-8r%?o^5$ZKdJ6I4Kur> z>WtRyT1KBr54L4|mpOkNGcANP21^v22{r$Ptfw~LMTyUkQL}KwHVf!JyqNU3+z}tQ z>y4Hoc*o5Y{kEiQlgl`u1eAtkg!2%kQ8&9U0sGeKcyj-iY@pH;^AjGg>KRXE76P+F zN>i=%)dd%^Ot9-lJT9cu3bEnp+moH3n1q)>e#f+LEN)=JOHP#G^(UxDZcl|j1Qq{) zQ`S?N_W)I16N!X|qs}AL&SJ0egsICaj27FGY3m0{uW=c`RY_+A6WCe>Ma>pEUY5S! zZjcD$kKy<6GrF21L>>n0690G z*>Sv5zr|#`|5hpI*^9=r9eR)zYZfSz21{UGe8UPuLb2^yGG>jg4m=U;?`3fgObVIc zAE}Y5ZV!OW5k=(W14c4I0e3dIO)5X!CmM88q~}TzO4riMH2(OLcS&6qY8a6#w1`R* z5$nnbv*w=T1-@vkpZ2FM!kD|{}t(chL7D$QIor{+Zd^g!mbQGNT!(4Sg@E6`MmbDvI%nc!wm ztl8~){QXW*m{|LK61tPsXw9mBI#vKZ9EZ@ZZ2gM2EI`#q5!mRIEwzqdiXub-_=~BO z^J)4{)O3PR!np|2{l?Pv0!<=&W#Fz!QE#l$`l24U0(5-bANLB?i51zcoN;4G9*&Gi zz_`s?qM4>I3`8cS-M`xW9`t>;bxk3hg@^->UrD2r+LH1&@vk3jD9H5THW)CdugG#j zA#v}JLA=ee;CMw#30EaomKQIgBaTN}$Y01u{({%Nyper^JL<@z z!}q}h4yzy_hBH#|z&zTkn|JVOInQPoW!N?emj4u7DJ>x2jgZ)P&M|i~nsU>f+D=!) zpDHRWUSwwNuHlaO6{et$^YKCr>Ty6xJk*zdqy^R=m;WMg`)xE#vHY;kPDp5AjqwU8 zm9V%rK>KGGVkS?A>KXR4D(h~}V?DV6&cTTH7ed3rNNIabci}RsliXGmxUq1-NvF1g zdw@l0J(C)7p-PF3UxsG*z(hC+Cm9z-znDC01*C0Qx#$L}kx?IG0(gngw0k%;tJ*$! z)En>ujRNZn-cVtJyb3o zja69bb2tLWoh|uU#cTb!ot1%A%k{xECfC0=8M8XJ{^13v_Hzmn$NOt~1C?G{mn`<@ zS});C?W+BsP10l1w>WhUb-KxNsS{C>)iNN|uu4{~kh@Cg;IY4wI}F6WWHEgN{%~8AQT= z!@O}k5q?1ZB6fC%%xlP{0FU^i8>)I{)6!x@2X2dzNwVr(jW+z6mDkDCE>mV|$}kPg zXCvSg5Y$1uZ-yiV`G-pc^_Y^wH}b6|f2cAtNKO(9`09`d%2Xc>0Mj;kuNDSw@j)Si zq47UzmK?^?_vO>hll6rOk%!%LWVIq#h@wnMmb(|_E5%#r)yD1%`_p&Xun}|4x@9S8 z5LkyMd!B9Tc7tE{XZ5|?4m;hvQ2>J7(ss-x=9j6?@FIPQ@6}`Rj^R`oVtMW@_5G_~ zB%wbrQvM$l5Z?bu0m-1B0w(}x&yb!1r(k2{U}0lpW&MZ$VC7+C;iP6^p{7M(R&+9# zFm<;8&`9vHvHTyBjJzpuSs)`D69*$J69)?uD?5Nj!$Jq3VB=u{_@`!Lmas6hF?FN` z*g2cJTf1490z52S-E5p30bES1Of0krLP7uwM{_4LTLf0t|3)U!@OHKUFe{tcs=GTN zFe?GrIsbzkadmSCuyOMIS3MAbm79YT0LZ`~0;dM**r~7cp?%~V7bQF?Q6HO*rCViA ziFozO!8_0*xs6az-8f*VuiNZ?zIM{<$J=9ATSvHb{VrY1chj;n6~*192qlq)ipY@` zpn^k<{G01sKyxSxdjq|J3*Sa&Vly0-DB-q~tUoiPEPxCmKbQ=U*V0Sv0&HBRVW3*Mmv@_V)b zhS3^BPg=6te9_xa+%mp4DjL{R2xH{a8j*W;z~>dXi;f4G#}02l^9(N^w9w&SCld@{ zahzG8F;SKV6J#s?kw!U>3MgZ1pP|N`Fy@~o8p)Mn#mOZosGmuco zWMEm>^EiQv7!fh5f9I%cP47A&Kn~3T^i=blqKETto=^M8i*Zn($ zvdtluiJGcsT&e)$MT+23&Q%(oAA-($-r@z!*%Z>H6Cb|-gPj5{7&#UlC{IAx=XUq6 zlX8jR+K8o>ip@&EYwMcsO?#0cOXt~HD}1pUJ5##0thoiNOmCX5+#z3|_=X8ck76ij zkY~_Sqx9H50aUC)A>iB9iEY@!cuQ>Mw)F1ShiGZLt~qYtlRt|cjFr}^iv3d|=g@TW zs}X12!yxUZmL!F&R-GG^cBuGj^1G<6qjUObP(yF?%V0Sa}qr>Qi9QS9t65H4Ib*jb!k(qTvj<6~;PSso3Va~JrlWLMS;{1Ygt(-dLVv~x znV1#~J`EYN(GlRGge+}aNch5g-QxfF;tcFomWH+B2fMy^#u9N}89E2~xJQ79{@*74PGBJ*dRKws|$@1BQCEI~_2yJbjLKenodQmib?SQ=!c-fA#bD&{X3h7C9>R)Ft1c>H9IInFgyu(|BL{+0e>z7s= zjo1^8EYKYcPd7?i9Y0Wdx%so$vmZVy*QKDII-aa$^q`d4nAKRnKxs zQ>7z6+ZRONRS3=9WKC2*8O9e&E%~=N#h%E0q@cF0)#qv|`D9a|SEk&`#%pfKZ3Dr) zhsqGusJF~HxX`hR>j%>2DVa_inWne6R4?g1*Tt-1hxF44sUWbZ{2o%U9H&WHcs6ot z7M!Sb-bNyVqwMKk=mngcCvgs)NLVm-A5ZbP*IlgKT}nNB%IsCe!6JJ$_i&7y(VBH? zFB4l>ov&Q@Sou|^0NBpNu?m^~w3c+dVJR>#mF%ay5oMSVl=EFf#eSZ0@RSk~LzZlq>b4Yqyq z4kiLU4dPPp3$}KrueTSb5lJntKq!5mRG(-y7~|hjm^MF!}8bSEK)H%MnUOu4{%eAj=C)BMmm~G%ZsKKqg+of2vMr;W~IOw_@v@PR9=K z+CC{sgBIf+ngM1~?Urmkt00d-C+&s-gF^5`g`R^KS#2Jk@j@ng-I$qWAafrkvo0$x442xjz4MlF;je8{ z2!UA}pw9|m2mEJE&B@6fz`^rxzuJG~mQDbU|AhblOe6sM0_@^aJd&IoVqBc!tUQt| zJZ$2eViKZa9Bdp?oLt;oTta~VNErVAnt#VASU6g_TLW1Cos`1DL<1z6;K%3(`xdtA zMn;T|K1dGNk3wT}9)y=OV{xdh-3TxX{sCS8Zj^v0!pnS-Hh_kj0!*!<}-I}*9QM%9bDuH75D#6gxuUsUERH0|6L>x3kM4i M0wtxSvJ}Gq09BPW`2YX_ From 8a9ade00254e403f15471b17ce9fe75fcf0da084 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 11 Jun 2020 10:58:44 -0500 Subject: [PATCH 048/199] remove extra semicolon --- gtsam/base/serialization.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 088029903..191e0ecfb 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -108,7 +108,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: return false; { boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input);; + out_archive << boost::serialization::make_nvp(name.c_str(), input); } out_archive_stream.close(); return true; From c83a4976a4681506d0576db06e108cd353f25d8b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sat, 13 Jun 2020 08:11:31 +0200 Subject: [PATCH 049/199] Remove all debian package files from this repository. They should belong to the new repository https://github.com/borglab/gtsam-packaging. Read: https://github.com/borglab/gtsam-packaging/issues/1 --- debian/README.md | 12 -- debian/changelog | 5 - debian/compat | 1 - debian/control | 15 -- debian/copyright | 15 -- debian/gtsam-docs.docs | 0 debian/rules | 29 --- debian/source/format | 1 - package_scripts/README.md | 44 ----- package_scripts/compile_static_boost.sh | 8 - package_scripts/prepare_debian.sh | 187 ------------------ .../prepare_debian_gen_snapshot_version.sh | 25 --- package_scripts/prepare_release.sh | 71 ------- .../prepare_ubuntu_pkgs_for_ppa.sh | 123 ------------ package_scripts/toolbox_package_unix.sh | 64 ------ package_scripts/upload_all_gtsam_ppa.sh | 31 --- 16 files changed, 631 deletions(-) delete mode 100644 debian/README.md delete mode 100644 debian/changelog delete mode 100644 debian/compat delete mode 100644 debian/control delete mode 100644 debian/copyright delete mode 100644 debian/gtsam-docs.docs delete mode 100755 debian/rules delete mode 100644 debian/source/format delete mode 100644 package_scripts/README.md delete mode 100755 package_scripts/compile_static_boost.sh delete mode 100755 package_scripts/prepare_debian.sh delete mode 100755 package_scripts/prepare_debian_gen_snapshot_version.sh delete mode 100755 package_scripts/prepare_release.sh delete mode 100755 package_scripts/prepare_ubuntu_pkgs_for_ppa.sh delete mode 100755 package_scripts/toolbox_package_unix.sh delete mode 100755 package_scripts/upload_all_gtsam_ppa.sh diff --git a/debian/README.md b/debian/README.md deleted file mode 100644 index 74eb351cd..000000000 --- a/debian/README.md +++ /dev/null @@ -1,12 +0,0 @@ -# How to build a GTSAM debian package - -To use the ``debuild`` command, install the ``devscripts`` package - - sudo apt install devscripts - -Change into the gtsam directory, then run: - - debuild -us -uc -j4 - -Adjust the ``-j4`` depending on how many CPUs you want to build on in -parallel. diff --git a/debian/changelog b/debian/changelog deleted file mode 100644 index ef5d5ab97..000000000 --- a/debian/changelog +++ /dev/null @@ -1,5 +0,0 @@ -gtsam (4.0.0-1berndpfrommer) bionic; urgency=medium - - * initial release - - -- Bernd Pfrommer Wed, 18 Jul 2018 20:36:44 -0400 diff --git a/debian/compat b/debian/compat deleted file mode 100644 index ec635144f..000000000 --- a/debian/compat +++ /dev/null @@ -1 +0,0 @@ -9 diff --git a/debian/control b/debian/control deleted file mode 100644 index 9b3ae5308..000000000 --- a/debian/control +++ /dev/null @@ -1,15 +0,0 @@ -Source: gtsam -Section: libs -Priority: optional -Maintainer: Frank Dellaert -Uploaders: Jose Luis Blanco Claraco , Bernd Pfrommer -Build-Depends: cmake, libboost-all-dev (>= 1.58), libeigen3-dev, libtbb-dev, debhelper (>=9) -Standards-Version: 3.9.7 -Homepage: https://github.com/borglab/gtsam -Vcs-Browser: https://github.com/borglab/gtsam - -Package: libgtsam-dev -Architecture: any -Depends: ${shlibs:Depends}, ${misc:Depends}, libboost-serialization-dev, libboost-system-dev, libboost-filesystem-dev, libboost-thread-dev, libboost-program-options-dev, libboost-date-time-dev, libboost-timer-dev, libboost-chrono-dev, libboost-regex-dev -Description: Georgia Tech Smoothing and Mapping Library - gtsam: Georgia Tech Smoothing and Mapping library for SLAM type applications diff --git a/debian/copyright b/debian/copyright deleted file mode 100644 index c2f41d83d..000000000 --- a/debian/copyright +++ /dev/null @@ -1,15 +0,0 @@ -Format: https://www.debian.org/doc/packaging-manuals/copyright-format/1.0/ -Upstream-Name: gtsam -Source: https://bitbucket.org/gtborg/gtsam.git - -Files: * -Copyright: 2017, Frank Dellaert -License: BSD - -Files: gtsam/3rdparty/CCOLAMD/* -Copyright: 2005-2011, Univ. of Florida. Authors: Timothy A. Davis, Sivasankaran Rajamanickam, and Stefan Larimore. Closely based on COLAMD by Davis, Stefan Larimore, in collaboration with Esmond Ng, and John Gilbert. http://www.cise.ufl.edu/research/sparse -License: GNU LESSER GENERAL PUBLIC LICENSE - -Files: gtsam/3rdparty/Eigen/* -Copyright: 2017, Multiple Authors -License: MPL2 diff --git a/debian/gtsam-docs.docs b/debian/gtsam-docs.docs deleted file mode 100644 index e69de29bb..000000000 diff --git a/debian/rules b/debian/rules deleted file mode 100755 index fab798f6e..000000000 --- a/debian/rules +++ /dev/null @@ -1,29 +0,0 @@ -#!/usr/bin/make -f -# See debhelper(7) (uncomment to enable) -# output every command that modifies files on the build system. -export DH_VERBOSE = 1 - -# Makefile target name for running unit tests: -GTSAM_TEST_TARGET = check - -# see FEATURE AREAS in dpkg-buildflags(1) -#export DEB_BUILD_MAINT_OPTIONS = hardening=+all - -# see ENVIRONMENT in dpkg-buildflags(1) -# package maintainers to append CFLAGS -#export DEB_CFLAGS_MAINT_APPEND = -Wall -pedantic -# package maintainers to append LDFLAGS -#export DEB_LDFLAGS_MAINT_APPEND = -Wl,--as-needed - -%: - dh $@ --parallel - -# dh_make generated override targets -# This is example for Cmake (See https://bugs.debian.org/641051 ) -override_dh_auto_configure: - dh_auto_configure -- -DCMAKE_BUILD_TYPE=RelWithDebInfo -DCMAKE_INSTALL_PREFIX=/usr -DGTSAM_BUILD_EXAMPLES_ALWAYS=OFF -DGTSAM_BUILD_TESTS=ON -DGTSAM_BUILD_WRAP=OFF -DGTSAM_BUILD_DOCS=OFF -DGTSAM_INSTALL_CPPUNITLITE=OFF -DGTSAM_INSTALL_GEOGRAPHICLIB=OFF -DGTSAM_BUILD_TYPE_POSTFIXES=OFF -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF - -override_dh_auto_test-arch: - # Tests for arch-dependent : - echo "[override_dh_auto_test-arch]" - dh_auto_build -O--buildsystem=cmake -- $(GTSAM_TEST_TARGET) diff --git a/debian/source/format b/debian/source/format deleted file mode 100644 index 163aaf8d8..000000000 --- a/debian/source/format +++ /dev/null @@ -1 +0,0 @@ -3.0 (quilt) diff --git a/package_scripts/README.md b/package_scripts/README.md deleted file mode 100644 index e27747717..000000000 --- a/package_scripts/README.md +++ /dev/null @@ -1,44 +0,0 @@ -# How to build Debian and Ubuntu Packages - -## Preparations - -Packages must be signed with a GPG key. First have a look of the keys -you have available: - - gpg --list-secret-keys - -If you don't have one, create one, then list again. - -Pick a secret key you like from the listed keys, for instance -"Your Name ". Then unlock that key by -signing a dummy file. The following line should pop up a window to -enter the passphrase: - - echo | gpg --local-user "Your Name " -s >/dev/null - -Now you can run the below scripts. Without this step they will fail -with "No secret key" or similar messages. - -## How to generate a Debian package - -Run the package script, providing a name/email that matches your PGP key. - - cd [GTSAM_SOURCE_ROOT] - bash package_scripts/prepare_debian.sh -e "Your Name " - - -## How to generate Ubuntu packages for a PPA - -Run the packaging script, passing the name of the gpg key -(see above) with the "-e" option: - - cd [GTSAM_SOURCE_ROOT] - bash package_scripts/prepare_ubuntu_pkgs_for_ppa.sh -e "Your Name " - -Check that you have uploaded this key to the ubuntu key server, and -have added the key to your account. - -Upload the package to your ppa: - - cd ~/gtsam_ubuntu - bash [GTSAM_SOURCE_ROOT]/package_scripts/upload_all_gtsam_ppa.sh -p "ppa:your-name/ppa-name" diff --git a/package_scripts/compile_static_boost.sh b/package_scripts/compile_static_boost.sh deleted file mode 100755 index ca3b99e09..000000000 --- a/package_scripts/compile_static_boost.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/bin/sh - -# Compile boost statically, with -fPIC to allow linking it into the mex -# module (which is a dynamic library). --disable-icu prevents depending -# on libicu, which is unneeded and would require then linking the mex -# module with it as well. We just stage instead of install, then the -# toolbox_package_unix.sh script uses the staged boost. -./b2 link=static threading=multi cxxflags=-fPIC cflags=-fPIC --disable-icu -a -j4 stage diff --git a/package_scripts/prepare_debian.sh b/package_scripts/prepare_debian.sh deleted file mode 100755 index 5dd191fc6..000000000 --- a/package_scripts/prepare_debian.sh +++ /dev/null @@ -1,187 +0,0 @@ -#!/bin/bash -# Prepare to build a Debian package. -# Jose Luis Blanco Claraco, 2019 (for GTSAM) -# Jose Luis Blanco Claraco, 2008-2018 (for MRPT) - -set -e # end on error -#set -x # for debugging - -APPEND_SNAPSHOT_NUM=0 -IS_FOR_UBUNTU=0 -APPEND_LINUX_DISTRO="" -VALUE_EXTRA_CMAKE_PARAMS="" -while getopts "sud:c:e:" OPTION -do - case $OPTION in - s) - APPEND_SNAPSHOT_NUM=1 - ;; - u) - IS_FOR_UBUNTU=1 - ;; - d) - APPEND_LINUX_DISTRO=$OPTARG - ;; - c) - VALUE_EXTRA_CMAKE_PARAMS=$OPTARG - ;; - e) - PACKAGER_EMAIL=$OPTARG - ;; - ?) - echo "Unknown command line argument!" - exit 1 - ;; - esac -done - -if [ -z ${PACKAGER_EMAIL+x} ]; then - echo "must specify packager email via -e option!" - exit -1 -fi - -if [ -f CMakeLists.txt ]; -then - source package_scripts/prepare_debian_gen_snapshot_version.sh -else - echo "Error: cannot find CMakeList.txt. This script is intended to be run from the root of the source tree." - exit 1 -fi - -# Append snapshot? -if [ $APPEND_SNAPSHOT_NUM == "1" ]; -then - CUR_SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" - source $CUR_SCRIPT_DIR/prepare_debian_gen_snapshot_version.sh # populate GTSAM_SNAPSHOT_VERSION - - GTSAM_VERSION_STR="${GTSAM_VERSION_STR}~snapshot${GTSAM_SNAPSHOT_VERSION}${APPEND_LINUX_DISTRO}" -else - GTSAM_VERSION_STR="${GTSAM_VERSION_STR}${APPEND_LINUX_DISTRO}" -fi - -# Call prepare_release -GTSAMSRC=`pwd` - -if [ -f $HOME/gtsam_release/gtsam*.tar.gz ]; -then - echo "## release file already exists. Reusing it." -else - source package_scripts/prepare_release.sh - echo - echo "## Done prepare_release.sh" -fi - -echo "=========== Generating GTSAM ${GTSAM_VER_MMP} Debian package ==============" -cd $GTSAMSRC - -set -x -if [ -z "$GTSAM_DEB_DIR" ]; then - GTSAM_DEB_DIR="$HOME/gtsam_debian" -fi -GTSAM_EXTERN_DEBIAN_DIR="$GTSAMSRC/debian/" -GTSAM_EXTERN_UBUNTU_PPA_DIR="$GTSAMSRC/debian/" - -if [ -f ${GTSAM_EXTERN_DEBIAN_DIR}/control ]; -then - echo "Using debian dir: ${GTSAM_EXTERN_DEBIAN_DIR}" -else - echo "ERROR: Cannot find ${GTSAM_EXTERN_DEBIAN_DIR}" - exit 1 -fi - -GTSAM_DEBSRC_DIR=$GTSAM_DEB_DIR/gtsam-${GTSAM_VERSION_STR} - -echo "GTSAM_VERSION_STR: ${GTSAM_VERSION_STR}" -echo "GTSAM_DEBSRC_DIR: ${GTSAM_DEBSRC_DIR}" - -# Prepare a directory for building the debian package: -# -rm -fR $GTSAM_DEB_DIR || true -mkdir -p $GTSAM_DEB_DIR || true - -# Orig tarball: -echo "Copying orig tarball: gtsam_${GTSAM_VERSION_STR}.orig.tar.gz" -cp $HOME/gtsam_release/gtsam*.tar.gz $GTSAM_DEB_DIR/gtsam_${GTSAM_VERSION_STR}.orig.tar.gz -cd ${GTSAM_DEB_DIR} -tar -xf gtsam_${GTSAM_VERSION_STR}.orig.tar.gz - -if [ ! -d "${GTSAM_DEBSRC_DIR}" ]; -then - mv gtsam-* ${GTSAM_DEBSRC_DIR} # fix different dir names for Ubuntu PPA packages -fi - -if [ ! -f "${GTSAM_DEBSRC_DIR}/CMakeLists.txt" ]; -then - echo "*ERROR*: Seems there was a problem copying sources to ${GTSAM_DEBSRC_DIR}... aborting script." - exit 1 -fi - -cd ${GTSAM_DEBSRC_DIR} - -# Copy debian directory: -#mkdir debian -cp -r ${GTSAM_EXTERN_DEBIAN_DIR}/* debian - -# Use modified control & rules files for Ubuntu PPA packages: -#if [ $IS_FOR_UBUNTU == "1" ]; -#then - # already done: cp ${GTSAM_EXTERN_UBUNTU_PPA_DIR}/control.in debian/ - # Ubuntu: force use of gcc-7: - #sed -i '9i\export CXX=/usr/bin/g++-7\' debian/rules - #sed -i '9i\export CC=/usr/bin/gcc-7\' debian/rules7 -#fi - -# Export signing pub key: -mkdir debian/upstream/ -gpg --export --export-options export-minimal --armor > debian/upstream/signing-key.asc - -# Parse debian/ control.in --> control -#mv debian/control.in debian/control -#sed -i "s/@GTSAM_VER_MM@/${GTSAM_VER_MM}/g" debian/control - -# Replace the text "REPLACE_HERE_EXTRA_CMAKE_PARAMS" in the "debian/rules" file -# with: ${${VALUE_EXTRA_CMAKE_PARAMS}} -RULES_FILE=debian/rules -sed -i -e "s/REPLACE_HERE_EXTRA_CMAKE_PARAMS/${VALUE_EXTRA_CMAKE_PARAMS}/g" $RULES_FILE -echo "Using these extra parameters for CMake: '${VALUE_EXTRA_CMAKE_PARAMS}'" - -# Strip my custom files... -rm debian/*.new || true - - -# Figure out the next Debian version number: -echo "Detecting next Debian version number..." - -CHANGELOG_UPSTREAM_VER=$( dpkg-parsechangelog | sed -n 's/Version:.*\([0-9]\.[0-9]*\.[0-9]*.*snapshot.*\)-.*/\1/p' ) -CHANGELOG_LAST_DEBIAN_VER=$( dpkg-parsechangelog | sed -n 's/Version:.*\([0-9]\.[0-9]*\.[0-9]*\).*-\([0-9]*\).*/\2/p' ) - -echo " -> PREVIOUS UPSTREAM: $CHANGELOG_UPSTREAM_VER -> New: ${GTSAM_VERSION_STR}" -echo " -> PREVIOUS DEBIAN VERSION: $CHANGELOG_LAST_DEBIAN_VER" - -# If we have the same upstream versions, increase the Debian version, otherwise create a new entry: -if [ "$CHANGELOG_UPSTREAM_VER" = "$GTSAM_VERSION_STR" ]; -then - NEW_DEBIAN_VER=$[$CHANGELOG_LAST_DEBIAN_VER + 1] - echo "Changing to a new Debian version: ${GTSAM_VERSION_STR}-${NEW_DEBIAN_VER}" - DEBCHANGE_CMD="--newversion ${GTSAM_VERSION_STR}-${NEW_DEBIAN_VER}" -else - DEBCHANGE_CMD="--newversion ${GTSAM_VERSION_STR}-1" -fi - -echo "Adding a new entry to debian/changelog..." - -DEBEMAIL=${PACKAGER_EMAIL} debchange $DEBCHANGE_CMD -b --distribution unstable --force-distribution New version of upstream sources. - -echo "Copying back the new changelog to a temporary file in: ${GTSAM_EXTERN_DEBIAN_DIR}changelog.new" -cp debian/changelog ${GTSAM_EXTERN_DEBIAN_DIR}changelog.new - -set +x - -echo "==============================================================" -echo "Now, you can build the source Deb package with 'debuild -S -sa'" -echo "==============================================================" - -cd .. -ls -lh - -exit 0 diff --git a/package_scripts/prepare_debian_gen_snapshot_version.sh b/package_scripts/prepare_debian_gen_snapshot_version.sh deleted file mode 100755 index 589d422fe..000000000 --- a/package_scripts/prepare_debian_gen_snapshot_version.sh +++ /dev/null @@ -1,25 +0,0 @@ -#!/bin/bash - -# See https://reproducible-builds.org/specs/source-date-epoch/ -# get SOURCE_DATE_EPOCH with UNIX time_t -if [ -d ".git" ]; -then - SOURCE_DATE_EPOCH=$(git log -1 --pretty=%ct) -else - echo "Error: intended for use from within a git repository" - exit 1 -fi -GTSAM_SNAPSHOT_VERSION=$(date -d @$SOURCE_DATE_EPOCH +%Y%m%d-%H%M) - -GTSAM_SNAPSHOT_VERSION+="-git-" -GTSAM_SNAPSHOT_VERSION+=`git rev-parse --short=8 HEAD` -GTSAM_SNAPSHOT_VERSION+="-" - -# x.y.z version components: -GTSAM_VERSION_MAJOR=$(grep "(GTSAM_VERSION_MAJOR" CMakeLists.txt | sed -r 's/^.*GTSAM_VERSION_MAJOR\s*([0-9])*.*$/\1/g') -GTSAM_VERSION_MINOR=$(grep "(GTSAM_VERSION_MINOR" CMakeLists.txt | sed -r 's/^.*GTSAM_VERSION_MINOR\s*([0-9])*.*$/\1/g') -GTSAM_VERSION_PATCH=$(grep "(GTSAM_VERSION_PATCH" CMakeLists.txt | sed -r 's/^.*GTSAM_VERSION_PATCH\s*([0-9])*.*$/\1/g') - -GTSAM_VER_MM="${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}" -GTSAM_VER_MMP="${GTSAM_VERSION_MAJOR}.${GTSAM_VERSION_MINOR}.${GTSAM_VERSION_PATCH}" -GTSAM_VERSION_STR=$GTSAM_VER_MMP diff --git a/package_scripts/prepare_release.sh b/package_scripts/prepare_release.sh deleted file mode 100755 index 750fc27b3..000000000 --- a/package_scripts/prepare_release.sh +++ /dev/null @@ -1,71 +0,0 @@ -#!/bin/bash -# Export sources from a git tree and prepare it for a public release. -# Jose Luis Blanco Claraco, 2019 (for GTSAM) -# Jose Luis Blanco Claraco, 2008-2018 (for MRPT) - -set -e # exit on error -#set -x # for debugging - -# Checks -# -------------------------------- -if [ -f version_prefix.txt ]; -then - if [ -z ${GTSAM_VERSION_STR+x} ]; - then - source package_scripts/prepare_debian_gen_snapshot_version.sh - fi - echo "ERROR: Run this script from the GTSAM source tree root directory." - exit 1 -fi - -GTSAM_SRC=`pwd` -OUT_RELEASES_DIR="$HOME/gtsam_release" - -OUT_DIR=$OUT_RELEASES_DIR/gtsam-${GTSAM_VERSION_STR} - -echo "=========== Generating GTSAM release ${GTSAM_VER_MMP} ==================" -echo "GTSAM_VERSION_STR : ${GTSAM_VERSION_STR}" -echo "OUT_DIR : ${OUT_DIR}" -echo "============================================================" -echo - -# Prepare output directory: -rm -fR $OUT_RELEASES_DIR || true -mkdir -p ${OUT_DIR} - -# Export / copy sources to target dir: -if [ -d "$GTSAM_SRC/.git" ]; -then - echo "# Exporting git source tree to ${OUT_DIR}" - git archive --format=tar HEAD | tar -x -C ${OUT_DIR} - - # Remove VCS control files: - find ${OUT_DIR} -name '.gitignore' | xargs rm - - # Generate ./SOURCE_DATE_EPOCH with UNIX time_t - SOURCE_DATE_EPOCH=$(git log -1 --pretty=%ct) -else - echo "# Copying sources to ${OUT_DIR}" - cp -R . ${OUT_DIR} - - # Generate ./SOURCE_DATE_EPOCH with UNIX time_t - SOURCE_DATE_EPOCH=$(date +%s) -fi - -# See https://reproducible-builds.org/specs/source-date-epoch/ -echo $SOURCE_DATE_EPOCH > ${OUT_DIR}/SOURCE_DATE_EPOCH - -cd ${OUT_DIR} - -# Dont include Debian files in releases: -rm -fR package_scripts - -# Orig tarball: -cd .. -echo "# Creating orig tarball: gtsam-${GTSAM_VERSION_STR}.tar.gz" -tar czf gtsam-${GTSAM_VERSION_STR}.tar.gz gtsam-${GTSAM_VERSION_STR} - -rm -fr gtsam-${GTSAM_VERSION_STR} - -# GPG signature: -gpg --armor --detach-sign gtsam-${GTSAM_VERSION_STR}.tar.gz diff --git a/package_scripts/prepare_ubuntu_pkgs_for_ppa.sh b/package_scripts/prepare_ubuntu_pkgs_for_ppa.sh deleted file mode 100755 index 33c016b94..000000000 --- a/package_scripts/prepare_ubuntu_pkgs_for_ppa.sh +++ /dev/null @@ -1,123 +0,0 @@ -#!/bin/bash -# Creates a set of packages for each different Ubuntu distribution, with the -# intention of uploading them to a PPA on launchpad -# -# JLBC, 2010 -# [Addition 2012:] -# -# You can declare a variable (in the caller shell) with extra flags for the -# CMake in the final ./configure like: -# -# GTSAM_PKG_CUSTOM_CMAKE_PARAMS="\"-DDISABLE_SSE3=ON\"" -# - - -function show_help { - echo "USAGE:" - echo "" - echo "- to display this help: " - echo "prepare_ubuntu_packages_for_ppa.sh -h or -?" - echo "" - echo "- to package to your PPA: " - echo "prepare_ubuntu_packages_for_ppa.sh -e email_of_your_gpg_key" - echo "" - echo "to pass custom config for GTSAM, set the following" - echo "environment variable beforehand: " - echo "" - echo "GTSAM_PKG_CUSTOM_CMAKE_PARAMS=\"\"-DDISABLE_SSE3=ON\"\"" - echo "" -} - -while getopts "h?e:" opt; do - case "$opt" in - h|\?) - show_help - exit 0 - ;; - e) PACKAGER_EMAIL=$OPTARG - ;; - esac -done - -if [ -z ${PACKAGER_EMAIL+x} ]; then - show_help - exit -1 -fi - - -set -e - -# List of distributions to create PPA packages for: -LST_DISTROS=(xenial bionic eoan focal) - -# Checks -# -------------------------------- -if [ -f CMakeLists.txt ]; -then - source package_scripts/prepare_debian_gen_snapshot_version.sh - echo "GTSAM version: ${GTSAM_VER_MMP}" -else - echo "ERROR: Run this script from the GTSAM root directory." - exit 1 -fi - -if [ -z "${gtsam_ubuntu_OUT_DIR}" ]; then - export gtsam_ubuntu_OUT_DIR="$HOME/gtsam_ubuntu" -fi -GTSAMSRC=`pwd` -if [ -z "${GTSAM_DEB_DIR}" ]; then - export GTSAM_DEB_DIR="$HOME/gtsam_debian" -fi -GTSAM_EXTERN_DEBIAN_DIR="$GTSAMSRC/debian/" - -# Clean out dirs: -rm -fr $gtsam_ubuntu_OUT_DIR/ - -# ------------------------------------------------------------------- -# And now create the custom packages for each Ubuntu distribution: -# ------------------------------------------------------------------- -count=${#LST_DISTROS[@]} -IDXS=$(seq 0 $(expr $count - 1)) - -cp ${GTSAM_EXTERN_DEBIAN_DIR}/changelog /tmp/my_changelog - -for IDX in ${IDXS}; -do - DEBIAN_DIST=${LST_DISTROS[$IDX]} - - # ------------------------------------------------------------------- - # Call the standard "prepare_debian.sh" script: - # ------------------------------------------------------------------- - cd ${GTSAMSRC} - bash package_scripts/prepare_debian.sh -e "$PACKAGER_EMAIL" -s -u -d ${DEBIAN_DIST} -c "${GTSAM_PKG_CUSTOM_CMAKE_PARAMS}" - - CUR_SCRIPT_DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" - source $CUR_SCRIPT_DIR/prepare_debian_gen_snapshot_version.sh # populate GTSAM_SNAPSHOT_VERSION - - echo "===== Distribution: ${DEBIAN_DIST} =========" - cd ${GTSAM_DEB_DIR}/gtsam-${GTSAM_VER_MMP}~snapshot${GTSAM_SNAPSHOT_VERSION}${DEBIAN_DIST}/debian - #cp ${GTSAM_EXTERN_DEBIAN_DIR}/changelog changelog - cp /tmp/my_changelog changelog - DEBCHANGE_CMD="--newversion ${GTSAM_VERSION_STR}~snapshot${GTSAM_SNAPSHOT_VERSION}${DEBIAN_DIST}-1" - echo "Changing to a new Debian version: ${DEBCHANGE_CMD}" - echo "Adding a new entry to debian/changelog for distribution ${DEBIAN_DIST}" - DEBEMAIL="${PACKAGER_EMAIL}" debchange $DEBCHANGE_CMD -b --distribution ${DEBIAN_DIST} --force-distribution New version of upstream sources. - - cp changelog /tmp/my_changelog - - echo "Now, let's build the source Deb package with 'debuild -S -sa':" - cd .. - # -S: source package - # -sa: force inclusion of sources - # -d: don't check dependencies in this system - debuild -S -sa -d - - # Make a copy of all these packages: - cd .. - mkdir -p $gtsam_ubuntu_OUT_DIR/$DEBIAN_DIST - cp gtsam_* $gtsam_ubuntu_OUT_DIR/${DEBIAN_DIST}/ - echo ">>>>>> Saving packages to: $gtsam_ubuntu_OUT_DIR/$DEBIAN_DIST/" -done - - -exit 0 diff --git a/package_scripts/toolbox_package_unix.sh b/package_scripts/toolbox_package_unix.sh deleted file mode 100755 index 28de2572a..000000000 --- a/package_scripts/toolbox_package_unix.sh +++ /dev/null @@ -1,64 +0,0 @@ -#!/bin/sh - -# Script to build a tarball with the matlab toolbox - -# Detect platform -os=`uname -s` -arch=`uname -m` -if [ "$os" = "Linux" -a "$arch" = "x86_64" ]; then - platform=lin64 -elif [ "$os" = "Linux" -a "$arch" = "i686" ]; then - platform=lin32 -elif [ "$os" = "Darwin" -a "$arch" = "x86_64" ]; then - platform=mac64 -else - echo "Unrecognized platform" - exit 1 -fi - -echo "Platform is ${platform}" - -# Check for empty diectory -if [ ! -z "`ls`" ]; then - echo "Please run this script from an empty build directory" - exit 1 -fi - -# Check for boost -if [ -z "$1" ]; then - echo "Usage: $0 BOOSTTREE" - echo "BOOSTTREE should be a boost source tree compiled with toolbox_build_boost." - exit 1 -fi - -# Run cmake -cmake -DCMAKE_BUILD_TYPE=Release \ --DGTSAM_INSTALL_MATLAB_TOOLBOX:BOOL=ON \ --DCMAKE_INSTALL_PREFIX="$PWD/stage" \ --DBoost_NO_SYSTEM_PATHS:BOOL=ON \ --DBoost_USE_STATIC_LIBS:BOOL=ON \ --DBOOST_ROOT="$1" \ --DGTSAM_BUILD_TESTS:BOOL=OFF \ --DGTSAM_BUILD_TIMING:BOOL=OFF \ --DGTSAM_BUILD_EXAMPLES_ALWAYS:BOOL=OFF \ --DGTSAM_WITH_TBB:BOOL=OFF \ --DGTSAM_SUPPORT_NESTED_DISSECTION:BOOL=OFF \ --DGTSAM_INSTALL_GEOGRAPHICLIB:BOOL=OFF \ --DGTSAM_BUILD_UNSTABLE:BOOL=OFF \ --DGTSAM_MEX_BUILD_STATIC_MODULE:BOOL=ON .. - -if [ $? -ne 0 ]; then - echo "CMake failed" - exit 1 -fi - -# Compile -make -j8 install - -if [ $? -ne 0 ]; then - echo "Compile failed" - exit 1 -fi - -# Create package -tar czf gtsam-toolbox-3.2.0-$platform.tgz -C stage/gtsam_toolbox toolbox diff --git a/package_scripts/upload_all_gtsam_ppa.sh b/package_scripts/upload_all_gtsam_ppa.sh deleted file mode 100755 index f06d005fb..000000000 --- a/package_scripts/upload_all_gtsam_ppa.sh +++ /dev/null @@ -1,31 +0,0 @@ -#!/bin/bash - -function show_help { - echo "USAGE:" - echo "" - echo "- to display this help: " - echo "upload_all_gtsam_ppa.sh -h or -?" - echo "" - echo "- to upload to your PPA: " - echo "upload_all_gtsam_ppa.sh -p ppa:your_name/name_of_ppa" - echo "" -} - -while getopts "h?p:" opt; do - case "$opt" in - h|\?) - show_help - exit 0 - ;; - p) ppa_name=$OPTARG - ;; - esac -done - -if [ -z ${ppa_name+x} ]; then - show_help - exit -1 -fi - - -find . -name '*.changes' | xargs -I FIL dput ${ppa_name} FIL From bd040c8b2287d08ffb07ace0a01ba2a789ce7cac Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 17 Jun 2020 15:02:24 -0500 Subject: [PATCH 050/199] set CMAKE_VERBOSE_MAKEFILE flag to OFF --- .travis.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.sh b/.travis.sh index 9fc09a3f8..535a72f4b 100755 --- a/.travis.sh +++ b/.travis.sh @@ -63,7 +63,7 @@ function configure() -DGTSAM_BUILD_EXAMPLES_ALWAYS=${GTSAM_BUILD_EXAMPLES_ALWAYS:-ON} \ -DGTSAM_ALLOW_DEPRECATED_SINCE_V4=${GTSAM_ALLOW_DEPRECATED_SINCE_V4:-OFF} \ -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF \ - -DCMAKE_VERBOSE_MAKEFILE=ON + -DCMAKE_VERBOSE_MAKEFILE=OFF } From 741df283d098536857bdacfb9140828a0dc3aca2 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Fri, 19 Jun 2020 09:00:15 +0200 Subject: [PATCH 051/199] Finish undo of #310 fill with zeros (not actually needed) --- gtsam/base/SymmetricBlockMatrix.h | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/gtsam/base/SymmetricBlockMatrix.h b/gtsam/base/SymmetricBlockMatrix.h index c2996109f..4e030606d 100644 --- a/gtsam/base/SymmetricBlockMatrix.h +++ b/gtsam/base/SymmetricBlockMatrix.h @@ -71,24 +71,22 @@ namespace gtsam { } /// Construct from a container of the sizes of each block. - /// Uninitialized blocks are filled with zeros. template SymmetricBlockMatrix(const CONTAINER& dimensions, bool appendOneDimension = false) : blockStart_(0) { fillOffsets(dimensions.begin(), dimensions.end(), appendOneDimension); - matrix_.setZero(variableColOffsets_.back(), variableColOffsets_.back()); + matrix_.resize(variableColOffsets_.back(), variableColOffsets_.back()); assertInvariants(); } /// Construct from iterator over the sizes of each vertical block. - /// Uninitialized blocks are filled with zeros. template SymmetricBlockMatrix(ITERATOR firstBlockDim, ITERATOR lastBlockDim, bool appendOneDimension = false) : blockStart_(0) { fillOffsets(firstBlockDim, lastBlockDim, appendOneDimension); - matrix_.setZero(variableColOffsets_.back(), variableColOffsets_.back()); + matrix_.resize(variableColOffsets_.back(), variableColOffsets_.back()); assertInvariants(); } @@ -418,4 +416,3 @@ namespace gtsam { class CholeskyFailed; } - From 0a44315a7f3b1b2f6e1953e5b73ece40c7097a01 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 08:46:06 +1000 Subject: [PATCH 052/199] Add Pose3-Point3 factor --- gtsam_unstable/slam/PoseToPointFactor.h | 95 +++++++++++++++++++ .../slam/tests/testPoseToPointFactor.h | 84 ++++++++++++++++ 2 files changed, 179 insertions(+) create mode 100644 gtsam_unstable/slam/PoseToPointFactor.h create mode 100644 gtsam_unstable/slam/tests/testPoseToPointFactor.h diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h new file mode 100644 index 000000000..98efd6a0b --- /dev/null +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -0,0 +1,95 @@ +/** + * @file PoseToPointFactor.hpp + * @brief This factor can be used to track a 3D landmark over time by providing + * local measurements of its location. + * @author David Wisth + **/ +#pragma once + +#include +#include +#include +#include + +namespace gtsam { + +/** + * A class for a measurement between a pose and a point. + * @addtogroup SLAM + */ +class PoseToPointFactor: public NoiseModelFactor2 { + +private: + + typedef PoseToPointFactor This; + typedef NoiseModelFactor2 Base; + + Point3 measured_; /** the point measurement */ + +public: + + // shorthand for a smart pointer to a factor + typedef boost::shared_ptr shared_ptr; + + /** default constructor - only use for serialization */ + PoseToPointFactor() {} + + /** Constructor */ + PoseToPointFactor(Key key1, Key key2, const Point3& measured, + const SharedNoiseModel& model) : + Base(model, key1, key2), measured_(measured) + { + } + + virtual ~PoseToPointFactor() {} + + /** implement functions needed for Testable */ + + /** print */ + virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { + std::cout << s << "PoseToPointFactor(" + << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n" + << " measured: " << measured_.transpose() << std::endl; + this->noiseModel_->print(" noise model: "); + } + + /** equals */ + virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { + const This *e = dynamic_cast (&expected); + return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); + } + + /** implement functions needed to derive from Factor */ + + /** vector of errors + * Error = pose_est.inverse()*point_est - measured_ + * (The error is in the measurement coordinate system) + */ + Vector evaluateError(const Pose3& W_T_WI, + const Point3& W_r_WC, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const + { + return W_T_WI.transformTo(W_r_WC, H1, H2) - measured_; + } + + /** return the measured */ + const Point3& measured() const { + return measured_; + } + +private: + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & boost::serialization::make_nvp("NoiseModelFactor2", + boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_NVP(measured_); + } + +}; // \class PoseToPointFactor + +} /// namespace gtsam diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h new file mode 100644 index 000000000..0a13e78e2 --- /dev/null +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -0,0 +1,84 @@ +/** + * @file testPoseToPointFactor.cpp + * @brief + * @author David Wisth + * @date June 20, 2020 + */ + +#include +#include +#include + +using namespace gtsam; +using namespace gtsam::noiseModel; + +/// Verify zero error when there is no noise +TEST(LandmarkFactor, errorNoiseless) { + Pose3 pose = Pose3::identity(); + Point3 point(1.0, 2.0, 3.0); + Point3 noise(0.0, 0.0, 0.0); + Point3 measured = t + noise; + + Key pose_key(1); + Key point_key(2); + PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + Vector expectedError = Vector3(0.0, 0.0, 0.0); + Vector actualError = factor.evaluateError(pose, point); + EXPECT(assert_equal(expectedError,actualError, 1E-5)); +} + +/// Verify expected error in test scenario +TEST(LandmarkFactor, errorNoise) { + Pose3 pose = Pose3::identity(); + Point3 point(1.0 , 2.0, 3.0); + Point3 noise(-1.0, 0.5, 0.3); + Point3 measured = t + noise; + + Key pose_key(1); + Key point_key(2); + PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + Vector expectedError = noise; + Vector actualError = factor.evaluateError(pose, point); + EXPECT(assert_equal(expectedError,actualError, 1E-5)); +} + +/// Check Jacobians are correct +TEST(LandmarkFactor, jacobian) { + // Measurement + gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); + + // Linearisation point + gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); + gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5*M_PI, -0.3*M_PI, 0.4*M_PI); + Pose3 p(p_R, p_t); + + gtsam::Point3 l = gtsam::Point3(3, 0, 5); + + // Factor + Key pose_key(1); + Key point_key(2); + SharedGaussian noise = noiseModel::Diagonal::Sigmas(Vector3(0.1, 0.1, 0.1)); + PoseToPointFactor factor(pose_key, point_key, l_meas, noise); + + // Calculate numerical derivatives + boost::function f = boost::bind( + &LandmarkFactor::evaluateError, factor, _1, _2, boost::none, boost::none); + Matrix numerical_H1 = numericalDerivative21(f, p, l); + Matrix numerical_H2 = numericalDerivative22(f, p, l); + + // Use the factor to calculate the derivative + Matrix actual_H1; + Matrix actual_H2; + factor.evaluateError(p, l, actual_H1, actual_H2); + + // Verify we get the expected error + EXPECT_TRUE(assert_equal(numerical_H1, actual_H1, 1e-8)); + EXPECT_TRUE(assert_equal(numerical_H2, actual_H2, 1e-8)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ From c422815b9402a0a0840c2902b8df647e6d527ca5 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 09:03:17 +1000 Subject: [PATCH 053/199] Update incorrect test name --- gtsam_unstable/slam/tests/testPoseToPointFactor.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h index 0a13e78e2..4b2793700 100644 --- a/gtsam_unstable/slam/tests/testPoseToPointFactor.h +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -13,7 +13,7 @@ using namespace gtsam; using namespace gtsam::noiseModel; /// Verify zero error when there is no noise -TEST(LandmarkFactor, errorNoiseless) { +TEST(PoseToPointFactor, errorNoiseless) { Pose3 pose = Pose3::identity(); Point3 point(1.0, 2.0, 3.0); Point3 noise(0.0, 0.0, 0.0); @@ -28,7 +28,7 @@ TEST(LandmarkFactor, errorNoiseless) { } /// Verify expected error in test scenario -TEST(LandmarkFactor, errorNoise) { +TEST(PoseToPointFactor, errorNoise) { Pose3 pose = Pose3::identity(); Point3 point(1.0 , 2.0, 3.0); Point3 noise(-1.0, 0.5, 0.3); @@ -43,7 +43,7 @@ TEST(LandmarkFactor, errorNoise) { } /// Check Jacobians are correct -TEST(LandmarkFactor, jacobian) { +TEST(PoseToPointFactor, jacobian) { // Measurement gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); From 0ee4e3b77eaaa879d5e995d92714698e94d11455 Mon Sep 17 00:00:00 2001 From: David Date: Sat, 20 Jun 2020 09:45:24 +1000 Subject: [PATCH 054/199] Add more documentation and clang-format --- gtsam_unstable/slam/PoseToPointFactor.h | 81 +++++++++---------- .../slam/tests/testPoseToPointFactor.h | 22 ++--- 2 files changed, 50 insertions(+), 53 deletions(-) diff --git a/gtsam_unstable/slam/PoseToPointFactor.h b/gtsam_unstable/slam/PoseToPointFactor.h index 98efd6a0b..ec7da22ef 100644 --- a/gtsam_unstable/slam/PoseToPointFactor.h +++ b/gtsam_unstable/slam/PoseToPointFactor.h @@ -1,15 +1,15 @@ /** * @file PoseToPointFactor.hpp - * @brief This factor can be used to track a 3D landmark over time by providing - * local measurements of its location. + * @brief This factor can be used to track a 3D landmark over time by + *providing local measurements of its location. * @author David Wisth **/ #pragma once -#include -#include #include #include +#include +#include namespace gtsam { @@ -17,17 +17,14 @@ namespace gtsam { * A class for a measurement between a pose and a point. * @addtogroup SLAM */ -class PoseToPointFactor: public NoiseModelFactor2 { - -private: - +class PoseToPointFactor : public NoiseModelFactor2 { + private: typedef PoseToPointFactor This; typedef NoiseModelFactor2 Base; - Point3 measured_; /** the point measurement */ - -public: + Point3 measured_; /** the point measurement in local coordinates */ + public: // shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; @@ -36,60 +33,58 @@ public: /** Constructor */ PoseToPointFactor(Key key1, Key key2, const Point3& measured, - const SharedNoiseModel& model) : - Base(model, key1, key2), measured_(measured) - { - } + const SharedNoiseModel& model) + : Base(model, key1, key2), measured_(measured) {} virtual ~PoseToPointFactor() {} /** implement functions needed for Testable */ /** print */ - virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const { - std::cout << s << "PoseToPointFactor(" - << keyFormatter(this->key1()) << "," - << keyFormatter(this->key2()) << ")\n" - << " measured: " << measured_.transpose() << std::endl; + virtual void print(const std::string& s, const KeyFormatter& keyFormatter = + DefaultKeyFormatter) const { + std::cout << s << "PoseToPointFactor(" << keyFormatter(this->key1()) << "," + << keyFormatter(this->key2()) << ")\n" + << " measured: " << measured_.transpose() << std::endl; this->noiseModel_->print(" noise model: "); } /** equals */ - virtual bool equals(const NonlinearFactor& expected, double tol=1e-9) const { - const This *e = dynamic_cast (&expected); - return e != nullptr && Base::equals(*e, tol) && traits::Equals(this->measured_, e->measured_, tol); + virtual bool equals(const NonlinearFactor& expected, + double tol = 1e-9) const { + const This* e = dynamic_cast(&expected); + return e != nullptr && Base::equals(*e, tol) && + traits::Equals(this->measured_, e->measured_, tol); } /** implement functions needed to derive from Factor */ /** vector of errors - * Error = pose_est.inverse()*point_est - measured_ - * (The error is in the measurement coordinate system) - */ - Vector evaluateError(const Pose3& W_T_WI, - const Point3& W_r_WC, + * @brief Error = wTwi.inverse()*wPwp - measured_ + * @param wTwi The pose of the sensor in world coordinates + * @param wPwp The estimated point location in world coordinates + * + * Note: measured_ and the error are in local coordiantes. + */ + Vector evaluateError(const Pose3& wTwi, const Point3& wPwp, boost::optional H1 = boost::none, - boost::optional H2 = boost::none) const - { - return W_T_WI.transformTo(W_r_WC, H1, H2) - measured_; + boost::optional H2 = boost::none) const { + return wTwi.transformTo(wPwp, H1, H2) - measured_; } /** return the measured */ - const Point3& measured() const { - return measured_; - } - -private: + const Point3& measured() const { return measured_; } + private: /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor2", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(measured_); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& boost::serialization::make_nvp( + "NoiseModelFactor2", boost::serialization::base_object(*this)); + ar& BOOST_SERIALIZATION_NVP(measured_); } -}; // \class PoseToPointFactor +}; // \class PoseToPointFactor -} /// namespace gtsam +} // namespace gtsam diff --git a/gtsam_unstable/slam/tests/testPoseToPointFactor.h b/gtsam_unstable/slam/tests/testPoseToPointFactor.h index 4b2793700..8f8563e9d 100644 --- a/gtsam_unstable/slam/tests/testPoseToPointFactor.h +++ b/gtsam_unstable/slam/tests/testPoseToPointFactor.h @@ -5,9 +5,9 @@ * @date June 20, 2020 */ +#include #include #include -#include using namespace gtsam; using namespace gtsam::noiseModel; @@ -21,25 +21,27 @@ TEST(PoseToPointFactor, errorNoiseless) { Key pose_key(1); Key point_key(2); - PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + PoseToPointFactor factor(pose_key, point_key, measured, + Isotropic::Sigma(3, 0.05)); Vector expectedError = Vector3(0.0, 0.0, 0.0); Vector actualError = factor.evaluateError(pose, point); - EXPECT(assert_equal(expectedError,actualError, 1E-5)); + EXPECT(assert_equal(expectedError, actualError, 1E-5)); } /// Verify expected error in test scenario TEST(PoseToPointFactor, errorNoise) { Pose3 pose = Pose3::identity(); - Point3 point(1.0 , 2.0, 3.0); + Point3 point(1.0, 2.0, 3.0); Point3 noise(-1.0, 0.5, 0.3); Point3 measured = t + noise; Key pose_key(1); Key point_key(2); - PoseToPointFactor factor(pose_key, point_key, measured, Isotropic::Sigma(3, 0.05)); + PoseToPointFactor factor(pose_key, point_key, measured, + Isotropic::Sigma(3, 0.05)); Vector expectedError = noise; Vector actualError = factor.evaluateError(pose, point); - EXPECT(assert_equal(expectedError,actualError, 1E-5)); + EXPECT(assert_equal(expectedError, actualError, 1E-5)); } /// Check Jacobians are correct @@ -48,8 +50,8 @@ TEST(PoseToPointFactor, jacobian) { gtsam::Point3 l_meas = gtsam::Point3(1, 2, 3); // Linearisation point - gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); - gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5*M_PI, -0.3*M_PI, 0.4*M_PI); + gtsam::Point3 p_t = gtsam::Point3(-5, 12, 2); + gtsam::Rot3 p_R = gtsam::Rot3::RzRyRx(1.5 * M_PI, -0.3 * M_PI, 0.4 * M_PI); Pose3 p(p_R, p_t); gtsam::Point3 l = gtsam::Point3(3, 0, 5); @@ -61,8 +63,8 @@ TEST(PoseToPointFactor, jacobian) { PoseToPointFactor factor(pose_key, point_key, l_meas, noise); // Calculate numerical derivatives - boost::function f = boost::bind( - &LandmarkFactor::evaluateError, factor, _1, _2, boost::none, boost::none); + auto f = boost::bind(&PoseToPointFactor::evaluateError, factor, _1, _2, + boost::none, boost::none); Matrix numerical_H1 = numericalDerivative21(f, p, l); Matrix numerical_H2 = numericalDerivative22(f, p, l); From 0bd81430573a32712642a546880600f498cac745 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Fri, 19 Jun 2020 23:33:29 -0400 Subject: [PATCH 055/199] Importing Frobenius error factors from Shonan effort --- cython/gtsam/tests/test_FrobeniusFactor.py | 56 +++++ gtsam.h | 29 +++ gtsam/slam/FrobeniusFactor.cpp | 117 ++++++++++ gtsam/slam/FrobeniusFactor.h | 145 ++++++++++++ gtsam/slam/tests/testFrobeniusFactor.cpp | 244 +++++++++++++++++++++ timing/timeFrobeniusFactor.cpp | 110 ++++++++++ 6 files changed, 701 insertions(+) create mode 100644 cython/gtsam/tests/test_FrobeniusFactor.py create mode 100644 gtsam/slam/FrobeniusFactor.cpp create mode 100644 gtsam/slam/FrobeniusFactor.h create mode 100644 gtsam/slam/tests/testFrobeniusFactor.cpp create mode 100644 timing/timeFrobeniusFactor.cpp diff --git a/cython/gtsam/tests/test_FrobeniusFactor.py b/cython/gtsam/tests/test_FrobeniusFactor.py new file mode 100644 index 000000000..82d1fb410 --- /dev/null +++ b/cython/gtsam/tests/test_FrobeniusFactor.py @@ -0,0 +1,56 @@ +""" +GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +FrobeniusFactor unit tests. +Author: Frank Dellaert +""" +# pylint: disable=no-name-in-module, import-error, invalid-name +import unittest + +import numpy as np +from gtsam import (SO3, SO4, FrobeniusBetweenFactorSO4, FrobeniusFactorSO4, + FrobeniusWormholeFactor, SOn) + +id = SO4() +v1 = np.array([0, 0, 0, 0.1, 0, 0]) +Q1 = SO4.Expmap(v1) +v2 = np.array([0, 0, 0, 0.01, 0.02, 0.03]) +Q2 = SO4.Expmap(v2) + + +class TestFrobeniusFactorSO4(unittest.TestCase): + """Test FrobeniusFactor factors.""" + + def test_frobenius_factor(self): + """Test creation of a factor that calculates the Frobenius norm.""" + factor = FrobeniusFactorSO4(1, 2) + actual = factor.evaluateError(Q1, Q2) + expected = (Q2.matrix()-Q1.matrix()).transpose().reshape((16,)) + np.testing.assert_array_equal(actual, expected) + + def test_frobenius_between_factor(self): + """Test creation of a Frobenius BetweenFactor.""" + factor = FrobeniusBetweenFactorSO4(1, 2, Q1.between(Q2)) + actual = factor.evaluateError(Q1, Q2) + expected = np.zeros((16,)) + np.testing.assert_array_almost_equal(actual, expected) + + def test_frobenius_wormhole_factor(self): + """Test creation of a factor that calculates Shonan error.""" + R1 = SO3.Expmap(v1[3:]) + R2 = SO3.Expmap(v2[3:]) + factor = FrobeniusWormholeFactor(1, 2, R1.between(R2), p=4) + I4 = SOn(4) + Q1 = I4.retract(v1) + Q2 = I4.retract(v2) + actual = factor.evaluateError(Q1, Q2) + expected = np.zeros((12,)) + np.testing.assert_array_almost_equal(actual, expected, decimal=4) + + +if __name__ == "__main__": + unittest.main() diff --git a/gtsam.h b/gtsam.h index 614db91c7..cbf737390 100644 --- a/gtsam.h +++ b/gtsam.h @@ -598,6 +598,7 @@ class SOn { // Standard Constructors SOn(size_t n); static gtsam::SOn FromMatrix(Matrix R); + static gtsam::SOn Lift(size_t n, Matrix R); // Testable void print(string s) const; @@ -2835,6 +2836,34 @@ virtual class KarcherMeanFactor : gtsam::NonlinearFactor { KarcherMeanFactor(const gtsam::KeyVector& keys); }; +#include +gtsam::noiseModel::Isotropic* ConvertPose3NoiseModel( + gtsam::noiseModel::Base* model, size_t d); + +template +virtual class FrobeniusFactor : gtsam::NoiseModelFactor { + FrobeniusFactor(size_t key1, size_t key2); + FrobeniusFactor(size_t key1, size_t key2, gtsam::noiseModel::Base* model); + + Vector evaluateError(const T& R1, const T& R2); +}; + +template +virtual class FrobeniusBetweenFactor : gtsam::NoiseModelFactor { + FrobeniusBetweenFactor(size_t key1, size_t key2, const T& R12); + FrobeniusBetweenFactor(size_t key1, size_t key2, const T& R12, gtsam::noiseModel::Base* model); + + Vector evaluateError(const T& R1, const T& R2); +}; + +virtual class FrobeniusWormholeFactor : gtsam::NoiseModelFactor { + FrobeniusWormholeFactor(size_t key1, size_t key2, const gtsam::Rot3& R12, + size_t p); + FrobeniusWormholeFactor(size_t key1, size_t key2, const gtsam::Rot3& R12, + size_t p, gtsam::noiseModel::Base* model); + Vector evaluateError(const gtsam::SOn& Q1, const gtsam::SOn& Q2); +}; + //************************************************************************* // Navigation //************************************************************************* diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp new file mode 100644 index 000000000..904addb03 --- /dev/null +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -0,0 +1,117 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file FrobeniusFactor.cpp + * @date March 2019 + * @author Frank Dellaert + * @brief Various factors that minimize some Frobenius norm + */ + +#include + +#include +#include +#include + +#include +#include +#include + +using namespace std; + +namespace gtsam { + +//****************************************************************************** +boost::shared_ptr ConvertPose3NoiseModel( + const SharedNoiseModel& model, size_t d, bool defaultToUnit) { + double sigma = 1.0; + if (model != nullptr) { + if (model->dim() != 6) { + if (!defaultToUnit) + throw std::runtime_error("Can only convert Pose3 noise models"); + } else { + auto sigmas = model->sigmas().head(3).eval(); + if (sigmas(1) != sigmas(0) || sigmas(2) != sigmas(0)) { + if (!defaultToUnit) + throw std::runtime_error("Can only convert isotropic rotation noise"); + } else { + sigma = sigmas(0); + } + } + } + return noiseModel::Isotropic::Sigma(d, sigma); +} + +//****************************************************************************** +FrobeniusWormholeFactor::FrobeniusWormholeFactor(Key j1, Key j2, const Rot3& R12, + size_t p, + const SharedNoiseModel& model) + : NoiseModelFactor2(ConvertPose3NoiseModel(model, p * 3), j1, j2), + M_(R12.matrix()), // 3*3 in all cases + p_(p), // 4 for SO(4) + pp_(p * p), // 16 for SO(4) + dimension_(SOn::Dimension(p)), // 6 for SO(4) + G_(pp_, dimension_) // 16*6 for SO(4) +{ + // Calculate G matrix of vectorized generators + Matrix Z = Matrix::Zero(p, p); + for (size_t j = 0; j < dimension_; j++) { + const auto X = SOn::Hat(Eigen::VectorXd::Unit(dimension_, j)); + G_.col(j) = Eigen::Map(X.data(), pp_, 1); + } + assert(noiseModel()->dim() == 3 * p_); +} + +//****************************************************************************** +Vector FrobeniusWormholeFactor::evaluateError( + const SOn& Q1, const SOn& Q2, boost::optional H1, + boost::optional H2) const { + gttic(FrobeniusWormholeFactorP_evaluateError); + + const Matrix& M1 = Q1.matrix(); + const Matrix& M2 = Q2.matrix(); + assert(M1.rows() == p_ && M2.rows() == p_); + + const size_t dim = 3 * p_; // Stiefel manifold dimension + Vector fQ2(dim), hQ1(dim); + + // Vectorize and extract only d leftmost columns, i.e. vec(M2*P) + fQ2 << Eigen::Map(M2.data(), dim, 1); + + // Vectorize M1*P*R12 + const Matrix Q1PR12 = M1.leftCols<3>() * M_; + hQ1 << Eigen::Map(Q1PR12.data(), dim, 1); + + // If asked, calculate Jacobian as (M \otimes M1) * G + if (H1) { + const size_t p2 = 2 * p_; + Matrix RPxQ = Matrix::Zero(dim, pp_); + RPxQ.block(0, 0, p_, dim) << M1 * M_(0, 0), M1 * M_(1, 0), M1 * M_(2, 0); + RPxQ.block(p_, 0, p_, dim) << M1 * M_(0, 1), M1 * M_(1, 1), M1 * M_(2, 1); + RPxQ.block(p2, 0, p_, dim) << M1 * M_(0, 2), M1 * M_(1, 2), M1 * M_(2, 2); + *H1 = -RPxQ * G_; + } + if (H2) { + const size_t p2 = 2 * p_; + Matrix PxQ = Matrix::Zero(dim, pp_); + PxQ.block(0, 0, p_, p_) = M2; + PxQ.block(p_, p_, p_, p_) = M2; + PxQ.block(p2, p2, p_, p_) = M2; + *H2 = PxQ * G_; + } + + return fQ2 - hQ1; +} + +//****************************************************************************** + +} // namespace gtsam diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h new file mode 100644 index 000000000..60fa82ab4 --- /dev/null +++ b/gtsam/slam/FrobeniusFactor.h @@ -0,0 +1,145 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file FrobeniusFactor.h + * @date March 2019 + * @author Frank Dellaert + * @brief Various factors that minimize some Frobenius norm + */ + +#pragma once + +#include +#include +#include + +namespace gtsam { + +/** + * When creating (any) FrobeniusFactor we convert a 6-dimensional Pose3 + * BetweenFactor noise model into an 9 or 16-dimensional isotropic noise + * model used to weight the Frobenius norm. If the noise model passed is + * null we return a Dim-dimensional isotropic noise model with sigma=1.0. If + * not, we we check if the 3-dimensional noise model on rotations is + * isotropic. If it is, we extend to 'Dim' dimensions, otherwise we throw an + * error. If defaultToUnit == false throws an exception on unexepcted input. + */ +boost::shared_ptr ConvertPose3NoiseModel( + const SharedNoiseModel& model, size_t d, bool defaultToUnit = true); + +/** + * FrobeniusPrior calculates the Frobenius norm between a given matrix and an + * element of SO(3) or SO(4). + */ +template +class FrobeniusPrior : public NoiseModelFactor1 { + enum { Dim = Rot::VectorN2::RowsAtCompileTime }; + using MatrixNN = typename Rot::MatrixNN; + Eigen::Matrix vecM_; ///< vectorized matrix to approximate + + public: + /// Constructor + FrobeniusPrior(Key j, const MatrixNN& M, + const SharedNoiseModel& model = nullptr) + : NoiseModelFactor1(ConvertPose3NoiseModel(model, Dim), j) { + vecM_ << Eigen::Map(M.data(), Dim, 1); + } + + /// Error is just Frobenius norm between Rot element and vectorized matrix M. + Vector evaluateError(const Rot& R, + boost::optional H = boost::none) const { + return R.vec(H) - vecM_; // Jacobian is computed only when needed. + } +}; + +/** + * FrobeniusFactor calculates the Frobenius norm between rotation matrices. + * The template argument can be any fixed-size SO. + */ +template +class FrobeniusFactor : public NoiseModelFactor2 { + enum { Dim = Rot::VectorN2::RowsAtCompileTime }; + + public: + /// Constructor + FrobeniusFactor(Key j1, Key j2, const SharedNoiseModel& model = nullptr) + : NoiseModelFactor2(ConvertPose3NoiseModel(model, Dim), j1, + j2) {} + + /// Error is just Frobenius norm between rotation matrices. + Vector evaluateError(const Rot& R1, const Rot& R2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const { + Vector error = R2.vec(H2) - R1.vec(H1); + if (H1) *H1 = -*H1; + return error; + } +}; + +/** + * FrobeniusBetweenFactor is a BetweenFactor that evaluates the Frobenius norm + * of the rotation error between measured and predicted (rather than the + * Logmap of the error). This factor is only defined for fixed-dimension types, + * and in fact only SO3 and SO4 really work, as we need SO::AdjointMap. + */ +template +class FrobeniusBetweenFactor : public NoiseModelFactor2 { + Rot R12_; ///< measured rotation between R1 and R2 + Eigen::Matrix + R2hat_H_R1_; ///< fixed derivative of R2hat wrpt R1 + enum { Dim = Rot::VectorN2::RowsAtCompileTime }; + + public: + /// Constructor + FrobeniusBetweenFactor(Key j1, Key j2, const Rot& R12, + const SharedNoiseModel& model = nullptr) + : NoiseModelFactor2( + ConvertPose3NoiseModel(model, Dim), j1, j2), + R12_(R12), + R2hat_H_R1_(R12.inverse().AdjointMap()) {} + + /// Error is Frobenius norm between R1*R12 and R2. + Vector evaluateError(const Rot& R1, const Rot& R2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const { + const Rot R2hat = R1.compose(R12_); + Eigen::Matrix vec_H_R2hat; + Vector error = R2.vec(H2) - R2hat.vec(H1 ? &vec_H_R2hat : nullptr); + if (H1) *H1 = -vec_H_R2hat * R2hat_H_R1_; + return error; + } +}; + +/** + * FrobeniusWormholeFactor is a BetweenFactor that moves in SO(p), but will + * land on the SO(3) sub-manifold of SO(p) at the global minimum. It projects + * the SO(p) matrices down to a Stiefel manifold of p*d matrices. + * TODO(frank): template on D=2 or 3 + */ +class FrobeniusWormholeFactor : public NoiseModelFactor2 { + Matrix M_; ///< measured rotation between R1 and R2 + size_t p_, pp_, dimension_; ///< dimensionality constants + Matrix G_; ///< matrix of vectorized generators + + public: + /// Constructor. Note we convert to 3*p-dimensional noise model. + FrobeniusWormholeFactor(Key j1, Key j2, const Rot3& R12, size_t p = 4, + const SharedNoiseModel& model = nullptr); + + /// Error is Frobenius norm between Q1*P*R12 and Q2*P, where P=[I_3x3;0] + /// projects down from SO(p) to the Stiefel manifold of px3 matrices. + Vector evaluateError(const SOn& Q1, const SOn& Q2, + boost::optional H1 = boost::none, + boost::optional H2 = boost::none) const; +}; + +} // namespace gtsam diff --git a/gtsam/slam/tests/testFrobeniusFactor.cpp b/gtsam/slam/tests/testFrobeniusFactor.cpp new file mode 100644 index 000000000..3aefeeb1a --- /dev/null +++ b/gtsam/slam/tests/testFrobeniusFactor.cpp @@ -0,0 +1,244 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * testFrobeniusFactor.cpp + * + * @file testFrobeniusFactor.cpp + * @date March 2019 + * @author Frank Dellaert + * @brief Check evaluateError for various Frobenius norm + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +//****************************************************************************** +namespace so3 { +SO3 id; +Vector3 v1 = (Vector(3) << 0.1, 0, 0).finished(); +SO3 R1 = SO3::Expmap(v1); +Vector3 v2 = (Vector(3) << 0.01, 0.02, 0.03).finished(); +SO3 R2 = SO3::Expmap(v2); +SO3 R12 = R1.between(R2); +} // namespace so3 + +/* ************************************************************************* */ +TEST(FrobeniusPriorSO3, evaluateError) { + using namespace ::so3; + auto factor = FrobeniusPrior(1, R2.matrix()); + Vector actual = factor.evaluateError(R1); + Vector expected = R1.vec() - R2.vec(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, R1); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +TEST(FrobeniusPriorSO3, ClosestTo) { + // Example top-left of SO(4) matrix not quite on SO(3) manifold + Matrix3 M; + M << 0.79067393, 0.6051136, -0.0930814, // + 0.4155925, -0.64214347, -0.64324489, // + -0.44948549, 0.47046326, -0.75917576; + + SO3 expected = SO3::ClosestTo(M); + + // manifold optimization gets same result as SVD solution in ClosestTo + NonlinearFactorGraph graph; + graph.emplace_shared >(1, M); + + Values initial; + initial.insert(1, SO3(I_3x3)); + auto result = GaussNewtonOptimizer(graph, initial).optimize(); + EXPECT_DOUBLES_EQUAL(0.0, graph.error(result), 1e-6); + EXPECT(assert_equal(expected, result.at(1), 1e-6)); +} + +/* ************************************************************************* */ +TEST(FrobeniusPriorSO3, ChordalL2mean) { + // See Hartley13ijcv: + // Cost function C(R) = \sum FrobeniusPrior(R,R_i) + // Closed form solution = ClosestTo(C_e), where + // C_e = \sum R_i !!!! + + // We will test by computing mean of R1=exp(v1) R1^T=exp(-v1): + using namespace ::so3; + SO3 expected; // identity + Matrix3 M = R1.matrix() + R1.matrix().transpose(); + EXPECT(assert_equal(expected, SO3::ClosestTo(M), 1e-6)); + EXPECT(assert_equal(expected, SO3::ChordalMean({R1, R1.inverse()}), 1e-6)); + + // manifold optimization gets same result as ChordalMean + NonlinearFactorGraph graph; + graph.emplace_shared >(1, R1.matrix()); + graph.emplace_shared >(1, R1.matrix().transpose()); + + Values initial; + initial.insert(1, R1.inverse()); + auto result = GaussNewtonOptimizer(graph, initial).optimize(); + EXPECT_DOUBLES_EQUAL(0.0, graph.error(result), 0.1); // Why so loose? + EXPECT(assert_equal(expected, result.at(1), 1e-5)); +} + +/* ************************************************************************* */ +TEST(FrobeniusFactorSO3, evaluateError) { + using namespace ::so3; + auto factor = FrobeniusFactor(1, 2); + Vector actual = factor.evaluateError(R1, R2); + Vector expected = R2.vec() - R1.vec(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, R1); + values.insert(2, R2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +// Commented out as SO(n) not yet supported (and might never be) +// TEST(FrobeniusBetweenFactorSOn, evaluateError) { +// using namespace ::so3; +// auto factor = +// FrobeniusBetweenFactor(1, 2, SOn::FromMatrix(R12.matrix())); +// Vector actual = factor.evaluateError(SOn::FromMatrix(R1.matrix()), +// SOn::FromMatrix(R2.matrix())); +// Vector expected = Vector9::Zero(); +// EXPECT(assert_equal(expected, actual, 1e-9)); + +// Values values; +// values.insert(1, R1); +// values.insert(2, R2); +// EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +// } + +/* ************************************************************************* */ +TEST(FrobeniusBetweenFactorSO3, evaluateError) { + using namespace ::so3; + auto factor = FrobeniusBetweenFactor(1, 2, R12); + Vector actual = factor.evaluateError(R1, R2); + Vector expected = Vector9::Zero(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, R1); + values.insert(2, R2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +//****************************************************************************** +namespace so4 { +SO4 id; +Vector6 v1 = (Vector(6) << 0.1, 0, 0, 0, 0, 0).finished(); +SO4 Q1 = SO4::Expmap(v1); +Vector6 v2 = (Vector(6) << 0.01, 0.02, 0.03, 0.04, 0.05, 0.06).finished(); +SO4 Q2 = SO4::Expmap(v2); +} // namespace so4 + +/* ************************************************************************* */ +TEST(FrobeniusFactorSO4, evaluateError) { + using namespace ::so4; + auto factor = FrobeniusFactor(1, 2, noiseModel::Unit::Create(6)); + Vector actual = factor.evaluateError(Q1, Q2); + Vector expected = Q2.vec() - Q1.vec(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, Q1); + values.insert(2, Q2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +/* ************************************************************************* */ +TEST(FrobeniusBetweenFactorSO4, evaluateError) { + using namespace ::so4; + Matrix4 M{I_4x4}; + M.topLeftCorner<3, 3>() = ::so3::R12.matrix(); + auto factor = FrobeniusBetweenFactor(1, 2, Q1.between(Q2)); + Matrix H1, H2; + Vector actual = factor.evaluateError(Q1, Q2, H1, H2); + Vector expected = SO4::VectorN2::Zero(); + EXPECT(assert_equal(expected, actual, 1e-9)); + + Values values; + values.insert(1, Q1); + values.insert(2, Q2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); +} + +//****************************************************************************** +namespace submanifold { +SO4 id; +Vector6 v1 = (Vector(6) << 0, 0, 0, 0.1, 0, 0).finished(); +SO3 R1 = SO3::Expmap(v1.tail<3>()); +SO4 Q1 = SO4::Expmap(v1); +Vector6 v2 = (Vector(6) << 0, 0, 0, 0.01, 0.02, 0.03).finished(); +SO3 R2 = SO3::Expmap(v2.tail<3>()); +SO4 Q2 = SO4::Expmap(v2); +SO3 R12 = R1.between(R2); +} // namespace submanifold + +/* ************************************************************************* */ +TEST(FrobeniusWormholeFactor, evaluateError) { + auto model = noiseModel::Isotropic::Sigma(6, 1.2); // dimension = 6 not 16 + for (const size_t p : {5, 4, 3}) { + Matrix M = Matrix::Identity(p, p); + M.topLeftCorner(3, 3) = submanifold::R1.matrix(); + SOn Q1(M); + M.topLeftCorner(3, 3) = submanifold::R2.matrix(); + SOn Q2(M); + auto factor = + FrobeniusWormholeFactor(1, 2, Rot3(::so3::R12.matrix()), p, model); + Matrix H1, H2; + factor.evaluateError(Q1, Q2, H1, H2); + + // Test derivatives + Values values; + values.insert(1, Q1); + values.insert(2, Q2); + EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); + } +} + +/* ************************************************************************* */ +TEST(FrobeniusWormholeFactor, equivalenceToSO3) { + using namespace ::submanifold; + auto R12 = ::so3::R12.retract(Vector3(0.1, 0.2, -0.1)); + auto model = noiseModel::Isotropic::Sigma(6, 1.2); // wrong dimension + auto factor3 = FrobeniusBetweenFactor(1, 2, R12, model); + auto factor4 = FrobeniusWormholeFactor(1, 2, Rot3(R12.matrix()), 4, model); + const Eigen::Map E3(factor3.evaluateError(R1, R2).data()); + const Eigen::Map E4( + factor4.evaluateError(SOn(Q1.matrix()), SOn(Q2.matrix())).data()); + EXPECT(assert_equal((Matrix)E4.topLeftCorner<3, 3>(), E3, 1e-9)); + EXPECT(assert_equal((Matrix)E4.row(3), Matrix13::Zero(), 1e-9)); +} + +/* ************************************************************************* */ +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} +/* ************************************************************************* */ diff --git a/timing/timeFrobeniusFactor.cpp b/timing/timeFrobeniusFactor.cpp new file mode 100644 index 000000000..c8bdd8fec --- /dev/null +++ b/timing/timeFrobeniusFactor.cpp @@ -0,0 +1,110 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file timeFrobeniusFactor.cpp + * @brief time FrobeniusFactor with BAL file + * @author Frank Dellaert + * @date June 6, 2015 + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +using namespace std; +using namespace gtsam; + +static SharedNoiseModel gNoiseModel = noiseModel::Unit::Create(2); + +int main(int argc, char* argv[]) { + // primitive argument parsing: + if (argc > 3) { + throw runtime_error("Usage: timeFrobeniusFactor [g2oFile]"); + } + + string g2oFile; + try { + if (argc > 1) + g2oFile = argv[argc - 1]; + else + g2oFile = + "/Users/dellaert/git/2019c-notes-shonanrotationaveraging/matlabCode/" + "datasets/randomTorus3D.g2o"; + // g2oFile = findExampleDataFile("sphere_smallnoise.graph"); + } catch (const exception& e) { + cerr << e.what() << '\n'; + exit(1); + } + + // Read G2O file + const auto factors = parse3DFactors(g2oFile); + const auto poses = parse3DPoses(g2oFile); + + // Build graph + NonlinearFactorGraph graph; + // graph.add(NonlinearEquality(0, SO4())); + auto priorModel = noiseModel::Isotropic::Sigma(6, 10000); + graph.add(PriorFactor(0, SO4(), priorModel)); + for (const auto& factor : factors) { + const auto& keys = factor->keys(); + const auto& Tij = factor->measured(); + const auto& model = factor->noiseModel(); + graph.emplace_shared( + keys[0], keys[1], SO3(Tij.rotation().matrix()), model); + } + + boost::mt19937 rng(42); + + // Set parameters to be similar to ceres + LevenbergMarquardtParams params; + LevenbergMarquardtParams::SetCeresDefaults(¶ms); + params.setLinearSolverType("MULTIFRONTAL_QR"); + // params.setVerbosityLM("SUMMARY"); + // params.linearSolverType = LevenbergMarquardtParams::Iterative; + // auto pcg = boost::make_shared(); + // pcg->preconditioner_ = + // boost::make_shared(); + // boost::make_shared(); + // params.iterativeParams = pcg; + + // Optimize + for (size_t i = 0; i < 100; i++) { + gttic_(optimize); + Values initial; + initial.insert(0, SO4()); + for (size_t j = 1; j < poses.size(); j++) { + initial.insert(j, SO4::Random(rng)); + } + LevenbergMarquardtOptimizer lm(graph, initial, params); + Values result = lm.optimize(); + cout << "cost = " << graph.error(result) << endl; + } + + tictoc_finishedIteration_(); + tictoc_print_(); + + return 0; +} From 604f1511ccd6bab7e14b6eb71249d29606e5188f Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 12:09:03 -0400 Subject: [PATCH 056/199] Fix UAF --- gtsam/slam/tests/testFrobeniusFactor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/slam/tests/testFrobeniusFactor.cpp b/gtsam/slam/tests/testFrobeniusFactor.cpp index 3aefeeb1a..9cb0c19fa 100644 --- a/gtsam/slam/tests/testFrobeniusFactor.cpp +++ b/gtsam/slam/tests/testFrobeniusFactor.cpp @@ -229,8 +229,8 @@ TEST(FrobeniusWormholeFactor, equivalenceToSO3) { auto model = noiseModel::Isotropic::Sigma(6, 1.2); // wrong dimension auto factor3 = FrobeniusBetweenFactor(1, 2, R12, model); auto factor4 = FrobeniusWormholeFactor(1, 2, Rot3(R12.matrix()), 4, model); - const Eigen::Map E3(factor3.evaluateError(R1, R2).data()); - const Eigen::Map E4( + const Matrix3 E3(factor3.evaluateError(R1, R2).data()); + const Matrix43 E4( factor4.evaluateError(SOn(Q1.matrix()), SOn(Q2.matrix())).data()); EXPECT(assert_equal((Matrix)E4.topLeftCorner<3, 3>(), E3, 1e-9)); EXPECT(assert_equal((Matrix)E4.row(3), Matrix13::Zero(), 1e-9)); From 37673771aec059e14705fad69a0282a9c55e3eba Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:21:17 -0400 Subject: [PATCH 057/199] Fixed all alignment problems --- gtsam.h | 2 +- gtsam/base/make_shared.h | 44 ++++++++++++++++++++++++++++++++++++++++ gtsam/base/types.h | 26 ++++++++++++++++++++++++ gtsam/geometry/SOn.h | 4 ++-- wrap/Module.cpp | 5 ++++- 5 files changed, 77 insertions(+), 4 deletions(-) create mode 100644 gtsam/base/make_shared.h diff --git a/gtsam.h b/gtsam.h index 614db91c7..cf232efa5 100644 --- a/gtsam.h +++ b/gtsam.h @@ -281,7 +281,7 @@ virtual class Value { }; #include -template +template virtual class GenericValue : gtsam::Value { void serializable() const; }; diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h new file mode 100644 index 000000000..c8b63f5d4 --- /dev/null +++ b/gtsam/base/make_shared.h @@ -0,0 +1,44 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file make_shared.h + * @brief make_shared trampoline function to ensure proper alignment + * @author Fan Jiang + */ + +#pragma once + +#include +#include + +#include + +#include + +namespace gtsam { + + /** + * And our own `make_shared` as a layer of wrapping on `boost::make_shared` + */ + template + boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + { + return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); + } + + template + boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + { + return boost::make_shared(std::forward (args)...); + } + +} \ No newline at end of file diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 2fa6eebb6..3abbdfe81 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -230,3 +230,29 @@ namespace std { #ifdef ERROR #undef ERROR #endif + +namespace gtsam { + + /** + * A trait to mark classes that need special alignment. + * Please refer to https://github.com/PointCloudLibrary/pcl/pull/3163 + */ +#if __cplusplus < 201703L + template using void_t = void; +#endif + + template> + struct has_custom_allocator : std::false_type { + }; + template + struct has_custom_allocator> : std::true_type { + }; + +} + +/** + * This is necessary for the Cython wrapper to work properly, and possibly reduce future misalignment problems. + */ +#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ + using _custom_allocator_type_trait = void; \ No newline at end of file diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 5313d3018..767b12020 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -20,8 +20,8 @@ #include #include +#include #include - #include #include // TODO(frank): how to avoid? @@ -54,7 +54,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { using VectorN2 = Eigen::Matrix; using MatrixDD = Eigen::Matrix; - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW protected: MatrixNN matrix_; ///< Rotation matrix diff --git a/wrap/Module.cpp b/wrap/Module.cpp index a7db9e1f6..ec02dc412 100644 --- a/wrap/Module.cpp +++ b/wrap/Module.cpp @@ -350,7 +350,10 @@ void Module::emit_cython_pxd(FileWriter& pxdFile) const { " T* get()\n" " long use_count() const\n" " T& operator*()\n\n" - " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n" + " cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r)\n\n"; + + // gtsam alignment-friendly shared_ptr + pxdFile.oss << "cdef extern from \"gtsam/base/make_shared.h\" namespace \"gtsam\":\n" " cdef shared_ptr[T] make_shared[T](const T& r)\n\n"; for(const TypedefPair& types: typedefs) From fad4fe39f28797f11a61461f3f0224f173046b2e Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:48:40 -0400 Subject: [PATCH 058/199] Add missing include --- gtsam/base/make_shared.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c8b63f5d4..c5ac98f9c 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -20,7 +20,7 @@ #include #include -#include +#include #include From 693253f3768bbd618a688a8c173b6f1bd576fdec Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 20 Jun 2020 22:52:58 -0400 Subject: [PATCH 059/199] Fix wrap tests --- wrap/tests/expected-cython/geometry.pxd | 2 ++ 1 file changed, 2 insertions(+) diff --git a/wrap/tests/expected-cython/geometry.pxd b/wrap/tests/expected-cython/geometry.pxd index 0d9adac5f..3527840a3 100644 --- a/wrap/tests/expected-cython/geometry.pxd +++ b/wrap/tests/expected-cython/geometry.pxd @@ -16,6 +16,8 @@ cdef extern from "boost/shared_ptr.hpp" namespace "boost": T& operator*() cdef shared_ptr[T] dynamic_pointer_cast[T,U](const shared_ptr[U]& r) + +cdef extern from "gtsam/base/make_shared.h" namespace "gtsam": cdef shared_ptr[T] make_shared[T](const T& r) cdef extern from "gtsam/geometry/Point2.h" namespace "gtsam": From eab53f69de01ac06b9d2d20821539b4be4fade21 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 22 Jun 2020 13:37:50 -0400 Subject: [PATCH 060/199] Address Frank's comments --- gtsam/base/make_shared.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c5ac98f9c..03de30497 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -17,28 +17,28 @@ #pragma once -#include #include -#include - #include +#include +#include + + namespace gtsam { - /** - * And our own `make_shared` as a layer of wrapping on `boost::make_shared` - */ + /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` template boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); } + /// Fall back to the boost version if no need for alignment template boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::make_shared(std::forward (args)...); } -} \ No newline at end of file +} From 8f923fa081f0702cb36681675833476c17f692ce Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 22 Jun 2020 15:18:31 -0400 Subject: [PATCH 061/199] Move away from boost --- gtsam/base/make_shared.h | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index 03de30497..966dd516d 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -22,21 +22,28 @@ #include #include -#include +#include + +#if __cplusplus <= 201103L +namespace gtsam { + template + using enable_if_t = typename std::enable_if::type; +} +#endif namespace gtsam { /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` template - boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); } /// Fall back to the boost version if no need for alignment template - boost::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) { return boost::make_shared(std::forward (args)...); } From 263a1d2afa7714a76b00771579202bbc543fa872 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 22 Jun 2020 16:47:37 -0500 Subject: [PATCH 062/199] export cython install path so it can be picked up by other cmake projects --- gtsam_extra.cmake.in | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam_extra.cmake.in b/gtsam_extra.cmake.in index 8a9a13648..01ac00b37 100644 --- a/gtsam_extra.cmake.in +++ b/gtsam_extra.cmake.in @@ -9,5 +9,6 @@ set (GTSAM_USE_TBB @GTSAM_USE_TBB@) set (GTSAM_DEFAULT_ALLOCATOR @GTSAM_DEFAULT_ALLOCATOR@) if("@GTSAM_INSTALL_CYTHON_TOOLBOX@") + list(APPEND GTSAM_CYTHON_INSTALL_PATH "@GTSAM_CYTHON_INSTALL_PATH@") list(APPEND GTSAM_EIGENCY_INSTALL_PATH "@GTSAM_EIGENCY_INSTALL_PATH@") endif() From 1725a577cf881ae5478dbe08cef19b4b3f5a4f55 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 21 Mar 2020 14:52:17 -0400 Subject: [PATCH 063/199] cmake function to install python package once make install is completed --- cmake/GtsamCythonWrap.cmake | 7 +++++++ cython/CMakeLists.txt | 2 ++ 2 files changed, 9 insertions(+) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index f1382729f..3ca8b903f 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -279,3 +279,10 @@ function(install_cython_files source_files dest_directory) endfunction() +function(install_python_package install_path) + set(package_path "${install_path}${GTSAM_BUILD_TAG}") + # set cython directory permissions to user so we don't get permission denied + install(CODE "execute_process(COMMAND sh \"-c\" \"chown -R $(logname):$(logname) ${package_path}\")") + # go to cython directory and run setup.py + install(CODE "execute_process(COMMAND sh \"-c\" \"cd ${package_path} && python setup.py install\")") +endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 4cc9d2f5d..96503b82f 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,4 +45,6 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + install_python_package("${GTSAM_CYTHON_INSTALL_PATH}") + endif () From a796f74b8004d7cc12acaf3d20c9b3827a590770 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 20:24:32 -0400 Subject: [PATCH 064/199] use boost paths append to have platform agnostic path separators --- gtsam/base/serializationTestHelpers.h | 27 ++++++++++++++------------- 1 file changed, 14 insertions(+), 13 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 031a6278f..602fd68f6 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -42,10 +42,11 @@ T create() { } // Creates or empties a folder in the build folder and returns the relative path -std::string resetFilesystem() { - boost::filesystem::remove_all("actual"); - boost::filesystem::create_directory("actual"); - return "actual/"; +boost::filesystem::path resetFilesystem( + boost::filesystem::path folder = "actual") { + boost::filesystem::remove_all(folder); + boost::filesystem::create_directory(folder); + return folder; } // Templated round-trip serialization @@ -61,10 +62,10 @@ void roundtrip(const T& input, T& output) { // Templated round-trip serialization using a file template void roundtripFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.dat"; - serializeToFile(input, path + "graph.dat"); - deserializeFromFile(path + "graph.dat", output); + serializeToFile(input, path.string()); + deserializeFromFile(path.string(), output); } // This version requires equality operator @@ -109,13 +110,13 @@ void roundtripXML(const T& input, T& output) { // Templated round-trip serialization using XML File template void roundtripXMLFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.xml"; // Serialize - serializeToXMLFile(input, path + "graph.xml"); + serializeToXMLFile(input, path.string()); // De-serialize - deserializeFromXMLFile(path + "graph.xml", output); + deserializeFromXMLFile(path.string(), output); } // This version requires equality operator @@ -160,11 +161,11 @@ void roundtripBinary(const T& input, T& output) { // Templated round-trip serialization using Binary file template void roundtripBinaryFile(const T& input, T& output) { - std::string path = resetFilesystem(); + boost::filesystem::path path = resetFilesystem()/"graph.bin"; // Serialize - serializeToBinaryFile(input, path + "graph.bin"); + serializeToBinaryFile(input, path.string()); // De-serialize - deserializeFromBinaryFile(path + "graph.bin", output); + deserializeFromBinaryFile(path.string(), output); } // This version requires equality operator From 93a00a38a40a21e21a1c20da9209192a7076fc85 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 22 Jun 2020 20:14:03 -0500 Subject: [PATCH 065/199] add new make command for installing python wrapper --- cmake/GtsamCythonWrap.cmake | 17 ++++++++++++----- cython/CMakeLists.txt | 3 +++ cython/scripts/install.bat | 0 cython/scripts/install.sh | 21 +++++++++++++++++++++ 4 files changed, 36 insertions(+), 5 deletions(-) create mode 100755 cython/scripts/install.bat create mode 100755 cython/scripts/install.sh diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 3ca8b903f..361038ce0 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -280,9 +280,16 @@ function(install_cython_files source_files dest_directory) endfunction() function(install_python_package install_path) - set(package_path "${install_path}${GTSAM_BUILD_TAG}") - # set cython directory permissions to user so we don't get permission denied - install(CODE "execute_process(COMMAND sh \"-c\" \"chown -R $(logname):$(logname) ${package_path}\")") - # go to cython directory and run setup.py - install(CODE "execute_process(COMMAND sh \"-c\" \"cd ${package_path} && python setup.py install\")") +#TODO this will only work for Linux. Need to make it work on macOS and Windows as well +#TODO Running `sudo make install` makes this run in admin space causing Python 2.7 to be picked up. + # # go to cython directory and run setup.py + # install(CODE "execute_process(COMMAND sh \"-c\" \"cd ${package_path} && python setup.py install\")") + if(CMAKE_SYSTEM_NAME STREQUAL "Windows") + set(PYTHON_INSTALL_SCRIPT "install.bat") + elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux" OR CMAKE_SYSTEM_NAME STREQUAL "Darwin") + set(PYTHON_INSTALL_SCRIPT "install.sh") + endif() + + configure_file(${PROJECT_SOURCE_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT} ${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}) + add_custom_target(python-install "${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}") endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 96503b82f..638bdfb2d 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,6 +45,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + # file(GLOB GTSAM_PYTHON_INSTALL_SCRIPTS "scripts/*") + # file(COPY ${GTSAM_PYTHON_INSTALL_SCRIPTS} DESTINATION ${PROJECT_BINARY_DIR}/cython/scripts) + install_python_package("${GTSAM_CYTHON_INSTALL_PATH}") endif () diff --git a/cython/scripts/install.bat b/cython/scripts/install.bat new file mode 100755 index 000000000..e69de29bb diff --git a/cython/scripts/install.sh b/cython/scripts/install.sh new file mode 100755 index 000000000..04759ca5e --- /dev/null +++ b/cython/scripts/install.sh @@ -0,0 +1,21 @@ +#!/bin/sh +echo "Installing GTSAM Python Wrapper" + +PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} + +if [ ! -d "$PACKAGE_PATH" ] +then + echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; + exit 1; +fi + +# set cython directory permissions to user so we don't get permission denied +if [ "$(whoami)" != "root" ] +then + sudo chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} +else + chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} +fi + +echo "Running setup.py in $PACKAGE_PATH" +${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 327cbc515ff93db6f6547ed3deead1bdf9cfdb2e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 21:15:07 -0400 Subject: [PATCH 066/199] Separate stream creation and serialization Recommended by @ProfFan in #343 with the objective of making (de)serialize to string and to file more similar --- gtsam/base/serialization.h | 86 +++++++++++++++++++++++--------------- 1 file changed, 53 insertions(+), 33 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 191e0ecfb..031ee3a3e 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -44,18 +44,28 @@ namespace gtsam { // Serialization directly to strings in compressed format template -std::string serialize(const T& input) { - std::ostringstream out_archive_stream; +void serialize(const T& input, std::ostream & out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; +} + +template +void deserialize(std::istream & in_archive_stream, T& output) { + boost::archive::text_iarchive in_archive(in_archive_stream); + in_archive >> output; +} + +template +std::string serialize(const T& input) { + std::ostringstream out_archive_stream; + serialize(input, out_archive_stream); return out_archive_stream.str(); } template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); - boost::archive::text_iarchive in_archive(in_archive_stream); - in_archive >> output; + deserialize(in_archive_stream, output); } template @@ -63,8 +73,7 @@ bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::text_oarchive out_archive(out_archive_stream); - out_archive << input; + serialize(input, out_archive_stream); out_archive_stream.close(); return true; } @@ -74,31 +83,37 @@ bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::text_iarchive in_archive(in_archive_stream); - in_archive >> output; + deserialize(in_archive_stream, output); in_archive_stream.close(); return true; } // Serialization to XML format with named structures +template +void serializeXML(const T& input, std::ostream& out_archive_stream, + const std::string& name = "data") { + boost::archive::xml_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input); +} + +template +void deserializeXML(std::istream& in_archive_stream, T& output, + const std::string& name = "data") { + boost::archive::xml_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); +} + template std::string serializeXML(const T& input, const std::string& name="data") { std::ostringstream out_archive_stream; - // braces to flush out_archive as it goes out of scope before taking str() - // fixes crash with boost 1.66-1.68 - // see https://github.com/boostorg/serialization/issues/82 - { - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); - } + serializeXML(input, out_archive_stream, name); return out_archive_stream.str(); } template void deserializeXML(const std::string& serialized, T& output, const std::string& name="data") { std::istringstream in_archive_stream(serialized); - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeXML(in_archive_stream, output, name); } template @@ -106,10 +121,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std:: std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - { - boost::archive::xml_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); - } + serializeXML(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -119,28 +131,38 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - { - boost::archive::xml_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); - } + deserializeXML(in_archive_stream, output, name); in_archive_stream.close(); return true; } +// Serialization to binary format with named structures +template +void serializeBinary(const T& input, std::ostream& out_archive_stream, + const std::string& name = "data") { + boost::archive::binary_oarchive out_archive(out_archive_stream); + out_archive << boost::serialization::make_nvp(name.c_str(), input); +} + +template +void deserializeBinary(std::istream& in_archive_stream, T& output, + const std::string& name = "data") { + boost::archive::binary_iarchive in_archive(in_archive_stream); + in_archive >> boost::serialization::make_nvp(name.c_str(), output); +} + // Serialization to binary format with named structures template std::string serializeBinary(const T& input, const std::string& name="data") { std::ostringstream out_archive_stream; - boost::archive::binary_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); + serializeBinary(input, out_archive_stream, name); return out_archive_stream.str(); } template void deserializeBinary(const std::string& serialized, T& output, const std::string& name="data") { std::istringstream in_archive_stream(serialized); - boost::archive::binary_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeBinary(in_archive_stream, output, name); } template @@ -148,8 +170,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, const st std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - boost::archive::binary_oarchive out_archive(out_archive_stream); - out_archive << boost::serialization::make_nvp(name.c_str(), input); + serializeBinary(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -159,8 +180,7 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, const std std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - boost::archive::binary_iarchive in_archive(in_archive_stream); - in_archive >> boost::serialization::make_nvp(name.c_str(), output); + deserializeBinary(in_archive_stream, output, name); in_archive_stream.close(); return true; } From a4737d47066c0ee0e533bea393f4da14347e9abf Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 21:18:43 -0400 Subject: [PATCH 067/199] formatting to Google style --- gtsam/base/serialization.h | 78 +++++++++++++++++++------------------- 1 file changed, 40 insertions(+), 38 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 031ee3a3e..aaf06275c 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -43,46 +43,44 @@ namespace gtsam { // Serialization directly to strings in compressed format -template -void serialize(const T& input, std::ostream & out_archive_stream) { +template +void serialize(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } -template -void deserialize(std::istream & in_archive_stream, T& output) { +template +void deserialize(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } -template +template std::string serialize(const T& input) { std::ostringstream out_archive_stream; serialize(input, out_archive_stream); return out_archive_stream.str(); } -template +template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); deserialize(in_archive_stream, output); } -template +template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serialize(input, out_archive_stream); out_archive_stream.close(); return true; } -template +template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserialize(in_archive_stream, output); in_archive_stream.close(); return true; @@ -103,34 +101,36 @@ void deserializeXML(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } -template -std::string serializeXML(const T& input, const std::string& name="data") { +template +std::string serializeXML(const T& input, + const std::string& name = "data") { std::ostringstream out_archive_stream; serializeXML(input, out_archive_stream, name); return out_archive_stream.str(); } -template -void deserializeXML(const std::string& serialized, T& output, const std::string& name="data") { +template +void deserializeXML(const std::string& serialized, T& output, + const std::string& name = "data") { std::istringstream in_archive_stream(serialized); deserializeXML(in_archive_stream, output, name); } -template -bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name="data") { +template +bool serializeToXMLFile(const T& input, const std::string& filename, + const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serializeXML(input, out_archive_stream, name); out_archive_stream.close(); return true; } -template -bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name="data") { +template +bool deserializeFromXMLFile(const std::string& filename, T& output, + const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserializeXML(in_archive_stream, output, name); in_archive_stream.close(); return true; @@ -139,7 +139,7 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::s // Serialization to binary format with named structures template void serializeBinary(const T& input, std::ostream& out_archive_stream, - const std::string& name = "data") { + const std::string& name = "data") { boost::archive::binary_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); } @@ -152,37 +152,39 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, } // Serialization to binary format with named structures -template -std::string serializeBinary(const T& input, const std::string& name="data") { +template +std::string serializeBinary(const T& input, + const std::string& name = "data") { std::ostringstream out_archive_stream; serializeBinary(input, out_archive_stream, name); return out_archive_stream.str(); } -template -void deserializeBinary(const std::string& serialized, T& output, const std::string& name="data") { +template +void deserializeBinary(const std::string& serialized, T& output, + const std::string& name = "data") { std::istringstream in_archive_stream(serialized); deserializeBinary(in_archive_stream, output, name); } -template -bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name="data") { +template +bool serializeToBinaryFile(const T& input, const std::string& filename, + const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); - if (!out_archive_stream.is_open()) - return false; + if (!out_archive_stream.is_open()) return false; serializeBinary(input, out_archive_stream, name); out_archive_stream.close(); return true; } -template -bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name="data") { +template +bool deserializeFromBinaryFile(const std::string& filename, T& output, + const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); - if (!in_archive_stream.is_open()) - return false; + if (!in_archive_stream.is_open()) return false; deserializeBinary(in_archive_stream, output, name); in_archive_stream.close(); return true; } -} // \namespace gtsam +} // namespace gtsam From ca46ebfda81d8b54b1098cce83a41f0c664ee8b8 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 22 Jun 2020 20:20:50 -0500 Subject: [PATCH 068/199] added comments and removed unnecessary code --- cmake/GtsamCythonWrap.cmake | 8 ++++---- cython/CMakeLists.txt | 3 --- cython/scripts/install.sh | 10 +++++++++- 3 files changed, 13 insertions(+), 8 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 361038ce0..4cd061852 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -280,16 +280,16 @@ function(install_cython_files source_files dest_directory) endfunction() function(install_python_package install_path) -#TODO this will only work for Linux. Need to make it work on macOS and Windows as well -#TODO Running `sudo make install` makes this run in admin space causing Python 2.7 to be picked up. - # # go to cython directory and run setup.py - # install(CODE "execute_process(COMMAND sh \"-c\" \"cd ${package_path} && python setup.py install\")") + # Select the correct install script based on the OS if(CMAKE_SYSTEM_NAME STREQUAL "Windows") set(PYTHON_INSTALL_SCRIPT "install.bat") elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux" OR CMAKE_SYSTEM_NAME STREQUAL "Darwin") set(PYTHON_INSTALL_SCRIPT "install.sh") endif() + # Configure the variables in the script configure_file(${PROJECT_SOURCE_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT} ${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}) + + # Add the new make target command add_custom_target(python-install "${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}") endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 638bdfb2d..96503b82f 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,9 +45,6 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - # file(GLOB GTSAM_PYTHON_INSTALL_SCRIPTS "scripts/*") - # file(COPY ${GTSAM_PYTHON_INSTALL_SCRIPTS} DESTINATION ${PROJECT_BINARY_DIR}/cython/scripts) - install_python_package("${GTSAM_CYTHON_INSTALL_PATH}") endif () diff --git a/cython/scripts/install.sh b/cython/scripts/install.sh index 04759ca5e..8e409803d 100755 --- a/cython/scripts/install.sh +++ b/cython/scripts/install.sh @@ -1,15 +1,22 @@ #!/bin/sh + +# This script runs the installation flow for python wrapped GTSAM. +# It does so by first setting the correct ownership permissions on the package directory, +# and then running `python setup.py install` to install the wrapped package. + echo "Installing GTSAM Python Wrapper" +# Set the package path PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} +# Check if package directory exists. If not, print warning and exit. if [ ! -d "$PACKAGE_PATH" ] then echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; exit 1; fi -# set cython directory permissions to user so we don't get permission denied +# Set cython directory permissions to user so we don't get permission denied if [ "$(whoami)" != "root" ] then sudo chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} @@ -17,5 +24,6 @@ else chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} fi +# Run setup.py install with full paths echo "Running setup.py in $PACKAGE_PATH" ${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 82db82bbf5d46bb64dc50ba52507b39ee7f061ed Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Mon, 22 Jun 2020 23:08:39 -0400 Subject: [PATCH 069/199] fixed unit test failure on `testSerializationBase` object `output` was getting reused, but should be re-loaded into a "blank" object each time. --- gtsam/base/serializationTestHelpers.h | 46 ++++++++++++--------------- 1 file changed, 20 insertions(+), 26 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 602fd68f6..bac166e5b 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -44,8 +44,8 @@ T create() { // Creates or empties a folder in the build folder and returns the relative path boost::filesystem::path resetFilesystem( boost::filesystem::path folder = "actual") { - boost::filesystem::remove_all(folder); - boost::filesystem::create_directory(folder); + // boost::filesystem::remove_all(folder); + // boost::filesystem::create_directory(folder); return folder; } @@ -71,11 +71,10 @@ void roundtripFile(const T& input, T& output) { // This version requires equality operator template bool equality(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtrip(input,output); - if (input != output) return false; - roundtripFile(input,output); - return input==output; + roundtripFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -89,11 +88,10 @@ bool equalsObj(const T& input = T()) { // De-referenced version for pointers, requires equals method template bool equalsDereferenced(const T& input) { - T output = create(); + T output = create(), outputf = create(); roundtrip(input,output); - if (!input->equals(*output)) return false; - roundtripFile(input,output); - return input->equals(*output); + roundtripFile(input,outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } // Templated round-trip serialization using XML @@ -122,11 +120,10 @@ void roundtripXMLFile(const T& input, T& output) { // This version requires equality operator template bool equalityXML(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripXML(input,output); - if (input != output) return false; - roundtripXMLFile(input,output); - return input==output; + roundtripXMLFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -140,11 +137,10 @@ bool equalsXML(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedXML(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripXML(input,output); - if (!input->equals(*output)) return false; - roundtripXMLFile(input, output); - return input->equals(*output); + roundtripXMLFile(input, outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } // Templated round-trip serialization using XML @@ -171,11 +167,10 @@ void roundtripBinaryFile(const T& input, T& output) { // This version requires equality operator template bool equalityBinary(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripBinary(input,output); - if (input != output) return false; - roundtripBinaryFile(input,output); - return input==output; + roundtripBinaryFile(input,outputf); + return (input==output) && (input==outputf); } // This version requires Testable @@ -189,11 +184,10 @@ bool equalsBinary(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedBinary(const T& input = T()) { - T output = create(); + T output = create(), outputf = create(); roundtripBinary(input,output); - if (!input->equals(*output)) return false; - roundtripBinaryFile(input,output); - return input->equals(*output); + roundtripBinaryFile(input,outputf); + return (input->equals(*output)) && (input->equals(*outputf)); } } // \namespace serializationTestHelpers From a0a3b8f459df37349a7b4af7d6b52016142204cb Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Tue, 23 Jun 2020 09:52:29 -0400 Subject: [PATCH 070/199] reset filesystem - forgot to uncomment these after debugging --- gtsam/base/serializationTestHelpers.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index bac166e5b..5d67b2687 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -44,8 +44,8 @@ T create() { // Creates or empties a folder in the build folder and returns the relative path boost::filesystem::path resetFilesystem( boost::filesystem::path folder = "actual") { - // boost::filesystem::remove_all(folder); - // boost::filesystem::create_directory(folder); + boost::filesystem::remove_all(folder); + boost::filesystem::create_directory(folder); return folder; } From 3ea9ff012005b1205b8c20f5ea2b676d4054ce76 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Tue, 23 Jun 2020 07:58:38 -0700 Subject: [PATCH 071/199] optional initialization for LMParams --- gtsam/sfm/TranslationRecovery.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index 5eea251cf..634825d29 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -61,8 +61,9 @@ class TranslationRecovery { * @param relativeTranslations the relative translations, in world coordinate * frames, indexed in a map by a pair of Pose keys. */ - TranslationRecovery(const TranslationEdges& relativeTranslations) - : relativeTranslations_(relativeTranslations) { + TranslationRecovery(const TranslationEdges& relativeTranslations, + const LevenbergMarquardtParams& lmParams = LevenbergMarquardtParams()) + : relativeTranslations_(relativeTranslations), params_(lmParams) { params_.setVerbosityLM("Summary"); } From 9daeb39267f80bef157c0d11e60f371e57a179bb Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 23 Jun 2020 16:08:44 -0500 Subject: [PATCH 072/199] Set minimum supported numpy version to 1.11.0 (#366) * add deadsnakes ppa to install python3.6 on Ubuntu Xenial * updated travis distro to Ubuntu 18.04 bionic * Revert "updated travis distro to Ubuntu 18.04 bionic" This reverts commit 323264a924e8554da49c27a374e9a6278c5a659e. * restrict numpy version to be less than 1.19.0 * use ubuntu packaged numpy as baseline version to test against * downgrade minimum required version of numpy to version supported by Ubuntu Xenial * undo explicit pip install --- .travis.yml | 3 ++- cython/requirements.txt | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index ca6a426ea..d8094ef4d 100644 --- a/.travis.yml +++ b/.travis.yml @@ -14,7 +14,8 @@ addons: - clang-9 - build-essential pkg-config - cmake - - libpython-dev python-numpy + - python3-dev libpython-dev + - python3-numpy - libboost-all-dev # before_install: diff --git a/cython/requirements.txt b/cython/requirements.txt index cd77b097d..8d3c7aeb4 100644 --- a/cython/requirements.txt +++ b/cython/requirements.txt @@ -1,3 +1,3 @@ Cython>=0.25.2 backports_abc>=0.5 -numpy>=1.12.0 +numpy>=1.11.0 From b41809203f636878dbbc0aad718ac6f7343e82e6 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Tue, 23 Jun 2020 18:37:12 -0400 Subject: [PATCH 073/199] Revise comments --- gtsam/base/types.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 3abbdfe81..93c475c40 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -235,7 +235,8 @@ namespace gtsam { /** * A trait to mark classes that need special alignment. - * Please refer to https://github.com/PointCloudLibrary/pcl/pull/3163 + * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python + * wrappers to work properly. */ #if __cplusplus < 201703L template using void_t = void; From de7332fceac3224d4ea693a8f1631300b3345c74 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 02:39:44 -0400 Subject: [PATCH 074/199] remove file roundtrip test for pointers --- gtsam/base/serializationTestHelpers.h | 15 ++++++--------- 1 file changed, 6 insertions(+), 9 deletions(-) diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 5d67b2687..78f9d6d10 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -88,10 +88,9 @@ bool equalsObj(const T& input = T()) { // De-referenced version for pointers, requires equals method template bool equalsDereferenced(const T& input) { - T output = create(), outputf = create(); + T output = create(); roundtrip(input,output); - roundtripFile(input,outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } // Templated round-trip serialization using XML @@ -137,10 +136,9 @@ bool equalsXML(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedXML(const T& input = T()) { - T output = create(), outputf = create(); + T output = create(); roundtripXML(input,output); - roundtripXMLFile(input, outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } // Templated round-trip serialization using XML @@ -184,10 +182,9 @@ bool equalsBinary(const T& input = T()) { // This version is for pointers, requires equals method template bool equalsDereferencedBinary(const T& input = T()) { - T output = create(), outputf = create(); + T output = create(); roundtripBinary(input,output); - roundtripBinaryFile(input,outputf); - return (input->equals(*output)) && (input->equals(*outputf)); + return input->equals(*output); } } // \namespace serializationTestHelpers From 6972a5c9a70e5ff8eaa3f8b5b0f9392c2829a195 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 11:06:01 -0500 Subject: [PATCH 075/199] updated comments in shell script --- cython/scripts/install.sh | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/cython/scripts/install.sh b/cython/scripts/install.sh index 8e409803d..fdf86f130 100755 --- a/cython/scripts/install.sh +++ b/cython/scripts/install.sh @@ -11,12 +11,13 @@ PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} # Check if package directory exists. If not, print warning and exit. if [ ! -d "$PACKAGE_PATH" ] -then +then echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; exit 1; fi -# Set cython directory permissions to user so we don't get permission denied +# Set cython directory permissions to user so we don't get permission denied. +# This also works inside Docker containers. if [ "$(whoami)" != "root" ] then sudo chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} @@ -24,6 +25,6 @@ else chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} fi -# Run setup.py install with full paths +# Run setup.py install with full paths. echo "Running setup.py in $PACKAGE_PATH" ${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 530016edf00e9a56cbdb4de27ce612580337a66a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 11:06:35 -0500 Subject: [PATCH 076/199] added Windows batch script to install python wrapped package --- cython/scripts/install.bat | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/cython/scripts/install.bat b/cython/scripts/install.bat index e69de29bb..4dbd2051f 100755 --- a/cython/scripts/install.bat +++ b/cython/scripts/install.bat @@ -0,0 +1,18 @@ +:: This script runs the installation flow for python wrapped GTSAM. +:: It does so by running `python setup.py install` to install the wrapped package. + +echo "Installing GTSAM Python Wrapper" + +:: Set the package path +PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} + +:: Check if package directory exists. If not, print warning and exit. +if [ ! -d "$PACKAGE_PATH" ] +then + echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; + exit 1; +fi + +:: Run setup.py install with full paths. +echo "Running setup.py in $PACKAGE_PATH" +${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 7d7475b881ffc9f21ce2f49c3e4d3890e9e6d21f Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 14:15:46 -0400 Subject: [PATCH 077/199] Style fixes as commented by @dellaert --- gtsam/base/make_shared.h | 22 +++++++++++++--------- gtsam/base/types.h | 19 ++++++++++--------- 2 files changed, 23 insertions(+), 18 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index 966dd516d..c7d98cdee 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -25,27 +25,31 @@ #include -#if __cplusplus <= 201103L namespace gtsam { template using enable_if_t = typename std::enable_if::type; } -#endif namespace gtsam { - /// Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + /** Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + * This solves the problem with the stock `make_shared` that custom alignment is not respected, causing SEGFAULTs + * at runtime, which is notoriously hard to debug. + * + * @tparam T The type of object being constructed + * @tparam Args Type of the arguments of the constructor + * @param args Arguments of the constructor + * @return The object created as a boost::shared_ptr + */ template - gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) - { - return boost::allocate_shared(Eigen::aligned_allocator(), std::forward (args)...); + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args &&... args) { + return boost::allocate_shared(Eigen::aligned_allocator(), std::forward(args)...); } /// Fall back to the boost version if no need for alignment template - gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args&&... args) - { - return boost::make_shared(std::forward (args)...); + gtsam::enable_if_t::value, boost::shared_ptr> make_shared(Args &&... args) { + return boost::make_shared(std::forward(args)...); } } diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 93c475c40..a4b2fb6ea 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -233,27 +233,28 @@ namespace std { namespace gtsam { + /// Convenience void_t as we assume C++11, it will not conflict the std one in C++17 as this is in `gtsam::` + template using void_t = void; + /** - * A trait to mark classes that need special alignment. + * A SFINAE trait to mark classes that need special alignment. * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python * wrappers to work properly. */ -#if __cplusplus < 201703L - template using void_t = void; -#endif - template> - struct has_custom_allocator : std::false_type { + struct needs_eigen_aligned_allocator : std::false_type { }; template - struct has_custom_allocator> : std::true_type { + struct needs_eigen_aligned_allocator> : std::true_type { }; } /** - * This is necessary for the Cython wrapper to work properly, and possibly reduce future misalignment problems. + * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned + * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for details */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ - using _custom_allocator_type_trait = void; \ No newline at end of file + using _eigen_aligned_allocator_trait = void; From 6d75e992e896f54a1bd3956ff5f8cd1dddf5e814 Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 14:16:00 -0400 Subject: [PATCH 078/199] serialization docstrings --- gtsam/base/serialization.h | 37 ++++++++++++++++++++++++--- gtsam/base/serializationTestHelpers.h | 17 +----------- 2 files changed, 34 insertions(+), 20 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index aaf06275c..1a319ab17 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -42,19 +42,25 @@ namespace gtsam { -// Serialization directly to strings in compressed format +/** @name Standard serialization + * Serialization in default compressed format + */ +///@{ +/// serializes to a stream template void serialize(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } +/// deserializes from a stream template void deserialize(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } +/// serializes to a string template std::string serialize(const T& input) { std::ostringstream out_archive_stream; @@ -62,12 +68,14 @@ std::string serialize(const T& input) { return out_archive_stream.str(); } +/// deserializes from a string template void deserialize(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); deserialize(in_archive_stream, output); } +/// serializes to a file template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); @@ -77,6 +85,7 @@ bool serializeToFile(const T& input, const std::string& filename) { return true; } +/// deserializes from a file template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); @@ -85,8 +94,13 @@ bool deserializeFromFile(const std::string& filename, T& output) { in_archive_stream.close(); return true; } +///@} -// Serialization to XML format with named structures +/** @name XML Serialization + * Serialization to XML format with named structures + */ +///@{ +/// serializes to a stream in XML template void serializeXML(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { @@ -94,6 +108,7 @@ void serializeXML(const T& input, std::ostream& out_archive_stream, out_archive << boost::serialization::make_nvp(name.c_str(), input); } +/// deserializes from a stream in XML template void deserializeXML(std::istream& in_archive_stream, T& output, const std::string& name = "data") { @@ -101,6 +116,7 @@ void deserializeXML(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } +/// serializes to a string in XML template std::string serializeXML(const T& input, const std::string& name = "data") { @@ -109,6 +125,7 @@ std::string serializeXML(const T& input, return out_archive_stream.str(); } +/// deserializes from a string in XML template void deserializeXML(const std::string& serialized, T& output, const std::string& name = "data") { @@ -116,6 +133,7 @@ void deserializeXML(const std::string& serialized, T& output, deserializeXML(in_archive_stream, output, name); } +/// serializes to an XML file template bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name = "data") { @@ -126,6 +144,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, return true; } +/// deserializes from an XML file template bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name = "data") { @@ -135,8 +154,13 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, in_archive_stream.close(); return true; } +///@} -// Serialization to binary format with named structures +/** @name Binary Serialization + * Serialization to binary format with named structures + */ +///@{ +/// serializes to a stream in binary template void serializeBinary(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { @@ -144,6 +168,7 @@ void serializeBinary(const T& input, std::ostream& out_archive_stream, out_archive << boost::serialization::make_nvp(name.c_str(), input); } +/// deserializes from a stream in binary template void deserializeBinary(std::istream& in_archive_stream, T& output, const std::string& name = "data") { @@ -151,7 +176,7 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, in_archive >> boost::serialization::make_nvp(name.c_str(), output); } -// Serialization to binary format with named structures +/// serializes to a string in binary template std::string serializeBinary(const T& input, const std::string& name = "data") { @@ -160,6 +185,7 @@ std::string serializeBinary(const T& input, return out_archive_stream.str(); } +/// deserializes from a string in binary template void deserializeBinary(const std::string& serialized, T& output, const std::string& name = "data") { @@ -167,6 +193,7 @@ void deserializeBinary(const std::string& serialized, T& output, deserializeBinary(in_archive_stream, output, name); } +/// serializes to a binary file template bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name = "data") { @@ -177,6 +204,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, return true; } +/// deserializes from a binary file template bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name = "data") { @@ -186,5 +214,6 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, in_archive_stream.close(); return true; } +///@} } // namespace gtsam diff --git a/gtsam/base/serializationTestHelpers.h b/gtsam/base/serializationTestHelpers.h index 78f9d6d10..5994a5e51 100644 --- a/gtsam/base/serializationTestHelpers.h +++ b/gtsam/base/serializationTestHelpers.h @@ -52,10 +52,8 @@ boost::filesystem::path resetFilesystem( // Templated round-trip serialization template void roundtrip(const T& input, T& output) { - // Serialize std::string serialized = serialize(input); if (verbose) std::cout << serialized << std::endl << std::endl; - deserialize(serialized, output); } @@ -63,12 +61,11 @@ void roundtrip(const T& input, T& output) { template void roundtripFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.dat"; - serializeToFile(input, path.string()); deserializeFromFile(path.string(), output); } -// This version requires equality operator +// This version requires equality operator and uses string and file round-trips template bool equality(const T& input = T()) { T output = create(), outputf = create(); @@ -96,11 +93,8 @@ bool equalsDereferenced(const T& input) { // Templated round-trip serialization using XML template void roundtripXML(const T& input, T& output) { - // Serialize std::string serialized = serializeXML(input); if (verbose) std::cout << serialized << std::endl << std::endl; - - // De-serialize deserializeXML(serialized, output); } @@ -108,11 +102,7 @@ void roundtripXML(const T& input, T& output) { template void roundtripXMLFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.xml"; - - // Serialize serializeToXMLFile(input, path.string()); - - // De-serialize deserializeFromXMLFile(path.string(), output); } @@ -144,11 +134,8 @@ bool equalsDereferencedXML(const T& input = T()) { // Templated round-trip serialization using XML template void roundtripBinary(const T& input, T& output) { - // Serialize std::string serialized = serializeBinary(input); if (verbose) std::cout << serialized << std::endl << std::endl; - - // De-serialize deserializeBinary(serialized, output); } @@ -156,9 +143,7 @@ void roundtripBinary(const T& input, T& output) { template void roundtripBinaryFile(const T& input, T& output) { boost::filesystem::path path = resetFilesystem()/"graph.bin"; - // Serialize serializeToBinaryFile(input, path.string()); - // De-serialize deserializeFromBinaryFile(path.string(), output); } From b37be7d640567be9b78c699d158c88035d4f789e Mon Sep 17 00:00:00 2001 From: Gerry Chen Date: Wed, 24 Jun 2020 14:33:08 -0400 Subject: [PATCH 079/199] rename serialization functions with less ambiguous names According to Varun's suggestion. Note: string functions should be automatically inlined by compiler to avoid passing big strings. --- gtsam/base/serialization.h | 88 +++++++++++++++++++++++++++----------- 1 file changed, 64 insertions(+), 24 deletions(-) diff --git a/gtsam/base/serialization.h b/gtsam/base/serialization.h index 1a319ab17..f589ecc5e 100644 --- a/gtsam/base/serialization.h +++ b/gtsam/base/serialization.h @@ -48,31 +48,31 @@ namespace gtsam { ///@{ /// serializes to a stream template -void serialize(const T& input, std::ostream& out_archive_stream) { +void serializeToStream(const T& input, std::ostream& out_archive_stream) { boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << input; } /// deserializes from a stream template -void deserialize(std::istream& in_archive_stream, T& output) { +void deserializeFromStream(std::istream& in_archive_stream, T& output) { boost::archive::text_iarchive in_archive(in_archive_stream); in_archive >> output; } /// serializes to a string template -std::string serialize(const T& input) { +std::string serializeToString(const T& input) { std::ostringstream out_archive_stream; - serialize(input, out_archive_stream); + serializeToStream(input, out_archive_stream); return out_archive_stream.str(); } /// deserializes from a string template -void deserialize(const std::string& serialized, T& output) { +void deserializeFromString(const std::string& serialized, T& output) { std::istringstream in_archive_stream(serialized); - deserialize(in_archive_stream, output); + deserializeFromStream(in_archive_stream, output); } /// serializes to a file @@ -80,7 +80,7 @@ template bool serializeToFile(const T& input, const std::string& filename) { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serialize(input, out_archive_stream); + serializeToStream(input, out_archive_stream); out_archive_stream.close(); return true; } @@ -90,10 +90,22 @@ template bool deserializeFromFile(const std::string& filename, T& output) { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserialize(in_archive_stream, output); + deserializeFromStream(in_archive_stream, output); in_archive_stream.close(); return true; } + +/// serializes to a string +template +std::string serialize(const T& input) { + return serializeToString(input); +} + +/// deserializes from a string +template +void deserialize(const std::string& serialized, T& output) { + deserializeFromString(serialized, output); +} ///@} /** @name XML Serialization @@ -102,7 +114,7 @@ bool deserializeFromFile(const std::string& filename, T& output) { ///@{ /// serializes to a stream in XML template -void serializeXML(const T& input, std::ostream& out_archive_stream, +void serializeToXMLStream(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { boost::archive::xml_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); @@ -110,7 +122,7 @@ void serializeXML(const T& input, std::ostream& out_archive_stream, /// deserializes from a stream in XML template -void deserializeXML(std::istream& in_archive_stream, T& output, +void deserializeFromXMLStream(std::istream& in_archive_stream, T& output, const std::string& name = "data") { boost::archive::xml_iarchive in_archive(in_archive_stream); in_archive >> boost::serialization::make_nvp(name.c_str(), output); @@ -118,19 +130,19 @@ void deserializeXML(std::istream& in_archive_stream, T& output, /// serializes to a string in XML template -std::string serializeXML(const T& input, +std::string serializeToXMLString(const T& input, const std::string& name = "data") { std::ostringstream out_archive_stream; - serializeXML(input, out_archive_stream, name); + serializeToXMLStream(input, out_archive_stream, name); return out_archive_stream.str(); } /// deserializes from a string in XML template -void deserializeXML(const std::string& serialized, T& output, +void deserializeFromXMLString(const std::string& serialized, T& output, const std::string& name = "data") { std::istringstream in_archive_stream(serialized); - deserializeXML(in_archive_stream, output, name); + deserializeFromXMLStream(in_archive_stream, output, name); } /// serializes to an XML file @@ -139,7 +151,7 @@ bool serializeToXMLFile(const T& input, const std::string& filename, const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serializeXML(input, out_archive_stream, name); + serializeToXMLStream(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -150,10 +162,24 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserializeXML(in_archive_stream, output, name); + deserializeFromXMLStream(in_archive_stream, output, name); in_archive_stream.close(); return true; } + +/// serializes to a string in XML +template +std::string serializeXML(const T& input, + const std::string& name = "data") { + return serializeToXMLString(input, name); +} + +/// deserializes from a string in XML +template +void deserializeXML(const std::string& serialized, T& output, + const std::string& name = "data") { + deserializeFromXMLString(serialized, output, name); +} ///@} /** @name Binary Serialization @@ -162,7 +188,7 @@ bool deserializeFromXMLFile(const std::string& filename, T& output, ///@{ /// serializes to a stream in binary template -void serializeBinary(const T& input, std::ostream& out_archive_stream, +void serializeToBinaryStream(const T& input, std::ostream& out_archive_stream, const std::string& name = "data") { boost::archive::binary_oarchive out_archive(out_archive_stream); out_archive << boost::serialization::make_nvp(name.c_str(), input); @@ -170,7 +196,7 @@ void serializeBinary(const T& input, std::ostream& out_archive_stream, /// deserializes from a stream in binary template -void deserializeBinary(std::istream& in_archive_stream, T& output, +void deserializeFromBinaryStream(std::istream& in_archive_stream, T& output, const std::string& name = "data") { boost::archive::binary_iarchive in_archive(in_archive_stream); in_archive >> boost::serialization::make_nvp(name.c_str(), output); @@ -178,19 +204,19 @@ void deserializeBinary(std::istream& in_archive_stream, T& output, /// serializes to a string in binary template -std::string serializeBinary(const T& input, +std::string serializeToBinaryString(const T& input, const std::string& name = "data") { std::ostringstream out_archive_stream; - serializeBinary(input, out_archive_stream, name); + serializeToBinaryStream(input, out_archive_stream, name); return out_archive_stream.str(); } /// deserializes from a string in binary template -void deserializeBinary(const std::string& serialized, T& output, +void deserializeFromBinaryString(const std::string& serialized, T& output, const std::string& name = "data") { std::istringstream in_archive_stream(serialized); - deserializeBinary(in_archive_stream, output, name); + deserializeFromBinaryStream(in_archive_stream, output, name); } /// serializes to a binary file @@ -199,7 +225,7 @@ bool serializeToBinaryFile(const T& input, const std::string& filename, const std::string& name = "data") { std::ofstream out_archive_stream(filename.c_str()); if (!out_archive_stream.is_open()) return false; - serializeBinary(input, out_archive_stream, name); + serializeToBinaryStream(input, out_archive_stream, name); out_archive_stream.close(); return true; } @@ -210,10 +236,24 @@ bool deserializeFromBinaryFile(const std::string& filename, T& output, const std::string& name = "data") { std::ifstream in_archive_stream(filename.c_str()); if (!in_archive_stream.is_open()) return false; - deserializeBinary(in_archive_stream, output, name); + deserializeFromBinaryStream(in_archive_stream, output, name); in_archive_stream.close(); return true; } + +/// serializes to a string in binary +template +std::string serializeBinary(const T& input, + const std::string& name = "data") { + return serializeToBinaryString(input, name); +} + +/// deserializes from a string in binary +template +void deserializeBinary(const std::string& serialized, T& output, + const std::string& name = "data") { + deserializeFromBinaryString(serialized, output, name); +} ///@} } // namespace gtsam From efde078b944e1865ea9e53e68726c48c5cf2d2e7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 14:05:17 -0500 Subject: [PATCH 080/199] pure CMake script to install Python wrapper after compiling --- cmake/GtsamCythonWrap.cmake | 15 --------------- cython/CMakeLists.txt | 3 ++- cython/scripts/install.bat | 18 ------------------ cython/scripts/install.sh | 30 ------------------------------ 4 files changed, 2 insertions(+), 64 deletions(-) delete mode 100755 cython/scripts/install.bat delete mode 100755 cython/scripts/install.sh diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 4cd061852..6331d1e95 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -278,18 +278,3 @@ function(install_cython_files source_files dest_directory) endif() endfunction() - -function(install_python_package install_path) - # Select the correct install script based on the OS - if(CMAKE_SYSTEM_NAME STREQUAL "Windows") - set(PYTHON_INSTALL_SCRIPT "install.bat") - elseif(CMAKE_SYSTEM_NAME STREQUAL "Linux" OR CMAKE_SYSTEM_NAME STREQUAL "Darwin") - set(PYTHON_INSTALL_SCRIPT "install.sh") - endif() - - # Configure the variables in the script - configure_file(${PROJECT_SOURCE_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT} ${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}) - - # Add the new make target command - add_custom_target(python-install "${PROJECT_BINARY_DIR}/cython/scripts/${PYTHON_INSTALL_SCRIPT}") -endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 96503b82f..bce9f2308 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,6 +45,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - install_python_package("${GTSAM_CYTHON_INSTALL_PATH}") + # Add the new make target command + add_custom_target(python-install COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install) endif () diff --git a/cython/scripts/install.bat b/cython/scripts/install.bat deleted file mode 100755 index 4dbd2051f..000000000 --- a/cython/scripts/install.bat +++ /dev/null @@ -1,18 +0,0 @@ -:: This script runs the installation flow for python wrapped GTSAM. -:: It does so by running `python setup.py install` to install the wrapped package. - -echo "Installing GTSAM Python Wrapper" - -:: Set the package path -PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} - -:: Check if package directory exists. If not, print warning and exit. -if [ ! -d "$PACKAGE_PATH" ] -then - echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; - exit 1; -fi - -:: Run setup.py install with full paths. -echo "Running setup.py in $PACKAGE_PATH" -${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install diff --git a/cython/scripts/install.sh b/cython/scripts/install.sh deleted file mode 100755 index fdf86f130..000000000 --- a/cython/scripts/install.sh +++ /dev/null @@ -1,30 +0,0 @@ -#!/bin/sh - -# This script runs the installation flow for python wrapped GTSAM. -# It does so by first setting the correct ownership permissions on the package directory, -# and then running `python setup.py install` to install the wrapped package. - -echo "Installing GTSAM Python Wrapper" - -# Set the package path -PACKAGE_PATH=${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG} - -# Check if package directory exists. If not, print warning and exit. -if [ ! -d "$PACKAGE_PATH" ] -then - echo "Directory $PACKAGE_PATH DOES NOT exist. Please run 'make install' first."; - exit 1; -fi - -# Set cython directory permissions to user so we don't get permission denied. -# This also works inside Docker containers. -if [ "$(whoami)" != "root" ] -then - sudo chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} -else - chown -R $(logname) ${GTSAM_CYTHON_INSTALL_PATH} -fi - -# Run setup.py install with full paths. -echo "Running setup.py in $PACKAGE_PATH" -${PYTHON_EXECUTABLE} $PACKAGE_PATH/setup.py install From 9698b032537e9a74a6414ff46e09f9cdef196bab Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 14:06:25 -0500 Subject: [PATCH 081/199] removed extra line --- cmake/GtsamCythonWrap.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 6331d1e95..b6c4c2856 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -277,4 +277,4 @@ function(install_cython_files source_files dest_directory) install(FILES "${source_files}" DESTINATION "${dest_directory}") endif() -endfunction() +endfunction() \ No newline at end of file From 5feaf6dd9da35b9a347dc5c0d006c72ab0a3f2d4 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 14:07:28 -0500 Subject: [PATCH 082/199] reset to previous version --- cmake/GtsamCythonWrap.cmake | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index b6c4c2856..6331d1e95 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -277,4 +277,4 @@ function(install_cython_files source_files dest_directory) install(FILES "${source_files}" DESTINATION "${dest_directory}") endif() -endfunction() \ No newline at end of file +endfunction() From 6dbd7c243abc91489c010261bde27685c491acac Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 16:25:46 -0400 Subject: [PATCH 083/199] Add comments --- gtsam/base/make_shared.h | 14 +++++++++++++- gtsam/base/types.h | 12 +++++++++++- 2 files changed, 24 insertions(+), 2 deletions(-) diff --git a/gtsam/base/make_shared.h b/gtsam/base/make_shared.h index c7d98cdee..5281eec6d 100644 --- a/gtsam/base/make_shared.h +++ b/gtsam/base/make_shared.h @@ -26,16 +26,28 @@ #include namespace gtsam { + /// An shorthand alias for accessing the ::type inside std::enable_if that can be used in a template directly template using enable_if_t = typename std::enable_if::type; } namespace gtsam { - /** Add our own `make_shared` as a layer of wrapping on `boost::make_shared` + /** + * Add our own `make_shared` as a layer of wrapping on `boost::make_shared` * This solves the problem with the stock `make_shared` that custom alignment is not respected, causing SEGFAULTs * at runtime, which is notoriously hard to debug. * + * Explanation + * =============== + * The template `needs_eigen_aligned_allocator::value` will evaluate to `std::true_type` if the type alias + * `_eigen_aligned_allocator_trait = void` is present in a class, which is automatically added by the + * `GTSAM_MAKE_ALIGNED_OPERATOR_NEW` macro. + * + * This function declaration will only be taken when the above condition is true, so if some object does not need to + * be aligned, `gtsam::make_shared` will fall back to the next definition, which is a simple wrapper for + * `boost::make_shared`. + * * @tparam T The type of object being constructed * @tparam Args Type of the arguments of the constructor * @param args Arguments of the constructor diff --git a/gtsam/base/types.h b/gtsam/base/types.h index a4b2fb6ea..b54cc2f2a 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -238,8 +238,18 @@ namespace gtsam { /** * A SFINAE trait to mark classes that need special alignment. + * * This is required to make boost::make_shared and etc respect alignment, which is essential for the Python * wrappers to work properly. + * + * Explanation + * ============= + * When a GTSAM type is not declared with the type alias `_eigen_aligned_allocator_trait = void`, the first template + * will be taken so `needs_eigen_aligned_allocator` will be resolved to `std::false_type`. + * + * Otherwise, it will resolve to the second template, which will be resolved to `std::true_type`. + * + * Please refer to `gtsam/base/make_shared.h` for an example. */ template> struct needs_eigen_aligned_allocator : std::false_type { @@ -253,7 +263,7 @@ namespace gtsam { /** * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. - * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for details + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for detailed explanation. */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ From fb21c553a05555ce4be3de305836d62fa1113bbe Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 24 Jun 2020 17:15:00 -0400 Subject: [PATCH 084/199] Switch to the new alignment marker type --- gtsam/base/GenericValue.h | 2 +- gtsam/base/Manifold.h | 2 +- gtsam/base/types.h | 9 +++++++++ gtsam/geometry/BearingRange.h | 2 +- gtsam/geometry/CameraSet.h | 2 +- gtsam/geometry/EssentialMatrix.h | 2 +- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 4 ++-- gtsam/geometry/Pose2.h | 2 +- gtsam/geometry/Pose3.h | 2 +- gtsam/geometry/Rot3.h | 2 +- gtsam/geometry/SOn.h | 2 +- gtsam/geometry/Unit3.h | 2 +- gtsam/geometry/triangulation.h | 2 +- gtsam/navigation/AttitudeFactor.h | 4 ++-- gtsam/navigation/CombinedImuFactor.h | 6 +++--- gtsam/navigation/ImuBias.h | 2 +- gtsam/navigation/PreintegratedRotation.h | 4 ++-- gtsam/navigation/PreintegrationBase.h | 2 +- gtsam/navigation/PreintegrationParams.h | 2 +- gtsam/navigation/TangentPreintegration.h | 2 +- gtsam/nonlinear/ExpressionFactor.h | 2 +- gtsam/nonlinear/NonlinearEquality.h | 6 +++--- gtsam/nonlinear/PriorFactor.h | 2 +- gtsam/nonlinear/internal/ExpressionNode.h | 2 +- gtsam/slam/BetweenFactor.h | 2 +- gtsam/slam/EssentialMatrixConstraint.h | 2 +- gtsam/slam/EssentialMatrixFactor.h | 6 +++--- gtsam/slam/ProjectionFactor.h | 2 +- gtsam/slam/RotateFactor.h | 2 +- gtsam/slam/SmartFactorBase.h | 2 +- 31 files changed, 48 insertions(+), 39 deletions(-) diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index e1cb3bc2c..2ac3eb80c 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -181,7 +181,7 @@ public: // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; /// use this macro instead of BOOST_CLASS_EXPORT for GenericValues diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index f3653f099..9feb2b451 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -214,7 +214,7 @@ public: enum { NeedsToAlign = (sizeof(M1) % 16) == 0 || (sizeof(M2) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Define any direct product group to be a model of the multiplicative Group concept diff --git a/gtsam/base/types.h b/gtsam/base/types.h index b54cc2f2a..924f339b3 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -268,3 +268,12 @@ namespace gtsam { #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ using _eigen_aligned_allocator_trait = void; + +/** + * This marks a GTSAM object to require alignment. With this macro an object will automatically be allocated in aligned + * memory when one uses `gtsam::make_shared`. It reduces future misalignment problems that is hard to debug. + * See https://eigen.tuxfamily.org/dox/group__DenseMatrixManipulation__Alignement.html for detailed explanation. + */ +#define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ + using _eigen_aligned_allocator_trait = void; \ No newline at end of file diff --git a/gtsam/geometry/BearingRange.h b/gtsam/geometry/BearingRange.h index 7c73f3cbd..8db7abffe 100644 --- a/gtsam/geometry/BearingRange.h +++ b/gtsam/geometry/BearingRange.h @@ -162,7 +162,7 @@ private: NeedsToAlign = (sizeof(B) % 16) == 0 || (sizeof(R) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // Declare this to be both Testable and a Manifold diff --git a/gtsam/geometry/CameraSet.h b/gtsam/geometry/CameraSet.h index ecf9a572d..feab8e0fa 100644 --- a/gtsam/geometry/CameraSet.h +++ b/gtsam/geometry/CameraSet.h @@ -319,7 +319,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; template diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index 3235fdedd..ca719eb37 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -212,7 +212,7 @@ class EssentialMatrix { /// @} public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; template<> diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index c52127a45..9a80b937b 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -325,7 +325,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // manifold traits diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 935962423..60088577c 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -222,7 +222,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // end of class PinholeBaseK @@ -425,7 +425,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // end of class PinholePose diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index 388318827..2a1f108ca 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -317,7 +317,7 @@ public: public: // Align for Point2, which is either derived from, or is typedef, of Vector2 - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // Pose2 /** specialization for pose2 wedge function (generic template in Lie.h) */ diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index fa55f98de..ced3b904b 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -355,7 +355,7 @@ public: #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; // Pose3 class diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index fc3a8b3f2..8f24f07c8 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -544,7 +544,7 @@ namespace gtsam { #ifdef GTSAM_USE_QUATERNIONS // only align if quaternion, Matrix3 has no alignment requirements public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 767b12020..a08f87783 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -54,7 +54,7 @@ class SO : public LieGroup, internal::DimensionSO(N)> { using VectorN2 = Eigen::Matrix; using MatrixDD = Eigen::Matrix; - GTSAM_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(true) protected: MatrixNN matrix_; ///< Rotation matrix diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index f1a9c1a69..b80e6e4d8 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -214,7 +214,7 @@ private: /// @} public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // Define GTSAM traits diff --git a/gtsam/geometry/triangulation.h b/gtsam/geometry/triangulation.h index 586b7b165..8cdf0fdc0 100644 --- a/gtsam/geometry/triangulation.h +++ b/gtsam/geometry/triangulation.h @@ -215,7 +215,7 @@ struct CameraProjectionMatrix { private: const Matrix3 K_; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index db588008e..5a0031caf 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -139,7 +139,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits @@ -219,7 +219,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index ca9b2ca1a..6b3bf979a 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -100,7 +100,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; @@ -210,7 +210,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -332,7 +332,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // class CombinedImuFactor diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index ff1a53025..d52b4eb29 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -171,7 +171,7 @@ private: public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW /// @} }; // ConstantBias class diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 71ef5d08f..12938a625 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -69,7 +69,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; @@ -182,7 +182,7 @@ class GTSAM_EXPORT PreintegratedRotation { #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index 9926d207a..eb30c1f13 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -214,7 +214,7 @@ class GTSAM_EXPORT PreintegrationBase { #endif public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 962fef277..4bff625ca 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -84,7 +84,7 @@ protected: #ifdef GTSAM_USE_QUATERNIONS // Align if we are using Quaternions public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW #endif }; diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 11945e53a..edf76e562 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -141,7 +141,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } /// namespace gtsam diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 04d82fe9a..c42b2bdfc 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -209,7 +209,7 @@ private: // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // ExpressionFactor diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index d4eb655c3..1bba57051 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -175,7 +175,7 @@ public: /// @} - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: @@ -265,7 +265,7 @@ public: traits::Print(value_, "Value"); } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: @@ -331,7 +331,7 @@ public: return traits::Local(x1,x2); } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW private: diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 8d8c67d5c..0afbaa588 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -114,7 +114,7 @@ namespace gtsam { // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(T) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; } /// namespace gtsam diff --git a/gtsam/nonlinear/internal/ExpressionNode.h b/gtsam/nonlinear/internal/ExpressionNode.h index 0011efb74..0ae37f130 100644 --- a/gtsam/nonlinear/internal/ExpressionNode.h +++ b/gtsam/nonlinear/internal/ExpressionNode.h @@ -150,7 +150,7 @@ public: return constant_; } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; //----------------------------------------------------------------------------- diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index 23138b9e6..b1d4904aa 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -126,7 +126,7 @@ namespace gtsam { // Alignment, see https://eigen.tuxfamily.org/dox/group__TopicStructHavingEigenMembers.html enum { NeedsToAlign = (sizeof(VALUE) % 16) == 0 }; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) + GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) }; // \class BetweenFactor /// traits diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index 179200fe1..e474ce5b3 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -105,7 +105,7 @@ private: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // \class EssentialMatrixConstraint diff --git a/gtsam/slam/EssentialMatrixFactor.h b/gtsam/slam/EssentialMatrixFactor.h index 8bd155a14..c214a2f48 100644 --- a/gtsam/slam/EssentialMatrixFactor.h +++ b/gtsam/slam/EssentialMatrixFactor.h @@ -81,7 +81,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /** @@ -201,7 +201,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // EssentialMatrixFactor2 @@ -286,7 +286,7 @@ public: } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; // EssentialMatrixFactor3 diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 856913aae..0bed15fdc 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -189,7 +189,7 @@ namespace gtsam { } public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; /// traits diff --git a/gtsam/slam/RotateFactor.h b/gtsam/slam/RotateFactor.h index b6ccc36a2..948fffe13 100644 --- a/gtsam/slam/RotateFactor.h +++ b/gtsam/slam/RotateFactor.h @@ -113,7 +113,7 @@ public: return error; } - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; } // namespace gtsam diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 34f9b9e9f..717a9c1f2 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -81,7 +81,7 @@ protected: mutable FBlocks Fs; public: - EIGEN_MAKE_ALIGNED_OPERATOR_NEW + GTSAM_MAKE_ALIGNED_OPERATOR_NEW /// shorthand for a smart pointer to a factor typedef boost::shared_ptr shared_ptr; From 2475e6c68c6581cce518f22c8d6683c857b0fc1b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 17:44:03 -0500 Subject: [PATCH 085/199] Load Cython requirements file instead of reading it in cmake --- cython/CMakeLists.txt | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index bce9f2308..0d2af6a33 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -32,8 +32,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) ) endif() - file(READ "${PROJECT_SOURCE_DIR}/cython/requirements.txt" CYTHON_INSTALL_REQUIREMENTS) - file(READ "${PROJECT_SOURCE_DIR}/README.md" README_CONTENTS) + set(CYTHON_INSTALL_REQUIREMENTS_FILE "${PROJECT_SOURCE_DIR}/cython/requirements.txt") # Install the custom-generated __init__.py # This is to make the build/cython/gtsam folder a python package, so gtsam can be found while wrapping gtsam_unstable From 453d3a74164613375a083566eea9f8b16c782d74 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 18:11:24 -0500 Subject: [PATCH 086/199] Added cmake variable GTSAM_CYTHON_INSTALL_FULLPATH to include build tag directly --- CMakeLists.txt | 4 +++- cmake/GtsamCythonWrap.cmake | 2 +- cython/gtsam_eigency/CMakeLists.txt | 8 ++++---- 3 files changed, 8 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a810ac9df..2cbdbf00c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -458,7 +458,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) if(NOT GTSAM_CYTHON_INSTALL_PATH) set(GTSAM_CYTHON_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/cython") endif() - set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) + # Cython install path appended with Build type (e.g. cython, cythonDebug, etc). + set(GTSAM_CYTHON_INSTALL_FULLPATH "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}") + set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) add_subdirectory(cython) else() set(GTSAM_INSTALL_CYTHON_TOOLBOX 0) # This will go into config.h diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 6331d1e95..851f53cfe 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -184,7 +184,7 @@ function(install_cython_wrapped_library interface_header generated_files_path in # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH/subdirectory if there is one get_filename_component(location "${install_path}" PATH) get_filename_component(name "${install_path}" NAME) - message(STATUS "Installing Cython Toolbox to ${location}${GTSAM_BUILD_TAG}/${name}") #${GTSAM_CYTHON_INSTALL_PATH}" + message(STATUS "Installing Cython Toolbox to ${location}${GTSAM_BUILD_TAG}/${name}") #${GTSAM_CYTHON_INSTALL_FULLPATH}" if(GTSAM_BUILD_TYPE_POSTFIXES) foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 77bead834..da174d690 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -39,11 +39,11 @@ add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigen # install install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}" + DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}" PATTERN "CMakeLists.txt" EXCLUDE PATTERN "__init__.py.in" EXCLUDE) install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency") -install(FILES ${OUTPUT_DIR}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency) + DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency") +install(FILES ${OUTPUT_DIR}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) configure_file(__init__.py.in ${OUTPUT_DIR}/__init__.py) -install(FILES ${OUTPUT_DIR}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/gtsam_eigency) +install(FILES ${OUTPUT_DIR}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) From 4f6f8216110a2db9d7a9be3fbdba65a967490793 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 18:39:49 -0500 Subject: [PATCH 087/199] Vastly improved setup.py template --- cython/setup.py.in | 27 +++++++++++++++++++-------- 1 file changed, 19 insertions(+), 8 deletions(-) diff --git a/cython/setup.py.in b/cython/setup.py.in index df92b564c..98a05c9f6 100644 --- a/cython/setup.py.in +++ b/cython/setup.py.in @@ -7,6 +7,22 @@ except ImportError: packages = find_packages() +package_data = { + package: + [f for f in os.listdir(package.replace('.', os.path.sep)) if os.path.splitext(f)[1] in ('.so', '.pyd')] + for package in packages +} + +cython_install_requirements = open("${CYTHON_INSTALL_REQUIREMENTS_FILE}").readlines() + +install_requires = [line.strip() \ + for line in cython_install_requirements \ + if len(line.strip()) > 0 and not line.strip().startswith('#') +] + +# Cleaner to read in the contents rather than copy them over. +readme_contents = open("${PROJECT_SOURCE_DIR}/README.md").read() + setup( name='gtsam', description='Georgia Tech Smoothing And Mapping library', @@ -16,7 +32,7 @@ setup( author_email='frank.dellaert@gtsam.org', license='Simplified BSD license', keywords='slam sam robotics localization mapping optimization', - long_description='''${README_CONTENTS}''', + long_description=readme_contents, long_description_content_type='text/markdown', python_requires='>=2.7', # https://pypi.org/pypi?%3Aaction=list_classifiers @@ -34,11 +50,6 @@ setup( ], packages=packages, - package_data={package: - [f for f in os.listdir(package.replace('.', os.path.sep)) if os.path.splitext(f)[1] in ('.so', '.pyd')] - for package in packages - }, - install_requires=[line.strip() for line in ''' -${CYTHON_INSTALL_REQUIREMENTS} -'''.splitlines() if len(line.strip()) > 0 and not line.strip().startswith('#')] + package_data=package_data, + install_requires=install_requires ) From 192184b3b7c1efacb5a7608a7da4205fbba3536f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 18:40:03 -0500 Subject: [PATCH 088/199] Specify working directory from where to call setup.py --- cython/CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 0d2af6a33..01b6c06d4 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,6 +45,8 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") # Add the new make target command - add_custom_target(python-install COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install) + add_custom_target(python-install + COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) endif () From a4ef531a32b6fa078a24cd30ef17cbdb9580688e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:23:37 -0500 Subject: [PATCH 089/199] print Eigen Unsupported status message correctly --- gtsam/3rdparty/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/3rdparty/CMakeLists.txt b/gtsam/3rdparty/CMakeLists.txt index 89149d964..c8fecc339 100644 --- a/gtsam/3rdparty/CMakeLists.txt +++ b/gtsam/3rdparty/CMakeLists.txt @@ -17,7 +17,7 @@ if(NOT GTSAM_USE_SYSTEM_EIGEN) endforeach(eigen_dir) if(GTSAM_WITH_EIGEN_UNSUPPORTED) - message("-- Installing Eigen Unsupported modules") + message(STATUS "Installing Eigen Unsupported modules") # do the same for the unsupported eigen folder file(GLOB_RECURSE unsupported_eigen_headers "${CMAKE_CURRENT_SOURCE_DIR}/Eigen/unsupported/Eigen/*.h") From 7f1384b0f26e89136237e538779c6f6b0972c6b4 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:25:56 -0500 Subject: [PATCH 090/199] wrap the biasHat function for PreintegratedMeasurement --- gtsam.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/gtsam.h b/gtsam.h index 614db91c7..bf4d7f4d1 100644 --- a/gtsam.h +++ b/gtsam.h @@ -2955,6 +2955,7 @@ class PreintegratedImuMeasurements { gtsam::Rot3 deltaRij() const; Vector deltaPij() const; Vector deltaVij() const; + gtsam::imuBias::ConstantBias biasHat() const; Vector biasHatVector() const; gtsam::NavState predict(const gtsam::NavState& state_i, const gtsam::imuBias::ConstantBias& bias) const; @@ -3016,6 +3017,7 @@ class PreintegratedCombinedMeasurements { gtsam::Rot3 deltaRij() const; Vector deltaPij() const; Vector deltaVij() const; + gtsam::imuBias::ConstantBias biasHat() const; Vector biasHatVector() const; gtsam::NavState predict(const gtsam::NavState& state_i, const gtsam::imuBias::ConstantBias& bias) const; From 350808d9dc7b6e2e31814e6b59ede8d59c9dfe8b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Jun 2020 19:27:45 -0500 Subject: [PATCH 091/199] added .gitignore for when building the sample cmake projects --- cmake/.gitignore | 1 + 1 file changed, 1 insertion(+) create mode 100644 cmake/.gitignore diff --git a/cmake/.gitignore b/cmake/.gitignore new file mode 100644 index 000000000..6f467448b --- /dev/null +++ b/cmake/.gitignore @@ -0,0 +1 @@ +**/build \ No newline at end of file From 17568e67793ad831b02ec701ef6734bbfe950f68 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Thu, 25 Jun 2020 00:14:21 -0400 Subject: [PATCH 092/199] Add missing lf --- gtsam/base/types.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 924f339b3..c5dac9ab7 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -276,4 +276,4 @@ namespace gtsam { */ #define GTSAM_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign) \ - using _eigen_aligned_allocator_trait = void; \ No newline at end of file + using _eigen_aligned_allocator_trait = void; From fee226a1de09c57c086ded40769a3cc024b2cdc5 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Wed, 24 Jun 2020 22:43:55 -0700 Subject: [PATCH 093/199] fix SfmData naming --- tests/testTranslationRecovery.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/testTranslationRecovery.cpp b/tests/testTranslationRecovery.cpp index 774a999e4..5a98c3bf5 100644 --- a/tests/testTranslationRecovery.cpp +++ b/tests/testTranslationRecovery.cpp @@ -33,7 +33,7 @@ using namespace gtsam; // sets up an optimization problem for the three unknown translations. TEST(TranslationRecovery, BAL) { const string filename = findExampleDataFile("dubrovnik-3-7-pre"); - SfM_data db; + SfmData db; bool success = readBAL(filename, db); if (!success) throw runtime_error("Could not access file!"); From c8583e921a2c370d244b7cf04e8f1a56a44d7f50 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 25 Jun 2020 10:28:59 -0500 Subject: [PATCH 094/199] Revert "added .gitignore for when building the sample cmake projects" This reverts commit 350808d9dc7b6e2e31814e6b59ede8d59c9dfe8b. --- cmake/.gitignore | 1 - 1 file changed, 1 deletion(-) delete mode 100644 cmake/.gitignore diff --git a/cmake/.gitignore b/cmake/.gitignore deleted file mode 100644 index 6f467448b..000000000 --- a/cmake/.gitignore +++ /dev/null @@ -1 +0,0 @@ -**/build \ No newline at end of file From 9d9c30e5dc399fafc1726c949f24276b160244b4 Mon Sep 17 00:00:00 2001 From: akrishnan86 Date: Sun, 28 Jun 2020 11:03:38 -0700 Subject: [PATCH 095/199] review1 changes --- gtsam/sfm/TranslationFactor.h | 6 ++++-- gtsam/sfm/TranslationRecovery.cpp | 2 +- gtsam/sfm/TranslationRecovery.h | 5 +++++ gtsam/sfm/tests/testTranslationFactor.cpp | 20 +++++++++++++++++++- 4 files changed, 29 insertions(+), 4 deletions(-) diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index 584b1fa69..9a4bd68a7 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -51,8 +51,10 @@ class TranslationFactor : public NoiseModelFactor2 { : Base(noiseModel, a, b), measured_w_aZb_(w_aZb.point3()) {} /** - * @brief Caclulate error norm(p1-p2) - measured - * + * @brief Caclulate error: (norm(Tb - Ta) - measurement) + * where Tb and Ta are Point3 translations and measurement is + * the Unit3 translation direction from a to b. + * * @param Ta translation for key a * @param Tb translation for key b * @param H1 optional jacobian in Ta diff --git a/gtsam/sfm/TranslationRecovery.cpp b/gtsam/sfm/TranslationRecovery.cpp index a0f3eb6b6..aeeae688f 100644 --- a/gtsam/sfm/TranslationRecovery.cpp +++ b/gtsam/sfm/TranslationRecovery.cpp @@ -60,7 +60,7 @@ void TranslationRecovery::addPrior(const double scale, } Values TranslationRecovery::initalizeRandomly() const { - // Create a lambda expression that checks whether value exists and randomly + // Create a lambda expression that checks whether value exists and randomly // initializes if not. Values initial; auto insert = [&initial](Key j) { diff --git a/gtsam/sfm/TranslationRecovery.h b/gtsam/sfm/TranslationRecovery.h index 634825d29..bb3c3cdb1 100644 --- a/gtsam/sfm/TranslationRecovery.h +++ b/gtsam/sfm/TranslationRecovery.h @@ -60,6 +60,9 @@ class TranslationRecovery { * * @param relativeTranslations the relative translations, in world coordinate * frames, indexed in a map by a pair of Pose keys. + * @param lmParams (optional) gtsam::LavenbergMarquardtParams that can be + * used to modify the parameters for the LM optimizer. By default, uses the + * default LM parameters. */ TranslationRecovery(const TranslationEdges& relativeTranslations, const LevenbergMarquardtParams& lmParams = LevenbergMarquardtParams()) @@ -102,6 +105,8 @@ class TranslationRecovery { * * @param poses SE(3) ground truth poses stored as Values * @param edges pairs (a,b) for which a measurement w_aZb will be generated. + * @return TranslationEdges map from a KeyPair to the simulated Unit3 + * translation direction measurement between the cameras in KeyPair. */ static TranslationEdges SimulateMeasurements( const Values& poses, const std::vector& edges); diff --git a/gtsam/sfm/tests/testTranslationFactor.cpp b/gtsam/sfm/tests/testTranslationFactor.cpp index da284bfd6..37e8b6c0f 100644 --- a/gtsam/sfm/tests/testTranslationFactor.cpp +++ b/gtsam/sfm/tests/testTranslationFactor.cpp @@ -38,7 +38,7 @@ TEST(TranslationFactor, Constructor) { } /* ************************************************************************* */ -TEST(TranslationFactor, Error) { +TEST(TranslationFactor, ZeroError) { // Create a factor TranslationFactor factor(kKey1, kKey2, kMeasured, model); @@ -51,6 +51,24 @@ TEST(TranslationFactor, Error) { // Verify we get the expected error Vector expected = (Vector3() << 0, 0, 0).finished(); EXPECT(assert_equal(expected, actualError, 1e-9)); + + +} + +/* ************************************************************************* */ +TEST(TranslationFactor, NonZeroError) { + // create a factor + TranslationFactor factor(kKey1, kKey2, kMeasured, model); + + // set the linearization + Point3 T1(0, 1, 1), T2(0, 2, 2); + + // use the factor to calculate the error + Vector actualError(factor.evaluateError(T1, T2)); + + // verify we get the expected error + Vector expected = (Vector3() << -1, 1/sqrt(2), 1/sqrt(2)).finished(); + EXPECT(assert_equal(expected, actualError, 1e-9)); } /* ************************************************************************* */ From 54c29031839fe00d559e97e4b2014927667180d2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 16:53:42 -0500 Subject: [PATCH 096/199] make python-install command depends on gtsam target --- cython/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 01b6c06d4..2bfa8ae7c 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -47,6 +47,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) # Add the new make target command add_custom_target(python-install COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install + DEPENDS gtsam WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) endif () From 806e5b12a37462481f1d1e656835b0beab89a6f1 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 19:29:52 -0500 Subject: [PATCH 097/199] cleaner version of execution script which only needs 'make install' --- cython/CMakeLists.txt | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 2bfa8ae7c..75cbfea8a 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -45,9 +45,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") # Add the new make target command - add_custom_target(python-install - COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}/setup.py install - DEPENDS gtsam - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) + install(CODE + "execute_process(COMMAND ${PYTHON_EXECUTABLE} setup.py install + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH})") + endif () From 16532bff37a5eb991f639d682ae733d2f27650b2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 29 Jun 2020 21:37:07 -0500 Subject: [PATCH 098/199] run setup.py after installing the gtsam_eigency module --- cython/CMakeLists.txt | 10 ++++++---- cython/gtsam_eigency/CMakeLists.txt | 22 ++++++++++++---------- 2 files changed, 18 insertions(+), 14 deletions(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 75cbfea8a..5569c0e47 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -44,10 +44,12 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - # Add the new make target command + # Adding custom function here so that gtsam_eigency is installed before + # the below execute_process runs. + install_gtsam_eigency(${PROJECT_BINARY_DIR}/cython/gtsam_eigency) + + # Automatically run the python installation via the setup.py install(CODE "execute_process(COMMAND ${PYTHON_EXECUTABLE} setup.py install - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH})") - - + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH})") endif () diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index da174d690..5ea1c337c 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -8,7 +8,7 @@ set(OUTPUT_DIR "${PROJECT_BINARY_DIR}/cython/gtsam_eigency") set(EIGENCY_INCLUDE_DIR ${OUTPUT_DIR}) # This is to make the build/cython/gtsam_eigency folder a python package -configure_file(__init__.py.in ${PROJECT_BINARY_DIR}/cython/gtsam_eigency/__init__.py) +configure_file(__init__.py.in ${OUTPUT_DIR}/__init__.py) # include eigency headers include_directories(${EIGENCY_INCLUDE_DIR}) @@ -38,12 +38,14 @@ add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) # install -install(DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}" - PATTERN "CMakeLists.txt" EXCLUDE - PATTERN "__init__.py.in" EXCLUDE) -install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency") -install(FILES ${OUTPUT_DIR}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) -configure_file(__init__.py.in ${OUTPUT_DIR}/__init__.py) -install(FILES ${OUTPUT_DIR}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) +function(install_gtsam_eigency source_directory) + install(DIRECTORY ${source_directory} + DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}" + PATTERN "CMakeLists.txt" EXCLUDE + PATTERN "__init__.py.in" EXCLUDE) + install(TARGETS cythonize_eigency_core cythonize_eigency_conversions + DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency") + install(FILES ${source_directory}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) + install(FILES ${source_directory}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) + +endfunction() \ No newline at end of file From 83cbcd0bea250e5c314131d3cca832800c6b3899 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 13:13:04 -0500 Subject: [PATCH 099/199] capture stdout in python test [only for python3] --- cython/gtsam/tests/test_logging_optimizer.py | 12 +++++++++++- 1 file changed, 11 insertions(+), 1 deletion(-) diff --git a/cython/gtsam/tests/test_logging_optimizer.py b/cython/gtsam/tests/test_logging_optimizer.py index c857a6f7d..e7d9645b7 100644 --- a/cython/gtsam/tests/test_logging_optimizer.py +++ b/cython/gtsam/tests/test_logging_optimizer.py @@ -4,6 +4,8 @@ Author: Jing Wu and Frank Dellaert """ # pylint: disable=invalid-name +import io +import sys import unittest from datetime import datetime @@ -37,6 +39,14 @@ class TestOptimizeComet(GtsamTestCase): self.optimizer = gtsam.GaussNewtonOptimizer( graph, initial, self.params) + # setup output capture + self.capturedOutput = io.StringIO() + sys.stdout = self.capturedOutput + + def tearDown(self): + """Reset print capture.""" + sys.stdout = sys.__stdout__ + def test_simple_printing(self): """Test with a simple hook.""" @@ -76,4 +86,4 @@ class TestOptimizeComet(GtsamTestCase): self.gtsamAssertEquals(actual.atRot3(KEY), self.expected) if __name__ == "__main__": - unittest.main() \ No newline at end of file + unittest.main() From 192bf870af28156de5808074f6a45aa36e962410 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 13:16:09 -0500 Subject: [PATCH 100/199] newline added to end of CMake file --- cython/gtsam_eigency/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 5ea1c337c..6cff534c5 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -48,4 +48,4 @@ function(install_gtsam_eigency source_directory) install(FILES ${source_directory}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) install(FILES ${source_directory}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) -endfunction() \ No newline at end of file +endfunction() From 9cbabb2cb6e8bf7407f67cfa8026cd227f069f5d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:45:55 -0500 Subject: [PATCH 101/199] Set high level Cython/Eigency variables to reduce duplication --- CMakeLists.txt | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2cbdbf00c..f8deebfcd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -454,13 +454,14 @@ endif() if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(GTSAM_INSTALL_CYTHON_TOOLBOX 1) # Set up cache options - set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to CMAKE_INSTALL_PREFIX/cython") - if(NOT GTSAM_CYTHON_INSTALL_PATH) - set(GTSAM_CYTHON_INSTALL_PATH "${CMAKE_INSTALL_PREFIX}/cython") - endif() + set(GTSAM_CYTHON_PATH "${PROJECT_BINARY_DIR}/cython" CACHE PATH "Cython source files directory path") # Cython install path appended with Build type (e.g. cython, cythonDebug, etc). - set(GTSAM_CYTHON_INSTALL_FULLPATH "${GTSAM_CYTHON_INSTALL_PATH}${GTSAM_BUILD_TAG}") - set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) + set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython.build") + if(NOT GTSAM_CYTHON_INSTALL_PATH) + set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython.build${GTSAM_BUILD_TAG}") + endif() + set(GTSAM_EIGENCY_PATH ${GTSAM_CYTHON_PATH}/gtsam_eigency) + set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) add_subdirectory(cython) else() set(GTSAM_INSTALL_CYTHON_TOOLBOX 0) # This will go into config.h From 06476c8ee745deca1b188730b4cf881d48a0f668 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:46:55 -0500 Subject: [PATCH 102/199] Create and use cython build directory --- cython/CMakeLists.txt | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 5569c0e47..b0eb43c50 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -1,3 +1,6 @@ +# Create directory where cython build files will be placed +file(MAKE_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH}) + # Install cython components include(GtsamCythonWrap) @@ -5,7 +8,7 @@ include(GtsamCythonWrap) if (GTSAM_INSTALL_CYTHON_TOOLBOX) # build and include the eigency version of eigency add_subdirectory(gtsam_eigency) - include_directories(${PROJECT_BINARY_DIR}/cython/gtsam_eigency) + include_directories(${GTSAM_EIGENCY_PATH}) # Fix for error "C1128: number of sections exceeded object file format limit" if(MSVC) @@ -44,12 +47,13 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - # Adding custom function here so that gtsam_eigency is installed before - # the below execute_process runs. - install_gtsam_eigency(${PROJECT_BINARY_DIR}/cython/gtsam_eigency) + # Install gtsam_eigency. + # The paths are picked up directly from the parent CMakeLists.txt. + install_gtsam_eigency() # Automatically run the python installation via the setup.py install(CODE "execute_process(COMMAND ${PYTHON_EXECUTABLE} setup.py install - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH})") + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH})") + endif () From c84060acea3321150f7fd5e652d0b8b8c5c90f53 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:47:32 -0500 Subject: [PATCH 103/199] Use the high level cython variables, improve install process --- cython/gtsam_eigency/CMakeLists.txt | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 6cff534c5..f64e45cdb 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -4,7 +4,7 @@ include(GtsamCythonWrap) # so that the cython-generated header "conversions_api.h" can be found when cythonizing eigency's core # and eigency's cython pxd headers can be found when cythonizing gtsam file(COPY "." DESTINATION ".") -set(OUTPUT_DIR "${PROJECT_BINARY_DIR}/cython/gtsam_eigency") +set(OUTPUT_DIR "${GTSAM_CYTHON_PATH}/gtsam_eigency") set(EIGENCY_INCLUDE_DIR ${OUTPUT_DIR}) # This is to make the build/cython/gtsam_eigency folder a python package @@ -16,8 +16,8 @@ include_directories(${EIGENCY_INCLUDE_DIR}) # Cythonize and build eigency message(STATUS "Cythonize and build eigency") # Important trick: use "../gtsam_eigency/conversions.pyx" to let cython know that the conversions module is -# a part of the gtsam_eigency package and generate the function call import_gtsam_igency__conversions() -# in conversions_api.h correctly!!! +# a part of the gtsam_eigency package and generate the function call import_gtsam_eigency__conversions() +# in conversions_api.h correctly! cythonize(cythonize_eigency_conversions "../gtsam_eigency/conversions.pyx" "conversions" "${OUTPUT_DIR}" "${EIGENCY_INCLUDE_DIR}" "" "" "") cythonize(cythonize_eigency_core "../gtsam_eigency/core.pyx" "core" @@ -38,14 +38,16 @@ add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) # install -function(install_gtsam_eigency source_directory) - install(DIRECTORY ${source_directory} - DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}" +function(install_gtsam_eigency) + install(DIRECTORY ${GTSAM_EIGENCY_PATH} + DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}" PATTERN "CMakeLists.txt" EXCLUDE - PATTERN "__init__.py.in" EXCLUDE) + PATTERN "__init__.py.in" EXCLUDE + PATTERN "*.dir" EXCLUDE + PATTERN "*.make" EXCLUDE) install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency") - install(FILES ${source_directory}/conversions_api.h DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) - install(FILES ${source_directory}/__init__.py DESTINATION ${GTSAM_CYTHON_INSTALL_FULLPATH}/gtsam_eigency) + DESTINATION "${GTSAM_EIGENCY_INSTALL_PATH}") + install(FILES ${GTSAM_EIGENCY_PATH}/conversions_api.h DESTINATION ${GTSAM_EIGENCY_INSTALL_PATH}) + install(FILES ${GTSAM_EIGENCY_PATH}/__init__.py DESTINATION ${GTSAM_EIGENCY_INSTALL_PATH}) endfunction() From 7a725bf46af9fc069f4db772e4f191956a783e89 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:48:01 -0500 Subject: [PATCH 104/199] Remove redundant postfix checking since the postfix is already added at the top level --- cmake/GtsamCythonWrap.cmake | 75 ++++++------------------------------- 1 file changed, 12 insertions(+), 63 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 851f53cfe..3ce7f4454 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -184,35 +184,16 @@ function(install_cython_wrapped_library interface_header generated_files_path in # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH/subdirectory if there is one get_filename_component(location "${install_path}" PATH) get_filename_component(name "${install_path}" NAME) - message(STATUS "Installing Cython Toolbox to ${location}${GTSAM_BUILD_TAG}/${name}") #${GTSAM_CYTHON_INSTALL_FULLPATH}" + message(STATUS "Installing Cython Toolbox to ${location}/${name}") #${GTSAM_CYTHON_INSTALL_PATH}" - if(GTSAM_BUILD_TYPE_POSTFIXES) - foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) - string(TOUPPER "${build_type}" build_type_upper) - if(${build_type_upper} STREQUAL "RELEASE") - set(build_type_tag "") # Don't create release mode tag on installed directory - else() - set(build_type_tag "${build_type}") - endif() - - install(DIRECTORY "${generated_files_path}/" DESTINATION "${location}${build_type_tag}/${name}" - CONFIGURATIONS "${build_type}" - PATTERN "build" EXCLUDE - PATTERN "CMakeFiles" EXCLUDE - PATTERN "Makefile" EXCLUDE - PATTERN "*.cmake" EXCLUDE - PATTERN "*.cpp" EXCLUDE - PATTERN "*.py" EXCLUDE) - endforeach() - else() - install(DIRECTORY "${generated_files_path}/" DESTINATION ${install_path} - PATTERN "build" EXCLUDE - PATTERN "CMakeFiles" EXCLUDE - PATTERN "Makefile" EXCLUDE - PATTERN "*.cmake" EXCLUDE - PATTERN "*.cpp" EXCLUDE - PATTERN "*.py" EXCLUDE) - endif() + install(DIRECTORY "${generated_files_path}/" DESTINATION ${install_path} + CONFIGURATIONS "${CMAKE_BUILD_TYPE}" + PATTERN "build" EXCLUDE + PATTERN "CMakeFiles" EXCLUDE + PATTERN "Makefile" EXCLUDE + PATTERN "*.cmake" EXCLUDE + PATTERN "*.cpp" EXCLUDE + PATTERN "*.py" EXCLUDE) endfunction() # Helper function to install Cython scripts and handle multiple build types where the scripts @@ -232,24 +213,9 @@ function(install_cython_scripts source_directory dest_directory patterns) foreach(pattern ${patterns}) list(APPEND patterns_args PATTERN "${pattern}") endforeach() - if(GTSAM_BUILD_TYPE_POSTFIXES) - foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) - string(TOUPPER "${build_type}" build_type_upper) - if(${build_type_upper} STREQUAL "RELEASE") - set(build_type_tag "") # Don't create release mode tag on installed directory - else() - set(build_type_tag "${build_type}") - endif() - # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH if there is one - get_filename_component(location "${dest_directory}" PATH) - get_filename_component(name "${dest_directory}" NAME) - install(DIRECTORY "${source_directory}" DESTINATION "${location}/${name}${build_type_tag}" CONFIGURATIONS "${build_type}" - FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) - endforeach() - else() - install(DIRECTORY "${source_directory}" DESTINATION "${dest_directory}" FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) - endif() + install(DIRECTORY "${source_directory}" DESTINATION "${dest_directory}" CONFIGURATIONS "${CMAKE_BUILD_TYPE}" + FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) endfunction() # Helper function to install specific files and handle multiple build types where the scripts @@ -259,22 +225,5 @@ endfunction() # source_files: The source files to be installed. # dest_directory: The destination directory to install to. function(install_cython_files source_files dest_directory) - - if(GTSAM_BUILD_TYPE_POSTFIXES) - foreach(build_type ${CMAKE_CONFIGURATION_TYPES}) - string(TOUPPER "${build_type}" build_type_upper) - if(${build_type_upper} STREQUAL "RELEASE") - set(build_type_tag "") # Don't create release mode tag on installed directory - else() - set(build_type_tag "${build_type}") - endif() - # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH if there is one - get_filename_component(location "${dest_directory}" PATH) - get_filename_component(name "${dest_directory}" NAME) - install(FILES "${source_files}" DESTINATION "${location}/${name}${build_type_tag}" CONFIGURATIONS "${build_type}") - endforeach() - else() - install(FILES "${source_files}" DESTINATION "${dest_directory}") - endif() - + install(FILES "${source_files}" DESTINATION "${dest_directory}" CONFIGURATIONS "${CMAKE_BUILD_TYPE}") endfunction() From 54f2acd521b0531c9a727ee585cae7afcf5ef2bd Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 30 Jun 2020 20:57:31 -0500 Subject: [PATCH 105/199] updated cython wrapper README --- cython/README.md | 89 +++++++++++++++++++++--------------------------- 1 file changed, 38 insertions(+), 51 deletions(-) diff --git a/cython/README.md b/cython/README.md index bc6e346d9..0c59915a0 100644 --- a/cython/README.md +++ b/cython/README.md @@ -1,33 +1,36 @@ # Python Wrapper -This is the Cython/Python wrapper around the GTSAM C++ library. +This is the Python wrapper around the GTSAM C++ library. We use Cython to generate the bindings to the underlying C++ code. + +## Requirements + +- If you want to build the gtsam python library for a specific python version (eg 2.7), use the `-DGTSAM_PYTHON_VERSION=2.7` option when running `cmake` otherwise the default interpreter will be used. + - If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment) then the environment should be active while building gtsam. +- This wrapper needs `Cython(>=0.25.2)`, `backports_abc(>=0.5)`, and `numpy(>=1.11.0)`. These can be installed as follows: + + ```bash + pip install -r /cython/requirements.txt + ``` + +- For compatibility with gtsam's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), +named `gtsam_eigency`, to interface between C++'s Eigen and Python's numpy. ## Install -- if you want to build the gtsam python library for a specific python version (eg 2.7), use the `-DGTSAM_PYTHON_VERSION=2.7` option when running `cmake` otherwise the default interpreter will be used. - - If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment) then the environment should be active while building gtsam. -- This wrapper needs Cython(>=0.25.2), backports_abc>=0.5, and numpy. These can be installed as follows: - -```bash - pip install -r /cython/requirements.txt -``` - -- For compatibility with gtsam's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), -named **gtsam_eigency**, to interface between C++'s Eigen and Python's numpy. - -- Build and install gtsam using cmake with `GTSAM_INSTALL_CYTHON_TOOLBOX` enabled. -The wrapped module will be installed to `GTSAM_CYTHON_INSTALL_PATH`, which is -by default: `/cython` +- Run cmake with the `GTSAM_INSTALL_CYTHON_TOOLBOX` cmake flag enabled to configure building the wrapper. The wrapped module will be built and copied to the directory defined by `GTSAM_CYTHON_INSTALL_PATH`, which is by default: `/cython.build`. - To use the library without installing system-wide: modify your `PYTHONPATH` to include the `GTSAM_CYTHON_INSTALL_PATH`: -```bash -export PYTHONPATH=$PYTHONPATH: -``` -- To install system-wide: run `make install` then navigate to `GTSAM_CYTHON_INSTALL_PATH` and run `python setup.py install` - - (the same command can be used to install into a virtual environment if it is active) - - note: if you don't want gtsam to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install gtsam to a subdirectory of the build directory. - - if you run `setup.py` from the build directory rather than the installation directory, the script will warn you with the message: `setup.py is being run from an unexpected location`. - Before `make install` is run, not all the components of the package have been copied across, so running `setup.py` from the build directory would result in an incomplete package. + + ```bash + export PYTHONPATH=$PYTHONPATH: + ``` + +- Build GTSAM and the wrapper with `make`. + +- To install system-wide, simply run `make install`. + - The same command can be used to install into a virtual environment if it is active. + - **NOTE**: if you don't want gtsam to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install gtsam to a subdirectory of the build directory. + - If you run `setup.py` from the build directory rather than the installation directory, the script will warn you with the message: `setup.py is being run from an unexpected location`. ## Unit Tests @@ -47,48 +50,32 @@ See the tests for examples. - Vector/Matrix: + GTSAM expects double-precision floating point vectors and matrices. - Hence, you should pass numpy matrices with dtype=float, or 'float64'. + Hence, you should pass numpy matrices with `dtype=float`, or `float64`. + Also, GTSAM expects *column-major* matrices, unlike the default storage scheme in numpy. Hence, you should pass column-major matrices to gtsam using the flag order='F'. And you always get column-major matrices back. - For more details, see: https://github.com/wouterboomsma/eigency#storage-layout---why-arrays-are-sometimes-transposed - + Passing row-major matrices of different dtype, e.g. 'int', will also work + For more details, see [this link](https://github.com/wouterboomsma/eigency#storage-layout---why-arrays-are-sometimes-transposed). + + Passing row-major matrices of different dtype, e.g. `int`, will also work as the wrapper converts them to column-major and dtype float for you, using numpy.array.astype(float, order='F', copy=False). However, this will result a copy if your matrix is not in the expected type and storage order. - Inner namespace: Classes in inner namespace will be prefixed by _ in Python. -Examples: noiseModel_Gaussian, noiseModel_mEstimator_Tukey + + Examples: `noiseModel_Gaussian`, `noiseModel_mEstimator_Tukey` - Casting from a base class to a derive class must be done explicitly. -Examples: -```Python - noiseBase = factor.noiseModel() - noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) -``` -## Wrapping Your Own Project That Uses GTSAM + Examples: + ```python + noiseBase = factor.noiseModel() + noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) + ``` -- Set PYTHONPATH to include ${GTSAM_CYTHON_INSTALL_PATH} - + so that it can find gtsam Cython header: gtsam/gtsam.pxd +## Wrapping Custom GTSAM-based Project -- In your CMakeList.txt -```cmake -find_package(GTSAM REQUIRED) # Make sure gtsam's install folder is in your PATH -set(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${GTSAM_DIR}/../GTSAMCMakeTools") - -# Wrap -include(GtsamCythonWrap) -include_directories(${GTSAM_EIGENCY_INSTALL_PATH}) -wrap_and_install_library_cython("your_project_interface.h" - "from gtsam.gtsam cimport *" # extra import of gtsam/gtsam.pxd Cython header - "your_install_path" - "libraries_to_link_with_the_cython_module" - "dependencies_which_need_to_be_built_before_the_wrapper" - ) -#Optional: install_cython_scripts and install_cython_files. See GtsamCythonWrap.cmake. -``` +Please refer to the template project and the corresponding tutorial available [here](https://github.com/borglab/gtsam-project-python). ## KNOWN ISSUES From 8859b963a24db117fc51ea9532c310b6721c0fc1 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 12:13:53 -0500 Subject: [PATCH 106/199] In-place cython build Build everything inside the build/cython{BuildType} directory directly, so we can bypass the `make install` step and introduce the `make python-install` step which allows cmake to handle all dependencies. --- CMakeLists.txt | 8 ++--- cmake/GtsamCythonWrap.cmake | 6 ++-- cython/CMakeLists.txt | 51 ++++++++++++++--------------- cython/gtsam_eigency/CMakeLists.txt | 17 +--------- 4 files changed, 31 insertions(+), 51 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f8deebfcd..a9966f5d3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -454,15 +454,13 @@ endif() if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(GTSAM_INSTALL_CYTHON_TOOLBOX 1) # Set up cache options - set(GTSAM_CYTHON_PATH "${PROJECT_BINARY_DIR}/cython" CACHE PATH "Cython source files directory path") # Cython install path appended with Build type (e.g. cython, cythonDebug, etc). - set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython.build") + set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython") if(NOT GTSAM_CYTHON_INSTALL_PATH) - set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython.build${GTSAM_BUILD_TAG}") + set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython${GTSAM_BUILD_TAG}" CACHE PATH "") endif() - set(GTSAM_EIGENCY_PATH ${GTSAM_CYTHON_PATH}/gtsam_eigency) set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) - add_subdirectory(cython) + add_subdirectory(cython ${GTSAM_CYTHON_INSTALL_PATH}) else() set(GTSAM_INSTALL_CYTHON_TOOLBOX 0) # This will go into config.h endif() diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 3ce7f4454..797745acf 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -41,9 +41,9 @@ execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" function(wrap_and_install_library_cython interface_header extra_imports install_path libs dependencies) # Paths for generated files get_filename_component(module_name "${interface_header}" NAME_WE) - set(generated_files_path "${PROJECT_BINARY_DIR}/cython/${module_name}") + set(generated_files_path "${GTSAM_CYTHON_INSTALL_PATH}/${module_name}") wrap_library_cython("${interface_header}" "${generated_files_path}" "${extra_imports}" "${libs}" "${dependencies}") - install_cython_wrapped_library("${interface_header}" "${generated_files_path}" "${install_path}") + # install_cython_wrapped_library("${interface_header}" "${generated_files_path}" "${install_path}") endfunction() function(set_up_required_cython_packages) @@ -214,7 +214,7 @@ function(install_cython_scripts source_directory dest_directory patterns) list(APPEND patterns_args PATTERN "${pattern}") endforeach() - install(DIRECTORY "${source_directory}" DESTINATION "${dest_directory}" CONFIGURATIONS "${CMAKE_BUILD_TYPE}" + file(COPY "${source_directory}" DESTINATION "${dest_directory}" FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index b0eb43c50..74725c463 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -1,21 +1,37 @@ -# Create directory where cython build files will be placed -file(MAKE_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH}) - # Install cython components include(GtsamCythonWrap) # Create the cython toolbox for the gtsam library if (GTSAM_INSTALL_CYTHON_TOOLBOX) + # Add the new make target command + add_custom_target(python-install + COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}/setup.py install + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) + # build and include the eigency version of eigency add_subdirectory(gtsam_eigency) - include_directories(${GTSAM_EIGENCY_PATH}) + include_directories(${GTSAM_EIGENCY_INSTALL_PATH}) # Fix for error "C1128: number of sections exceeded object file format limit" if(MSVC) add_compile_options(/bigobj) endif() - # wrap gtsam + # First set up all the package related files. + # This also ensures the below wrap operations work correctly. + set(CYTHON_INSTALL_REQUIREMENTS_FILE "${PROJECT_SOURCE_DIR}/cython/requirements.txt") + + # Install the custom-generated __init__.py + # This makes the cython (sub-)directories into python packages, so gtsam can be found while wrapping gtsam_unstable + configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam/__init__.py COPYONLY) + configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_unstable/__init__.py COPYONLY) + configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${GTSAM_CYTHON_INSTALL_PATH}/setup.py) + install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") + # install scripts and tests + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + + # Wrap gtsam add_custom_target(gtsam_header DEPENDS "../gtsam.h") wrap_and_install_library_cython("../gtsam.h" # interface_header "" # extra imports @@ -23,8 +39,9 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) gtsam # library to link with "wrap;cythonize_eigency;gtsam;gtsam_header" # dependencies which need to be built before wrapping ) + add_dependencies(python-install gtsam gtsam_header) - # wrap gtsam_unstable + # Wrap gtsam_unstable if(GTSAM_BUILD_UNSTABLE) add_custom_target(gtsam_unstable_header DEPENDS "../gtsam_unstable/gtsam_unstable.h") wrap_and_install_library_cython("../gtsam_unstable/gtsam_unstable.h" # interface_header @@ -33,27 +50,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) gtsam_unstable # library to link with "gtsam_unstable;gtsam_unstable_header;cythonize_gtsam" # dependencies to be built before wrapping ) + add_dependencies(python-install gtsam_unstable gtsam_unstable_header) endif() - set(CYTHON_INSTALL_REQUIREMENTS_FILE "${PROJECT_SOURCE_DIR}/cython/requirements.txt") - - # Install the custom-generated __init__.py - # This is to make the build/cython/gtsam folder a python package, so gtsam can be found while wrapping gtsam_unstable - configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam/__init__.py ${PROJECT_BINARY_DIR}/cython/gtsam/__init__.py COPYONLY) - configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${PROJECT_BINARY_DIR}/cython/gtsam_unstable/__init__.py COPYONLY) - configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${PROJECT_BINARY_DIR}/cython/setup.py) - install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") - # install scripts and tests - install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - - # Install gtsam_eigency. - # The paths are picked up directly from the parent CMakeLists.txt. - install_gtsam_eigency() - - # Automatically run the python installation via the setup.py - install(CODE - "execute_process(COMMAND ${PYTHON_EXECUTABLE} setup.py install - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH})") - endif () diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index f64e45cdb..7c215e89c 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -4,7 +4,7 @@ include(GtsamCythonWrap) # so that the cython-generated header "conversions_api.h" can be found when cythonizing eigency's core # and eigency's cython pxd headers can be found when cythonizing gtsam file(COPY "." DESTINATION ".") -set(OUTPUT_DIR "${GTSAM_CYTHON_PATH}/gtsam_eigency") +set(OUTPUT_DIR "${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency") set(EIGENCY_INCLUDE_DIR ${OUTPUT_DIR}) # This is to make the build/cython/gtsam_eigency folder a python package @@ -36,18 +36,3 @@ target_include_directories(cythonize_eigency_core PUBLIC add_dependencies(cythonize_eigency_core cythonize_eigency_conversions) add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) - -# install -function(install_gtsam_eigency) - install(DIRECTORY ${GTSAM_EIGENCY_PATH} - DESTINATION "${GTSAM_CYTHON_INSTALL_PATH}" - PATTERN "CMakeLists.txt" EXCLUDE - PATTERN "__init__.py.in" EXCLUDE - PATTERN "*.dir" EXCLUDE - PATTERN "*.make" EXCLUDE) - install(TARGETS cythonize_eigency_core cythonize_eigency_conversions - DESTINATION "${GTSAM_EIGENCY_INSTALL_PATH}") - install(FILES ${GTSAM_EIGENCY_PATH}/conversions_api.h DESTINATION ${GTSAM_EIGENCY_INSTALL_PATH}) - install(FILES ${GTSAM_EIGENCY_PATH}/__init__.py DESTINATION ${GTSAM_EIGENCY_INSTALL_PATH}) - -endfunction() From 74591eece60b45342a865474fef452a7683430c7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 14:36:16 -0500 Subject: [PATCH 107/199] fixed CYTHON_INSTALL_PATH cmake variable wrt cache --- CMakeLists.txt | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a9966f5d3..f5b9c5e22 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -455,10 +455,8 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(GTSAM_INSTALL_CYTHON_TOOLBOX 1) # Set up cache options # Cython install path appended with Build type (e.g. cython, cythonDebug, etc). - set(GTSAM_CYTHON_INSTALL_PATH "" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython") - if(NOT GTSAM_CYTHON_INSTALL_PATH) - set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython${GTSAM_BUILD_TAG}" CACHE PATH "") - endif() + # This does not override custom values set from the command line + set(GTSAM_CYTHON_INSTALL_PATH "${PROJECT_BINARY_DIR}/cython${GTSAM_BUILD_TAG}" CACHE PATH "Cython toolbox destination, blank defaults to PROJECT_BINARY_DIR/cython") set(GTSAM_EIGENCY_INSTALL_PATH ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_eigency) add_subdirectory(cython ${GTSAM_CYTHON_INSTALL_PATH}) else() From 59968fddc5d7e0ded0102a8ac310602b9dd5c4b9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 14:36:57 -0500 Subject: [PATCH 108/199] Python Wrapper CMake update - Added python-install target variable for easy updating. - Fixed/Added all dependencies so that everything is built automatically. - Removed unnecessary install commands --- cmake/GtsamCythonWrap.cmake | 26 +++----------------------- cython/CMakeLists.txt | 14 ++++++++------ cython/gtsam_eigency/CMakeLists.txt | 2 ++ 3 files changed, 13 insertions(+), 29 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 797745acf..7597834c9 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -43,7 +43,6 @@ function(wrap_and_install_library_cython interface_header extra_imports install_ get_filename_component(module_name "${interface_header}" NAME_WE) set(generated_files_path "${GTSAM_CYTHON_INSTALL_PATH}/${module_name}") wrap_library_cython("${interface_header}" "${generated_files_path}" "${extra_imports}" "${libs}" "${dependencies}") - # install_cython_wrapped_library("${interface_header}" "${generated_files_path}" "${install_path}") endfunction() function(set_up_required_cython_packages) @@ -170,32 +169,13 @@ function(wrap_library_cython interface_header generated_files_path extra_imports cythonize(cythonize_${module_name} ${generated_pyx} ${module_name} ${generated_files_path} "${include_dirs}" "${libs}" ${interface_header} cython_wrap_${module_name}_pyx) + add_dependencies(${python_install_target} cython_wrap_${module_name}_pyx) + # distclean add_custom_target(wrap_${module_name}_cython_distclean COMMAND cmake -E remove_directory ${generated_files_path}) endfunction() -# Internal function that installs a wrap toolbox -function(install_cython_wrapped_library interface_header generated_files_path install_path) - get_filename_component(module_name "${interface_header}" NAME_WE) - - # NOTE: only installs .pxd and .pyx and binary files (not .cpp) - the trailing slash on the directory name - # here prevents creating the top-level module name directory in the destination. - # Split up filename to strip trailing '/' in GTSAM_CYTHON_INSTALL_PATH/subdirectory if there is one - get_filename_component(location "${install_path}" PATH) - get_filename_component(name "${install_path}" NAME) - message(STATUS "Installing Cython Toolbox to ${location}/${name}") #${GTSAM_CYTHON_INSTALL_PATH}" - - install(DIRECTORY "${generated_files_path}/" DESTINATION ${install_path} - CONFIGURATIONS "${CMAKE_BUILD_TYPE}" - PATTERN "build" EXCLUDE - PATTERN "CMakeFiles" EXCLUDE - PATTERN "Makefile" EXCLUDE - PATTERN "*.cmake" EXCLUDE - PATTERN "*.cpp" EXCLUDE - PATTERN "*.py" EXCLUDE) -endfunction() - # Helper function to install Cython scripts and handle multiple build types where the scripts # should be installed to all build type toolboxes # @@ -225,5 +205,5 @@ endfunction() # source_files: The source files to be installed. # dest_directory: The destination directory to install to. function(install_cython_files source_files dest_directory) - install(FILES "${source_files}" DESTINATION "${dest_directory}" CONFIGURATIONS "${CMAKE_BUILD_TYPE}") + file(COPY "${source_files}" DESTINATION "${dest_directory}") endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 74725c463..ce93120c2 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -4,7 +4,8 @@ include(GtsamCythonWrap) # Create the cython toolbox for the gtsam library if (GTSAM_INSTALL_CYTHON_TOOLBOX) # Add the new make target command - add_custom_target(python-install + set(python_install_target python-install) + add_custom_target(${python_install_target} COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}/setup.py install WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) @@ -27,9 +28,6 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_unstable/__init__.py COPYONLY) configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${GTSAM_CYTHON_INSTALL_PATH}/setup.py) install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") - # install scripts and tests - install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") - install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") # Wrap gtsam add_custom_target(gtsam_header DEPENDS "../gtsam.h") @@ -39,7 +37,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) gtsam # library to link with "wrap;cythonize_eigency;gtsam;gtsam_header" # dependencies which need to be built before wrapping ) - add_dependencies(python-install gtsam gtsam_header) + add_dependencies(${python_install_target} gtsam gtsam_header) # Wrap gtsam_unstable if(GTSAM_BUILD_UNSTABLE) @@ -50,7 +48,11 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) gtsam_unstable # library to link with "gtsam_unstable;gtsam_unstable_header;cythonize_gtsam" # dependencies to be built before wrapping ) - add_dependencies(python-install gtsam_unstable gtsam_unstable_header) + add_dependencies(${python_install_target} gtsam_unstable gtsam_unstable_header) endif() + # install scripts and tests + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + install_cython_scripts("${PROJECT_SOURCE_DIR}/cython/gtsam_unstable" "${GTSAM_CYTHON_INSTALL_PATH}" "*.py") + endif () diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 7c215e89c..663ea0a32 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -36,3 +36,5 @@ target_include_directories(cythonize_eigency_core PUBLIC add_dependencies(cythonize_eigency_core cythonize_eigency_conversions) add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) + +add_dependencies(${python_install_target} cythonize_eigency) From a6908cd1cb003ee184d0018a559075b319d65afe Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 16:23:24 -0500 Subject: [PATCH 109/199] removed unneeded install commands and updated README --- cmake/GtsamCythonWrap.cmake | 10 ----- cython/CMakeLists.txt | 1 - cython/README.md | 83 ++++++++++++++++++++----------------- 3 files changed, 44 insertions(+), 50 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 7597834c9..c155cbbd8 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -197,13 +197,3 @@ function(install_cython_scripts source_directory dest_directory patterns) file(COPY "${source_directory}" DESTINATION "${dest_directory}" FILES_MATCHING ${patterns_args} PATTERN "${exclude_patterns}" EXCLUDE) endfunction() - -# Helper function to install specific files and handle multiple build types where the scripts -# should be installed to all build type toolboxes -# -# Arguments: -# source_files: The source files to be installed. -# dest_directory: The destination directory to install to. -function(install_cython_files source_files dest_directory) - file(COPY "${source_files}" DESTINATION "${dest_directory}") -endfunction() diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index ce93120c2..65a9e9c62 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -27,7 +27,6 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam/__init__.py COPYONLY) configure_file(${PROJECT_SOURCE_DIR}/cython/gtsam_unstable/__init__.py ${GTSAM_CYTHON_INSTALL_PATH}/gtsam_unstable/__init__.py COPYONLY) configure_file(${PROJECT_SOURCE_DIR}/cython/setup.py.in ${GTSAM_CYTHON_INSTALL_PATH}/setup.py) - install_cython_files("${PROJECT_BINARY_DIR}/cython/setup.py" "${GTSAM_CYTHON_INSTALL_PATH}") # Wrap gtsam add_custom_target(gtsam_header DEPENDS "../gtsam.h") diff --git a/cython/README.md b/cython/README.md index 0c59915a0..f69b7a5a6 100644 --- a/cython/README.md +++ b/cython/README.md @@ -4,43 +4,48 @@ This is the Python wrapper around the GTSAM C++ library. We use Cython to genera ## Requirements -- If you want to build the gtsam python library for a specific python version (eg 2.7), use the `-DGTSAM_PYTHON_VERSION=2.7` option when running `cmake` otherwise the default interpreter will be used. - - If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment) then the environment should be active while building gtsam. +- If you want to build the GTSAM python library for a specific python version (eg 3.6), + use the `-DGTSAM_PYTHON_VERSION=3.6` option when running `cmake` otherwise the default interpreter will be used. +- If the interpreter is inside an environment (such as an anaconda environment or virtualenv environment), + then the environment should be active while building GTSAM. - This wrapper needs `Cython(>=0.25.2)`, `backports_abc(>=0.5)`, and `numpy(>=1.11.0)`. These can be installed as follows: ```bash pip install -r /cython/requirements.txt ``` -- For compatibility with gtsam's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), -named `gtsam_eigency`, to interface between C++'s Eigen and Python's numpy. +- For compatibility with GTSAM's Eigen version, it contains its own cloned version of [Eigency](https://github.com/wouterboomsma/eigency.git), + named `gtsam_eigency`, to interface between C++'s Eigen and Python's numpy. ## Install -- Run cmake with the `GTSAM_INSTALL_CYTHON_TOOLBOX` cmake flag enabled to configure building the wrapper. The wrapped module will be built and copied to the directory defined by `GTSAM_CYTHON_INSTALL_PATH`, which is by default: `/cython.build`. - -- To use the library without installing system-wide: modify your `PYTHONPATH` to include the `GTSAM_CYTHON_INSTALL_PATH`: - - ```bash - export PYTHONPATH=$PYTHONPATH: - ``` +- Run cmake with the `GTSAM_INSTALL_CYTHON_TOOLBOX` cmake flag enabled to configure building the wrapper. The wrapped module will be built and copied to the directory defined by `GTSAM_CYTHON_INSTALL_PATH`, which is by default `/cython` in Release mode and `/cython` for other modes. - Build GTSAM and the wrapper with `make`. -- To install system-wide, simply run `make install`. - - The same command can be used to install into a virtual environment if it is active. - - **NOTE**: if you don't want gtsam to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install gtsam to a subdirectory of the build directory. - - If you run `setup.py` from the build directory rather than the installation directory, the script will warn you with the message: `setup.py is being run from an unexpected location`. +- To install, simply run `make python-install`. + - The same command can be used to install into a virtual environment if it is active. + - **NOTE**: if you don't want GTSAM to install to a system directory such as `/usr/local`, pass `-DCMAKE_INSTALL_PREFIX="./install"` to cmake to install GTSAM to a subdirectory of the build directory. + +- You can also directly run `make python-install` without running `make`, and it will compile all the dependencies accordingly. ## Unit Tests The Cython toolbox also has a small set of unit tests located in the test directory. To run them: -```bash - cd - python -m unittest discover -``` + ```bash + cd + python -m unittest discover + ``` + +## Utils + +TODO + +## Examples + +TODO ## Writing Your Own Scripts @@ -49,25 +54,27 @@ See the tests for examples. ### Some Important Notes: - Vector/Matrix: - + GTSAM expects double-precision floating point vectors and matrices. + + - GTSAM expects double-precision floating point vectors and matrices. Hence, you should pass numpy matrices with `dtype=float`, or `float64`. - + Also, GTSAM expects *column-major* matrices, unlike the default storage - scheme in numpy. Hence, you should pass column-major matrices to gtsam using + - Also, GTSAM expects _column-major_ matrices, unlike the default storage + scheme in numpy. Hence, you should pass column-major matrices to GTSAM using the flag order='F'. And you always get column-major matrices back. For more details, see [this link](https://github.com/wouterboomsma/eigency#storage-layout---why-arrays-are-sometimes-transposed). - + Passing row-major matrices of different dtype, e.g. `int`, will also work + - Passing row-major matrices of different dtype, e.g. `int`, will also work as the wrapper converts them to column-major and dtype float for you, using numpy.array.astype(float, order='F', copy=False). However, this will result a copy if your matrix is not in the expected type and storage order. -- Inner namespace: Classes in inner namespace will be prefixed by _ in Python. +- Inner namespace: Classes in inner namespace will be prefixed by \_ in Python. Examples: `noiseModel_Gaussian`, `noiseModel_mEstimator_Tukey` - Casting from a base class to a derive class must be done explicitly. Examples: + ```python noiseBase = factor.noiseModel() noiseGaussian = dynamic_cast_noiseModel_Gaussian_noiseModel_Base(noiseBase) @@ -75,37 +82,35 @@ See the tests for examples. ## Wrapping Custom GTSAM-based Project -Please refer to the template project and the corresponding tutorial available [here](https://github.com/borglab/gtsam-project-python). +Please refer to the template project and the corresponding tutorial available [here](https://github.com/borglab/GTSAM-project-python). ## KNOWN ISSUES - - Doesn't work with python3 installed from homebrew - - size-related issue: can only wrap up to a certain number of classes: up to mEstimator! - - Guess: 64 vs 32b? disutils Compiler flags? - - Bug with Cython 0.24: instantiated factor classes return FastVector for keys(), which can't be casted to FastVector - - Upgrading to 0.25 solves the problem - - Need default constructor and default copy constructor for almost every classes... :( - - support these constructors by default and declare "delete" for special classes? - +- Doesn't work with python3 installed from homebrew + - size-related issue: can only wrap up to a certain number of classes: up to mEstimator! + - Guess: 64 vs 32b? disutils Compiler flags? +- Bug with Cython 0.24: instantiated factor classes return FastVector for keys(), which can't be casted to FastVector + - Upgrading to 0.25 solves the problem +- Need default constructor and default copy constructor for almost every classes... :( + - support these constructors by default and declare "delete" for special classes? ### TODO - [ ] allow duplication of parent' functions in child classes. Not allowed for now due to conflicts in Cython. -- [ ] a common header for boost shared_ptr? (Or wait until everything is switched to std::shared_ptr in gtsam?) +- [ ] a common header for boost shared_ptr? (Or wait until everything is switched to std::shared_ptr in GTSAM?) - [ ] inner namespaces ==> inner packages? - [ ] Wrap fixed-size Matrices/Vectors? - ### Completed/Cancelled: -- [x] Fix Python tests: don't use " import * ": Bad style!!! (18-03-17 19:50) +- [x] Fix Python tests: don't use " import \* ": Bad style!!! (18-03-17 19:50) - [x] Unit tests for cython wrappers @done (18-03-17 18:45) -- simply compare generated files - [x] Wrap unstable @done (18-03-17 15:30) -- [x] Unify cython/gtsam.h and the original gtsam.h @done (18-03-17 15:30) +- [x] Unify cython/GTSAM.h and the original GTSAM.h @done (18-03-17 15:30) - [x] 18-03-17: manage to unify the two versions by removing std container stubs from the matlab version,and keeping KeyList/KeyVector/KeySet as in the matlab version. Probably Cython 0.25 fixes the casting problem. - [x] 06-03-17: manage to remove the requirements for default and copy constructors - [ ] 25-11-16: Try to unify but failed. Main reasons are: Key/size_t, std containers, KeyVector/KeyList/KeySet. Matlab doesn't need to know about Key, but I can't make Cython to ignore Key as it couldn't cast KeyVector, i.e. FastVector, to FastVector. -- [ ] Marginal and JointMarginal: revert changes @failed (17-03-17 11:00) -- Cython does need a default constructor! It produces cpp code like this: ```gtsam::JointMarginal __pyx_t_1;``` Users don't have to wrap this constructor, however. +- [ ] Marginal and JointMarginal: revert changes @failed (17-03-17 11:00) -- Cython does need a default constructor! It produces cpp code like this: `GTSAM::JointMarginal __pyx_t_1;` Users don't have to wrap this constructor, however. - [x] Convert input numpy Matrix/Vector to float dtype and storage order 'F' automatically, cannot crash! @done (15-03-17 13:00) - [x] Remove requirements.txt - Frank: don't bother with only 2 packages and a special case for eigency! @done (08-03-17 10:30) - [x] CMake install script @done (25-11-16 02:30) @@ -119,7 +124,7 @@ Please refer to the template project and the corresponding tutorial available [h - [x] Casting from parent and grandparents @done (16-11-16 17:00) - [x] Allow overloading constructors. The current solution is annoying!!! @done (16-11-16 17:00) - [x] Support "print obj" @done (16-11-16 17:00) -- [x] methods for FastVector: at, [], ... @done (16-11-16 17:00) +- [x] methods for FastVector: at, [], ... @done (16-11-16 17:00) - [x] Cython: Key and size_t: traits doesn't exist @done (16-09-12 18:34) - [x] KeyVector, KeyList, KeySet... @done (16-09-13 17:19) - [x] [Nice to have] parse typedef @done (16-09-13 17:19) From d2f69eeab41044219f4a40314eaf98d62254d183 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 17:07:31 -0500 Subject: [PATCH 110/199] Add python-install dependency for gtsam_unstable as well --- cmake/GtsamCythonWrap.cmake | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index c155cbbd8..2f5582513 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -137,6 +137,8 @@ function(cythonize target pyx_file output_lib_we output_dir include_dirs libs in target_link_libraries(${target} "${libs}") endif() add_dependencies(${target} ${target}_pyx2cpp) + + add_dependencies(${python_install_target} ${target}) endfunction() # Internal function that wraps a library and compiles the wrapper @@ -169,8 +171,6 @@ function(wrap_library_cython interface_header generated_files_path extra_imports cythonize(cythonize_${module_name} ${generated_pyx} ${module_name} ${generated_files_path} "${include_dirs}" "${libs}" ${interface_header} cython_wrap_${module_name}_pyx) - add_dependencies(${python_install_target} cython_wrap_${module_name}_pyx) - # distclean add_custom_target(wrap_${module_name}_cython_distclean COMMAND cmake -E remove_directory ${generated_files_path}) From 52da4580fb58b79a2aca51c65fa4d1046f6a6f1d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 1 Jul 2020 18:52:02 -0500 Subject: [PATCH 111/199] make utils and test code python2 compliant --- cython/gtsam/tests/test_logging_optimizer.py | 12 ++++++++---- cython/gtsam/utils/logging_optimizer.py | 10 +++------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/cython/gtsam/tests/test_logging_optimizer.py b/cython/gtsam/tests/test_logging_optimizer.py index e7d9645b7..69665db65 100644 --- a/cython/gtsam/tests/test_logging_optimizer.py +++ b/cython/gtsam/tests/test_logging_optimizer.py @@ -4,8 +4,12 @@ Author: Jing Wu and Frank Dellaert """ # pylint: disable=invalid-name -import io import sys +if sys.version_info.major >= 3: + from io import StringIO +else: + from cStringIO import StringIO + import unittest from datetime import datetime @@ -40,7 +44,7 @@ class TestOptimizeComet(GtsamTestCase): graph, initial, self.params) # setup output capture - self.capturedOutput = io.StringIO() + self.capturedOutput = StringIO() sys.stdout = self.capturedOutput def tearDown(self): @@ -51,7 +55,7 @@ class TestOptimizeComet(GtsamTestCase): """Test with a simple hook.""" # Provide a hook that just prints - def hook(_, error: float): + def hook(_, error): print(error) # Only thing we require from optimizer is an iterate method @@ -75,7 +79,7 @@ class TestOptimizeComet(GtsamTestCase): + str(time.hour)+":"+str(time.minute)+":"+str(time.second)) # I want to do some comet thing here - def hook(optimizer, error: float): + def hook(optimizer, error): comet.log_metric("Karcher error", error, optimizer.iterations()) diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index b201bb8aa..939453927 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -4,15 +4,11 @@ Author: Jing Wu and Frank Dellaert """ # pylint: disable=invalid-name -from typing import TypeVar - from gtsam import NonlinearOptimizer, NonlinearOptimizerParams import gtsam -T = TypeVar('T') - -def optimize(optimizer: T, check_convergence, hook): +def optimize(optimizer, check_convergence, hook): """ Given an optimizer and a convergence check, iterate until convergence. After each iteration, hook(optimizer, error) is called. After the function, use values and errors to get the result. @@ -36,8 +32,8 @@ def optimize(optimizer: T, check_convergence, hook): current_error = new_error -def gtsam_optimize(optimizer: NonlinearOptimizer, - params: NonlinearOptimizerParams, +def gtsam_optimize(optimizer, + params, hook): """ Given an optimizer and params, iterate until convergence. After each iteration, hook(optimizer) is called. From cb151dd9ee9426f60c371c4a49c043726f7a4afa Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 4 Jul 2020 20:42:15 -0400 Subject: [PATCH 112/199] update python build location in travis script --- .travis.python.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.python.sh b/.travis.python.sh index 1ef5799aa..772311f38 100644 --- a/.travis.python.sh +++ b/.travis.python.sh @@ -34,7 +34,7 @@ cmake $CURRDIR -DCMAKE_BUILD_TYPE=Release \ make -j$(nproc) install -cd $CURRDIR/../gtsam_install/cython +cd cython sudo $PYTHON setup.py install From 564d2c58730e9710385b4009e7e676117076ccb2 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 5 Jul 2020 10:19:05 -0400 Subject: [PATCH 113/199] Fix memory leak in Expressions --- gtsam/nonlinear/internal/ExecutionTrace.h | 6 ++++++ gtsam/nonlinear/tests/testExecutionTrace.cpp | 1 + 2 files changed, 7 insertions(+) diff --git a/gtsam/nonlinear/internal/ExecutionTrace.h b/gtsam/nonlinear/internal/ExecutionTrace.h index ace0aaea8..2943b5e68 100644 --- a/gtsam/nonlinear/internal/ExecutionTrace.h +++ b/gtsam/nonlinear/internal/ExecutionTrace.h @@ -169,6 +169,12 @@ class ExecutionTrace { content.ptr->reverseAD2(dTdA, jacobians); } + ~ExecutionTrace() { + if (kind == Function) { + content.ptr->~CallRecord(); + } + } + /// Define type so we can apply it as a meta-function typedef ExecutionTrace type; }; diff --git a/gtsam/nonlinear/tests/testExecutionTrace.cpp b/gtsam/nonlinear/tests/testExecutionTrace.cpp index c2b245780..58f76089a 100644 --- a/gtsam/nonlinear/tests/testExecutionTrace.cpp +++ b/gtsam/nonlinear/tests/testExecutionTrace.cpp @@ -16,6 +16,7 @@ * @brief unit tests for Expression internals */ +#include #include #include From 258d05c9efd5223c29a80441bb7ebdb3aeada224 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 4 Jul 2020 20:31:04 -0400 Subject: [PATCH 114/199] Fix TranslationFactor with Vector3 as Point3 --- gtsam/sfm/TranslationFactor.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/gtsam/sfm/TranslationFactor.h b/gtsam/sfm/TranslationFactor.h index 9a4bd68a7..d63633d7e 100644 --- a/gtsam/sfm/TranslationFactor.h +++ b/gtsam/sfm/TranslationFactor.h @@ -67,8 +67,7 @@ class TranslationFactor : public NoiseModelFactor2 { boost::optional H2 = boost::none) const override { const Point3 dir = Tb - Ta; Matrix33 H_predicted_dir; - const Point3 predicted = - dir.normalized(H1 || H2 ? &H_predicted_dir : nullptr); + const Point3 predicted = normalize(dir, H1 || H2 ? &H_predicted_dir : nullptr); if (H1) *H1 = -H_predicted_dir; if (H2) *H2 = H_predicted_dir; return predicted - measured_w_aZb_; From df687e5abf4da44933f00b121356817f1c85bd6c Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 19 Jun 2020 10:40:07 -0400 Subject: [PATCH 115/199] Fix MSVC build --- gtsam/base/types.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index c5dac9ab7..857de00c9 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -28,6 +28,7 @@ #include #include +#include #ifdef GTSAM_USE_TBB #include From e08e39202074fed0b0a40fdb821e5f0726ec4799 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 5 Jul 2020 21:57:18 -0500 Subject: [PATCH 116/199] Improved paths and added checks --- cmake/GtsamCythonWrap.cmake | 13 +++++++++---- cython/gtsam_eigency/CMakeLists.txt | 4 +++- 2 files changed, 12 insertions(+), 5 deletions(-) diff --git a/cmake/GtsamCythonWrap.cmake b/cmake/GtsamCythonWrap.cmake index 2f5582513..c8f876895 100644 --- a/cmake/GtsamCythonWrap.cmake +++ b/cmake/GtsamCythonWrap.cmake @@ -41,7 +41,7 @@ execute_process(COMMAND "${PYTHON_EXECUTABLE}" "-c" function(wrap_and_install_library_cython interface_header extra_imports install_path libs dependencies) # Paths for generated files get_filename_component(module_name "${interface_header}" NAME_WE) - set(generated_files_path "${GTSAM_CYTHON_INSTALL_PATH}/${module_name}") + set(generated_files_path "${install_path}") wrap_library_cython("${interface_header}" "${generated_files_path}" "${extra_imports}" "${libs}" "${dependencies}") endfunction() @@ -138,7 +138,9 @@ function(cythonize target pyx_file output_lib_we output_dir include_dirs libs in endif() add_dependencies(${target} ${target}_pyx2cpp) - add_dependencies(${python_install_target} ${target}) + if(TARGET ${python_install_target}) + add_dependencies(${python_install_target} ${target}) + endif() endfunction() # Internal function that wraps a library and compiles the wrapper @@ -151,9 +153,12 @@ function(wrap_library_cython interface_header generated_files_path extra_imports get_filename_component(module_name "${interface_header}" NAME_WE) # Wrap module to Cython pyx - message(STATUS "Cython wrapper generating ${module_name}.pyx") + message(STATUS "Cython wrapper generating ${generated_files_path}/${module_name}.pyx") set(generated_pyx "${generated_files_path}/${module_name}.pyx") - file(MAKE_DIRECTORY "${generated_files_path}") + if(NOT EXISTS ${generated_files_path}) + file(MAKE_DIRECTORY "${generated_files_path}") + endif() + add_custom_command( OUTPUT ${generated_pyx} DEPENDS ${interface_header} wrap diff --git a/cython/gtsam_eigency/CMakeLists.txt b/cython/gtsam_eigency/CMakeLists.txt index 663ea0a32..a0cf0fbde 100644 --- a/cython/gtsam_eigency/CMakeLists.txt +++ b/cython/gtsam_eigency/CMakeLists.txt @@ -37,4 +37,6 @@ add_dependencies(cythonize_eigency_core cythonize_eigency_conversions) add_custom_target(cythonize_eigency) add_dependencies(cythonize_eigency cythonize_eigency_conversions cythonize_eigency_core) -add_dependencies(${python_install_target} cythonize_eigency) +if(TARGET ${python_install_target}) + add_dependencies(${python_install_target} cythonize_eigency) +endif() From 3c5f8711caabe0a1db5a7b293b2bed05f74004d2 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Mon, 6 Jul 2020 20:07:18 +0200 Subject: [PATCH 117/199] Fix missing DLL exported symbol --- gtsam/base/types.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/base/types.h b/gtsam/base/types.h index 857de00c9..aaada3cee 100644 --- a/gtsam/base/types.h +++ b/gtsam/base/types.h @@ -55,7 +55,7 @@ namespace gtsam { /// Function to demangle type name of variable, e.g. demangle(typeid(x).name()) - std::string demangle(const char* name); + std::string GTSAM_EXPORT demangle(const char* name); /// Integer nonlinear key type typedef std::uint64_t Key; From 7d0e440293fe87b2f5ff6e142bf10588d9c051ee Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 6 Jul 2020 17:38:34 -0400 Subject: [PATCH 118/199] new definition for FunctorizedFactor to allow for using std::function and lambdas --- gtsam/nonlinear/FunctorizedFactor.h | 73 +++++++-------- .../nonlinear/tests/testFunctorizedFactor.cpp | 89 ++++++++++++++----- 2 files changed, 97 insertions(+), 65 deletions(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 82d2f822e..c88579587 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -27,14 +27,11 @@ namespace gtsam { /** * Factor which evaluates functor and uses the result to compute * error on provided measurement. - * The provided FUNCTOR should provide two type aliases: `argument_type` which - * corresponds to the type of input it accepts and `return_type` which indicates - * the type of the return value. This factor uses those type values to construct - * the functor. * * Template parameters are - * @param FUNCTOR: A class which operates as a functor. - * + * @param R: The return type of the functor after evaluation. + * @param T: The argument type for the functor. + * * Example: * Key key = Symbol('X', 0); * auto model = noiseModel::Isotropic::Sigma(9, 1); @@ -48,58 +45,53 @@ namespace gtsam { * MultiplyFunctor(double m) : m_(m) {} * Matrix operator()(const Matrix &X, * OptionalJacobian<-1, -1> H = boost::none) const { - * if (H) *H = m_ * Matrix::Identity(X.rows()*X.cols(), X.rows()*X.cols()); - * return m_ * X; + * if (H) *H = m_ * Matrix::Identity(X.rows()*X.cols(), + * X.rows()*X.cols()); return m_ * X; * } * }; * * Matrix measurement = Matrix::Identity(3, 3); * double multiplier = 2.0; - * FunctorizedFactor factor(keyX, measurement, model, multiplier); + * + * FunctorizedFactor factor(keyX, measurement, model, + * MultiplyFunctor(multiplier)); */ -template -class GTSAM_EXPORT FunctorizedFactor - : public NoiseModelFactor1 { -private: - using T = typename FUNCTOR::argument_type; +template +class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { + private: using Base = NoiseModelFactor1; - typename FUNCTOR::return_type - measured_; ///< value that is compared with functor return value - SharedNoiseModel noiseModel_; ///< noise model - FUNCTOR func_; ///< functor instance + R measured_; ///< value that is compared with functor return value + SharedNoiseModel noiseModel_; ///< noise model + std::function)> func_; ///< functor instance -public: + public: /** default constructor - only use for serialization */ FunctorizedFactor() {} /** Construct with given x and the parameters of the basis - * - * @param Args: Variadic template parameter for functor arguments. * * @param key: Factor key - * @param z: Measurement object of type FUNCTOR::return_type + * @param z: Measurement object of type R * @param model: Noise model - * @param args: Variable number of arguments used to instantiate functor + * @param func: The instance of the functor object */ - template - FunctorizedFactor(Key key, const typename FUNCTOR::return_type &z, - const SharedNoiseModel &model, Args &&... args) - : Base(model, key), measured_(z), noiseModel_(model), - func_(std::forward(args)...) {} + FunctorizedFactor(Key key, const R &z, const SharedNoiseModel &model, + const std::function)> func) + : Base(model, key), measured_(z), noiseModel_(model), func_(func) {} virtual ~FunctorizedFactor() {} /// @return a deep copy of this factor virtual NonlinearFactor::shared_ptr clone() const { return boost::static_pointer_cast( - NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); + NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); } Vector evaluateError(const T ¶ms, boost::optional H = boost::none) const { - typename FUNCTOR::return_type x = func_(params, H); - Vector error = traits::Local(measured_, x); + R x = func_(params, H); + Vector error = traits::Local(measured_, x); return error; } @@ -110,22 +102,21 @@ public: Base::print(s, keyFormatter); std::cout << s << (s != "" ? " " : "") << "FunctorizedFactor(" << keyFormatter(this->key()) << ")" << std::endl; - traits::Print(measured_, " measurement: "); + traits::Print(measured_, " measurement: "); std::cout << " noise model sigmas: " << noiseModel_->sigmas().transpose() << std::endl; } virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) const { - const FunctorizedFactor *e = - dynamic_cast *>(&other); + const FunctorizedFactor *e = + dynamic_cast *>(&other); const bool base = Base::equals(*e, tol); return e && Base::equals(other, tol) && - traits::Equals(this->measured_, e->measured_, - tol); + traits::Equals(this->measured_, e->measured_, tol); } /// @} -private: + private: /** Serialization function */ friend class boost::serialization::access; template @@ -138,8 +129,8 @@ private: }; /// traits -template -struct traits> - : public Testable> {}; +template +struct traits> + : public Testable> {}; -} // namespace gtsam +} // namespace gtsam diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp index 9393a4410..9ff6b8e24 100644 --- a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -17,13 +17,12 @@ * @brief unit tests for FunctorizedFactor class */ +#include #include #include #include #include -#include - using namespace std; using namespace gtsam; @@ -32,9 +31,9 @@ auto model = noiseModel::Isotropic::Sigma(9, 1); /// Functor that takes a matrix and multiplies every element by m class MultiplyFunctor { - double m_; ///< simple multiplier + double m_; ///< simple multiplier -public: + public: using argument_type = Matrix; using return_type = Matrix; @@ -42,32 +41,33 @@ public: Matrix operator()(const Matrix &X, OptionalJacobian<-1, -1> H = boost::none) const { - if (H) - *H = m_ * Matrix::Identity(X.rows() * X.cols(), X.rows() * X.cols()); + if (H) *H = m_ * Matrix::Identity(X.rows() * X.cols(), X.rows() * X.cols()); return m_ * X; } }; +/* ************************************************************************* */ TEST(FunctorizedFactor, Identity) { - Matrix X = Matrix::Identity(3, 3), measurement = Matrix::Identity(3, 3); double multiplier = 1.0; - FunctorizedFactor factor(key, measurement, model, - multiplier); + FunctorizedFactor factor(key, measurement, model, + MultiplyFunctor(multiplier)); Vector error = factor.evaluateError(X); EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } +/* ************************************************************************* */ TEST(FunctorizedFactor, Multiply2) { double multiplier = 2.0; Matrix X = Matrix::Identity(3, 3); Matrix measurement = multiplier * Matrix::Identity(3, 3); - FunctorizedFactor factor(key, measurement, model, multiplier); + FunctorizedFactor factor(key, measurement, model, + MultiplyFunctor(multiplier)); Vector error = factor.evaluateError(X); @@ -79,10 +79,10 @@ TEST(FunctorizedFactor, Equality) { double multiplier = 2.0; - FunctorizedFactor factor1(key, measurement, model, - multiplier); - FunctorizedFactor factor2(key, measurement, model, - multiplier); + FunctorizedFactor factor1(key, measurement, model, + MultiplyFunctor(multiplier)); + FunctorizedFactor factor2(key, measurement, model, + MultiplyFunctor(multiplier)); EXPECT(factor1.equals(factor2)); } @@ -94,7 +94,8 @@ TEST(FunctorizedFactor, Jacobians) { double multiplier = 2.0; - FunctorizedFactor factor(key, X, model, multiplier); + FunctorizedFactor factor(key, X, model, + MultiplyFunctor(multiplier)); Values values; values.insert(key, X); @@ -103,12 +104,14 @@ TEST(FunctorizedFactor, Jacobians) { EXPECT_CORRECT_FACTOR_JACOBIANS(factor, values, 1e-7, 1e-5); } +/* ************************************************************************* */ TEST(FunctorizedFactor, Print) { Matrix X = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor(key, X, model, multiplier); + FunctorizedFactor factor(key, X, model, + MultiplyFunctor(multiplier)); // redirect output to buffer so we can compare stringstream buffer; @@ -120,18 +123,56 @@ TEST(FunctorizedFactor, Print) { string actual = buffer.str(); cout.rdbuf(old); - string expected = " keys = { X0 }\n" - " noise model: unit (9) \n" - "FunctorizedFactor(X0)\n" - " measurement: [\n" - " 1, 0;\n" - " 0, 1\n" - "]\n" - " noise model sigmas: 1 1 1 1 1 1 1 1 1\n"; + string expected = + " keys = { X0 }\n" + " noise model: unit (9) \n" + "FunctorizedFactor(X0)\n" + " measurement: [\n" + " 1, 0;\n" + " 0, 1\n" + "]\n" + " noise model sigmas: 1 1 1 1 1 1 1 1 1\n"; CHECK_EQUAL(expected, actual); } +/* ************************************************************************* */ +// Test factor using a std::function type. +TEST(FunctorizedFactor, Functional) { + double multiplier = 2.0; + Matrix X = Matrix::Identity(3, 3); + Matrix measurement = multiplier * Matrix::Identity(3, 3); + + std::function)> functional = + MultiplyFunctor(multiplier); + FunctorizedFactor factor(key, measurement, model, functional); + + Vector error = factor.evaluateError(X); + + EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); +} + +/* ************************************************************************* */ +TEST(FunctorizedFactor, Lambda) { + double multiplier = 2.0; + Matrix X = Matrix::Identity(3, 3); + Matrix measurement = multiplier * Matrix::Identity(3, 3); + + auto lambda = [multiplier](const Matrix &X, + OptionalJacobian<-1, -1> H = boost::none) { + if (H) + *H = multiplier * + Matrix::Identity(X.rows() * X.cols(), X.rows() * X.cols()); + return multiplier * X; + }; + // FunctorizedFactor factor(key, measurement, model, lambda); + auto factor = FunctorizedFactor(key, measurement, model, lambda); + + Vector error = factor.evaluateError(X); + + EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); +} + /* ************************************************************************* */ int main() { From 30ffcdd1371985b5415e7b22918c65ecbc42789e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Mon, 6 Jul 2020 21:48:51 -0400 Subject: [PATCH 119/199] Simplified FunctorizedFactor By adding the helper function MakeFunctorizedFactor, we now only need to provide the argument type in the template parameter list. This considerably simplifies the factor declaration, while removing the need for argument type and return type in the functor definition. Also added tests for std::function and lambda functions. --- gtsam/nonlinear/FunctorizedFactor.h | 38 ++++++++++----- .../nonlinear/tests/testFunctorizedFactor.cpp | 47 ++++++++++--------- 2 files changed, 50 insertions(+), 35 deletions(-) diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index c88579587..a83198967 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -25,8 +25,8 @@ namespace gtsam { /** - * Factor which evaluates functor and uses the result to compute - * error on provided measurement. + * Factor which evaluates provided unary functor and uses the result to compute + * error with respect to the provided measurement. * * Template parameters are * @param R: The return type of the functor after evaluation. @@ -40,13 +40,12 @@ namespace gtsam { * class MultiplyFunctor { * double m_; ///< simple multiplier * public: - * using argument_type = Matrix; - * using return_type = Matrix; * MultiplyFunctor(double m) : m_(m) {} * Matrix operator()(const Matrix &X, * OptionalJacobian<-1, -1> H = boost::none) const { - * if (H) *H = m_ * Matrix::Identity(X.rows()*X.cols(), - * X.rows()*X.cols()); return m_ * X; + * if (H) + * *H = m_ * Matrix::Identity(X.rows()*X.cols(), X.rows()*X.cols()); + * return m_ * X; * } * }; * @@ -72,7 +71,7 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { /** Construct with given x and the parameters of the basis * * @param key: Factor key - * @param z: Measurement object of type R + * @param z: Measurement object of same type as that returned by functor * @param model: Noise model * @param func: The instance of the functor object */ @@ -85,7 +84,7 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { /// @return a deep copy of this factor virtual NonlinearFactor::shared_ptr clone() const { return boost::static_pointer_cast( - NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); + NonlinearFactor::shared_ptr(new FunctorizedFactor(*this))); } Vector evaluateError(const T ¶ms, @@ -108,8 +107,8 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { } virtual bool equals(const NonlinearFactor &other, double tol = 1e-9) const { - const FunctorizedFactor *e = - dynamic_cast *>(&other); + const FunctorizedFactor *e = + dynamic_cast *>(&other); const bool base = Base::equals(*e, tol); return e && Base::equals(other, tol) && traits::Equals(this->measured_, e->measured_, tol); @@ -129,8 +128,21 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { }; /// traits -template -struct traits> - : public Testable> {}; +template +struct traits> + : public Testable> {}; + +/** + * Helper function to create a functorized factor. + * + * Uses function template deduction to identify return type and functor type, so + * template list only needs the functor argument type. + */ +template +FunctorizedFactor MakeFunctorizedFactor(Key key, const R &z, + const SharedNoiseModel &model, + const FUNC func) { + return FunctorizedFactor(key, z, model, func); +} } // namespace gtsam diff --git a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp index 9ff6b8e24..12dd6b91c 100644 --- a/gtsam/nonlinear/tests/testFunctorizedFactor.cpp +++ b/gtsam/nonlinear/tests/testFunctorizedFactor.cpp @@ -34,9 +34,6 @@ class MultiplyFunctor { double m_; ///< simple multiplier public: - using argument_type = Matrix; - using return_type = Matrix; - MultiplyFunctor(double m) : m_(m) {} Matrix operator()(const Matrix &X, @@ -47,13 +44,13 @@ class MultiplyFunctor { }; /* ************************************************************************* */ +// Test identity operation for FunctorizedFactor. TEST(FunctorizedFactor, Identity) { Matrix X = Matrix::Identity(3, 3), measurement = Matrix::Identity(3, 3); double multiplier = 1.0; - - FunctorizedFactor factor(key, measurement, model, - MultiplyFunctor(multiplier)); + auto functor = MultiplyFunctor(multiplier); + auto factor = MakeFunctorizedFactor(key, measurement, model, functor); Vector error = factor.evaluateError(X); @@ -61,41 +58,45 @@ TEST(FunctorizedFactor, Identity) { } /* ************************************************************************* */ +// Test FunctorizedFactor with multiplier value of 2. TEST(FunctorizedFactor, Multiply2) { double multiplier = 2.0; Matrix X = Matrix::Identity(3, 3); Matrix measurement = multiplier * Matrix::Identity(3, 3); - FunctorizedFactor factor(key, measurement, model, - MultiplyFunctor(multiplier)); + auto factor = MakeFunctorizedFactor(key, measurement, model, + MultiplyFunctor(multiplier)); Vector error = factor.evaluateError(X); EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } +/* ************************************************************************* */ +// Test equality function for FunctorizedFactor. TEST(FunctorizedFactor, Equality) { Matrix measurement = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor1(key, measurement, model, - MultiplyFunctor(multiplier)); - FunctorizedFactor factor2(key, measurement, model, - MultiplyFunctor(multiplier)); + auto factor1 = MakeFunctorizedFactor(key, measurement, model, + MultiplyFunctor(multiplier)); + auto factor2 = MakeFunctorizedFactor(key, measurement, model, + MultiplyFunctor(multiplier)); EXPECT(factor1.equals(factor2)); } -//****************************************************************************** +/* *************************************************************************** */ +// Test Jacobians of FunctorizedFactor. TEST(FunctorizedFactor, Jacobians) { Matrix X = Matrix::Identity(3, 3); Matrix actualH; double multiplier = 2.0; - FunctorizedFactor factor(key, X, model, - MultiplyFunctor(multiplier)); + auto factor = + MakeFunctorizedFactor(key, X, model, MultiplyFunctor(multiplier)); Values values; values.insert(key, X); @@ -105,13 +106,14 @@ TEST(FunctorizedFactor, Jacobians) { } /* ************************************************************************* */ +// Test print result of FunctorizedFactor. TEST(FunctorizedFactor, Print) { Matrix X = Matrix::Identity(2, 2); double multiplier = 2.0; - FunctorizedFactor factor(key, X, model, - MultiplyFunctor(multiplier)); + auto factor = + MakeFunctorizedFactor(key, X, model, MultiplyFunctor(multiplier)); // redirect output to buffer so we can compare stringstream buffer; @@ -137,7 +139,7 @@ TEST(FunctorizedFactor, Print) { } /* ************************************************************************* */ -// Test factor using a std::function type. +// Test FunctorizedFactor using a std::function type. TEST(FunctorizedFactor, Functional) { double multiplier = 2.0; Matrix X = Matrix::Identity(3, 3); @@ -145,7 +147,8 @@ TEST(FunctorizedFactor, Functional) { std::function)> functional = MultiplyFunctor(multiplier); - FunctorizedFactor factor(key, measurement, model, functional); + auto factor = + MakeFunctorizedFactor(key, measurement, model, functional); Vector error = factor.evaluateError(X); @@ -153,6 +156,7 @@ TEST(FunctorizedFactor, Functional) { } /* ************************************************************************* */ +// Test FunctorizedFactor with a lambda function. TEST(FunctorizedFactor, Lambda) { double multiplier = 2.0; Matrix X = Matrix::Identity(3, 3); @@ -166,15 +170,14 @@ TEST(FunctorizedFactor, Lambda) { return multiplier * X; }; // FunctorizedFactor factor(key, measurement, model, lambda); - auto factor = FunctorizedFactor(key, measurement, model, lambda); + auto factor = MakeFunctorizedFactor(key, measurement, model, lambda); Vector error = factor.evaluateError(X); EXPECT(assert_equal(Vector::Zero(9), error, 1e-9)); } -/* ************************************************************************* - */ +/* ************************************************************************* */ int main() { TestResult tr; return TestRegistry::runAllTests(tr); From 683e37f14889701b5acd40797d6a5a0648c2e601 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Mon, 6 Jul 2020 23:36:17 -0400 Subject: [PATCH 120/199] Fix FrobeniusWormholeFactor Python test --- cython/gtsam/tests/test_FrobeniusFactor.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cython/gtsam/tests/test_FrobeniusFactor.py b/cython/gtsam/tests/test_FrobeniusFactor.py index 82d1fb410..f3f5354bb 100644 --- a/cython/gtsam/tests/test_FrobeniusFactor.py +++ b/cython/gtsam/tests/test_FrobeniusFactor.py @@ -12,7 +12,7 @@ Author: Frank Dellaert import unittest import numpy as np -from gtsam import (SO3, SO4, FrobeniusBetweenFactorSO4, FrobeniusFactorSO4, +from gtsam import (Rot3, SO3, SO4, FrobeniusBetweenFactorSO4, FrobeniusFactorSO4, FrobeniusWormholeFactor, SOn) id = SO4() @@ -43,7 +43,7 @@ class TestFrobeniusFactorSO4(unittest.TestCase): """Test creation of a factor that calculates Shonan error.""" R1 = SO3.Expmap(v1[3:]) R2 = SO3.Expmap(v2[3:]) - factor = FrobeniusWormholeFactor(1, 2, R1.between(R2), p=4) + factor = FrobeniusWormholeFactor(1, 2, Rot3(R1.between(R2).matrix()), p=4) I4 = SOn(4) Q1 = I4.retract(v1) Q2 = I4.retract(v2) From 66570469c5f890af0245ec0b1334c9a9c1294782 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 7 Jul 2020 17:38:27 -0400 Subject: [PATCH 121/199] fix working directory for python install target --- cython/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cython/CMakeLists.txt b/cython/CMakeLists.txt index 65a9e9c62..221025575 100644 --- a/cython/CMakeLists.txt +++ b/cython/CMakeLists.txt @@ -7,7 +7,7 @@ if (GTSAM_INSTALL_CYTHON_TOOLBOX) set(python_install_target python-install) add_custom_target(${python_install_target} COMMAND ${PYTHON_EXECUTABLE} ${GTSAM_CYTHON_INSTALL_PATH}/setup.py install - WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_FULLPATH}) + WORKING_DIRECTORY ${GTSAM_CYTHON_INSTALL_PATH}) # build and include the eigency version of eigency add_subdirectory(gtsam_eigency) From 73007fe0483c81f72b05220b8d0a45b8eb18a363 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 7 Jul 2020 19:24:38 -0400 Subject: [PATCH 122/199] test SmartFactor when body_P_sensor is passed in --- gtsam/slam/SmartFactorBase.h | 7 ++-- gtsam/slam/tests/testSmartFactorBase.cpp | 42 +++++++++++++++++++++--- 2 files changed, 41 insertions(+), 8 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 717a9c1f2..3bedf599f 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -206,11 +206,12 @@ protected: boost::optional E = boost::none) const { Vector ue = cameras.reprojectionError(point, measured_, Fs, E); if (body_P_sensor_ && Fs) { - const Pose3 sensor_P_body = body_P_sensor_->inverse(); + const Pose3 sensor_T_body = body_P_sensor_->inverse(); for (size_t i = 0; i < Fs->size(); i++) { - const Pose3 w_Pose_body = cameras[i].pose() * sensor_P_body; + const Pose3 world_T_body = cameras[i].pose() * sensor_T_body; Matrix J(6, 6); - const Pose3 world_P_body = w_Pose_body.compose(*body_P_sensor_, J); + // Call compose to compute Jacobian + world_T_body.compose(*body_P_sensor_, J); Fs->at(i) = Fs->at(i) * J; } } diff --git a/gtsam/slam/tests/testSmartFactorBase.cpp b/gtsam/slam/tests/testSmartFactorBase.cpp index f69f4c113..bb04ad56d 100644 --- a/gtsam/slam/tests/testSmartFactorBase.cpp +++ b/gtsam/slam/tests/testSmartFactorBase.cpp @@ -37,11 +37,11 @@ class PinholeFactor: public SmartFactorBase > { public: typedef SmartFactorBase > Base; PinholeFactor() {} - PinholeFactor(const SharedNoiseModel& sharedNoiseModel): Base(sharedNoiseModel) { - } - virtual double error(const Values& values) const { - return 0.0; - } + PinholeFactor(const SharedNoiseModel& sharedNoiseModel, + boost::optional body_P_sensor = boost::none, + size_t expectedNumberCameras = 10) + : Base(sharedNoiseModel, body_P_sensor, expectedNumberCameras) {} + virtual double error(const Values& values) const { return 0.0; } virtual boost::shared_ptr linearize( const Values& values) const { return boost::shared_ptr(new JacobianFactor()); @@ -60,6 +60,38 @@ TEST(SmartFactorBase, Pinhole) { EXPECT_LONGS_EQUAL(2 * 2, f.dim()); } +TEST(SmartFactorBase, PinholeWithSensor) { + Pose3 body_P_sensor(Rot3(), Point3(1, 0, 0)); + PinholeFactor f = PinholeFactor(unit2, body_P_sensor); + EXPECT(assert_equal(f.body_P_sensor(), body_P_sensor)); + + PinholeFactor::Cameras cameras; + // Assume body at origin. + Pose3 world_T_body = Pose3(); + // Camera coordinates in world frame. + Pose3 wTc = world_T_body * body_P_sensor; + cameras.push_back(PinholeCamera(wTc)); + + // Simple point to project slightly off image center + Point3 p(0, 0, 10); + Point2 measurement = cameras[0].project(p); + f.add(measurement, 1); + + PinholeFactor::Cameras::FBlocks Fs; + Matrix E; + Vector error = f.unwhitenedError(cameras, p, Fs, E); + + Vector expectedError = Vector::Zero(2); + Matrix29 expectedFs; + expectedFs << -0.001, -1.00001, 0, -0.1, 0, -0.01, 0, 0, 0, 1, 0, 0, 0, -0.1, 0, 0, 0, 0; + Matrix23 expectedE; + expectedE << 0.1, 0, 0.01, 0, 0.1, 0; + + EXPECT(assert_equal(error, expectedError)); + EXPECT(assert_equal(expectedFs, Fs[0])); // We only have the jacobian for the 1 camera + EXPECT(assert_equal(expectedE, E)); +} + /* ************************************************************************* */ #include From e3712772cbdfa2f0e851e80241d46236c901c7b9 Mon Sep 17 00:00:00 2001 From: Thomas Jespersen Date: Wed, 8 Jul 2020 00:05:38 +0800 Subject: [PATCH 123/199] ISAM2 Kitti example: Addressed review comments --- examples/IMUKittiExampleGPS.cpp | 380 ++++++++++++++++++-------------- 1 file changed, 220 insertions(+), 160 deletions(-) diff --git a/examples/IMUKittiExampleGPS.cpp b/examples/IMUKittiExampleGPS.cpp index 9f302ab2f..7cfccbc11 100644 --- a/examples/IMUKittiExampleGPS.cpp +++ b/examples/IMUKittiExampleGPS.cpp @@ -24,241 +24,301 @@ #include #include #include -#include #include #include + #include #include #include -using namespace gtsam; using namespace std; +using namespace gtsam; -using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) -using symbol_shorthand::V; // Vel (xdot,ydot,zdot) -using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) +using symbol_shorthand::X; // Pose3 (x,y,z,r,p,y) +using symbol_shorthand::V; // Vel (xdot,ydot,zdot) +using symbol_shorthand::B; // Bias (ax,ay,az,gx,gy,gz) -typedef struct { - double Time; +struct KittiCalibration { + double body_ptx; + double body_pty; + double body_ptz; + double body_prx; + double body_pry; + double body_prz; + double accelerometer_sigma; + double gyroscope_sigma; + double integration_sigma; + double accelerometer_bias_sigma; + double gyroscope_bias_sigma; + double average_delta_t; +}; + +struct ImuMeasurement { + double time; double dt; - Vector3 Accelerometer; - Vector3 Gyroscope; // omega -} imuMeasurement_t; + Vector3 accelerometer; + Vector3 gyroscope; // omega +}; -typedef struct { - double Time; - Vector3 Position; // x,y,z -} gpsMeasurement_t; +struct GpsMeasurement { + double time; + Vector3 position; // x,y,z +}; -const string output_filename = "IMUKittyExampleGPSResults.csv"; +const string output_filename = "IMUKittiExampleGPSResults.csv"; -int main(int argc, char* argv[]) -{ +void loadKittiData(KittiCalibration& kitti_calibration, + vector& imu_measurements, + vector& gps_measurements) { string line; // Read IMU metadata and compute relative sensor pose transforms - // BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma GyroscopeSigma IntegrationSigma AccelerometerBiasSigma GyroscopeBiasSigma AverageDeltaT - // 0 0 0 0 0 0 0.01 0.000175 0 0.000167 2.91e-006 0.0100395199348279 - string IMU_metadata_file = findExampleDataFile("KittiEquivBiasedImu_metadata.txt"); - ifstream IMU_metadata(IMU_metadata_file.c_str()); + // BodyPtx BodyPty BodyPtz BodyPrx BodyPry BodyPrz AccelerometerSigma GyroscopeSigma IntegrationSigma + // AccelerometerBiasSigma GyroscopeBiasSigma AverageDeltaT + string imu_metadata_file = findExampleDataFile("KittiEquivBiasedImu_metadata.txt"); + ifstream imu_metadata(imu_metadata_file.c_str()); printf("-- Reading sensor metadata\n"); - getline(IMU_metadata, line, '\n'); // ignore the first line + getline(imu_metadata, line, '\n'); // ignore the first line - double BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz, AccelerometerSigma, GyroscopeSigma, IntegrationSigma, AccelerometerBiasSigma, GyroscopeBiasSigma, AverageDeltaT; - getline(IMU_metadata, line, '\n'); - sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf", &BodyPtx, &BodyPty, &BodyPtz, &BodyPrx, &BodyPry, &BodyPrz, &AccelerometerSigma, &GyroscopeSigma, &IntegrationSigma, &AccelerometerBiasSigma, &GyroscopeBiasSigma, &AverageDeltaT); - printf("IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz, AccelerometerSigma, GyroscopeSigma, IntegrationSigma, AccelerometerBiasSigma, GyroscopeBiasSigma, AverageDeltaT); + // Load Kitti calibration + getline(imu_metadata, line, '\n'); + sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf", + &kitti_calibration.body_ptx, + &kitti_calibration.body_pty, + &kitti_calibration.body_ptz, + &kitti_calibration.body_prx, + &kitti_calibration.body_pry, + &kitti_calibration.body_prz, + &kitti_calibration.accelerometer_sigma, + &kitti_calibration.gyroscope_sigma, + &kitti_calibration.integration_sigma, + &kitti_calibration.accelerometer_bias_sigma, + &kitti_calibration.gyroscope_bias_sigma, + &kitti_calibration.average_delta_t); + printf("IMU metadata: %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf %lf\n", + kitti_calibration.body_ptx, + kitti_calibration.body_pty, + kitti_calibration.body_ptz, + kitti_calibration.body_prx, + kitti_calibration.body_pry, + kitti_calibration.body_prz, + kitti_calibration.accelerometer_sigma, + kitti_calibration.gyroscope_sigma, + kitti_calibration.integration_sigma, + kitti_calibration.accelerometer_bias_sigma, + kitti_calibration.gyroscope_bias_sigma, + kitti_calibration.average_delta_t); - Vector6 BodyP = (Vector(6) << BodyPtx, BodyPty, BodyPtz, BodyPrx, BodyPry, BodyPrz).finished(); + // Read IMU data + // Time dt accelX accelY accelZ omegaX omegaY omegaZ + string imu_data_file = findExampleDataFile("KittiEquivBiasedImu.txt"); + printf("-- Reading IMU measurements from file\n"); + { + ifstream imu_data(imu_data_file.c_str()); + getline(imu_data, line, '\n'); // ignore the first line + + double time = 0, dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0; + while (!imu_data.eof()) { + getline(imu_data, line, '\n'); + sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf", + &time, &dt, + &acc_x, &acc_y, &acc_z, + &gyro_x, &gyro_y, &gyro_z); + + ImuMeasurement measurement; + measurement.time = time; + measurement.dt = dt; + measurement.accelerometer = Vector3(acc_x, acc_y, acc_z); + measurement.gyroscope = Vector3(gyro_x, gyro_y, gyro_z); + imu_measurements.push_back(measurement); + } + } + + // Read GPS data + // Time,X,Y,Z + string gps_data_file = findExampleDataFile("KittiGps_converted.txt"); + printf("-- Reading GPS measurements from file\n"); + { + ifstream gps_data(gps_data_file.c_str()); + getline(gps_data, line, '\n'); // ignore the first line + + double time = 0, gps_x = 0, gps_y = 0, gps_z = 0; + while (!gps_data.eof()) { + getline(gps_data, line, '\n'); + sscanf(line.c_str(), "%lf,%lf,%lf,%lf", &time, &gps_x, &gps_y, &gps_z); + + GpsMeasurement measurement; + measurement.time = time; + measurement.position = Vector3(gps_x, gps_y, gps_z); + gps_measurements.push_back(measurement); + } + } +} + +int main(int argc, char* argv[]) { + KittiCalibration kitti_calibration; + vector imu_measurements; + vector gps_measurements; + loadKittiData(kitti_calibration, imu_measurements, gps_measurements); + + Vector6 BodyP = (Vector(6) << kitti_calibration.body_ptx, kitti_calibration.body_pty, kitti_calibration.body_ptz, + kitti_calibration.body_prx, kitti_calibration.body_pry, kitti_calibration.body_prz) + .finished(); auto body_T_imu = Pose3::Expmap(BodyP); if (!body_T_imu.equals(Pose3(), 1e-5)) { printf("Currently only support IMUinBody is identity, i.e. IMU and body frame are the same"); exit(-1); } - // Read IMU data - // Time dt accelX accelY accelZ omegaX omegaY omegaZ - // 46534.47837579 46534.47837579 1.7114864219577 0.1717911743144 9.80533438749 -0.0032006241515747 0.031231284764596 -0.0063569265706488 - vector IMU_measurements; - string IMU_data_file = findExampleDataFile("KittiEquivBiasedImu.txt"); - - printf("-- Reading IMU measurements from file\n"); - { - ifstream IMU_data(IMU_data_file.c_str()); - getline(IMU_data, line, '\n'); // ignore the first line - - double time = 0, dt = 0, acc_x = 0, acc_y = 0, acc_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0; - while (!IMU_data.eof()) { - getline(IMU_data, line, '\n'); - sscanf(line.c_str(), "%lf %lf %lf %lf %lf %lf %lf %lf", &time, &dt, &acc_x, &acc_y, &acc_z, &gyro_x, - &gyro_y, &gyro_z); - - imuMeasurement_t measurement; - measurement.Time = time; - measurement.dt = dt; - measurement.Accelerometer = Vector3(acc_x, acc_y, acc_z); - measurement.Gyroscope = Vector3(gyro_x, gyro_y, gyro_z); - IMU_measurements.push_back(measurement); - } - } - - // Read GPS data - // Time,X,Y,Z - // 46534.478375790000428,-6.8269361350059405424,-11.868164241239471224,0.040306091310000624617 - vector GPS_measurements; - string GPS_data_file = findExampleDataFile("KittiGps_converted.txt"); - - printf("-- Reading GPS measurements from file\n"); - { - ifstream GPS_data(GPS_data_file.c_str()); - getline(GPS_data, line, '\n'); // ignore the first line - - double time = 0, gps_x = 0, gps_y = 0, gps_z = 0; - while (!GPS_data.eof()) { - getline(GPS_data, line, '\n'); - sscanf(line.c_str(), "%lf,%lf,%lf,%lf", &time, &gps_x, &gps_y, &gps_z); - - gpsMeasurement_t measurement; - measurement.Time = time; - measurement.Position = Vector3(gps_x, gps_y, gps_z); - GPS_measurements.push_back(measurement); - } - } - // Configure different variables - double tOffset = GPS_measurements[0].Time; - size_t firstGPSPose = 1; - size_t GPSskip = 10; // Skip this many GPS measurements each time + double t_offset = gps_measurements[0].time; + size_t first_gps_pose = 1; + size_t gps_skip = 10; // Skip this many GPS measurements each time double g = 9.8; - auto w_coriolis = Vector3(); // zero vector + auto w_coriolis = Vector3(); // zero vector // Configure noise models - noiseModel::Diagonal::shared_ptr noiseModelGPS = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), Vector3::Constant(1.0/0.07)).finished()); + auto noise_model_gps = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), + Vector3::Constant(1.0/0.07)) + .finished()); // Set initial conditions for the estimated trajectory - auto currentPoseGlobal = Pose3(Rot3(), GPS_measurements[firstGPSPose].Position); // initial pose is the reference frame (navigation frame) - auto currentVelocityGlobal = Vector3(); // the vehicle is stationary at the beginning at position 0,0,0 - auto currentBias = imuBias::ConstantBias(); // init with zero bias + // initial pose is the reference frame (navigation frame) + auto current_pose_global = Pose3(Rot3(), gps_measurements[first_gps_pose].position); + auto current_velocity_global = Vector3(); // the vehicle is stationary at the beginning at position 0,0,0 + auto current_bias = imuBias::ConstantBias(); // init with zero bias - noiseModel::Diagonal::shared_ptr sigma_init_x = noiseModel::Isotropic::Precisions((Vector(6) << Vector3::Constant(0), Vector3::Constant(1.0)).finished()); - noiseModel::Diagonal::shared_ptr sigma_init_v = noiseModel::Isotropic::Sigma(3, 1000.0); - noiseModel::Diagonal::shared_ptr sigma_init_b = noiseModel::Isotropic::Sigmas((Vector(6) << Vector3::Constant(0.100), Vector3::Constant(5.00e-05)).finished()); + auto sigma_init_x = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), + Vector3::Constant(1.0)) + .finished()); + auto sigma_init_v = noiseModel::Diagonal::Sigmas(Vector3::Constant(1000.0)); + auto sigma_init_b = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(0.100), + Vector3::Constant(5.00e-05)) + .finished()); // Set IMU preintegration parameters - Matrix33 measured_acc_cov = Matrix33::Identity(3,3) * pow(AccelerometerSigma,2); - Matrix33 measured_omega_cov = Matrix33::Identity(3,3) * pow(GyroscopeSigma,2); - Matrix33 integration_error_cov = Matrix33::Identity(3,3) * pow(IntegrationSigma,2); // error committed in integrating position from velocities + Matrix33 measured_acc_cov = I_3x3 * pow(kitti_calibration.accelerometer_sigma, 2); + Matrix33 measured_omega_cov = I_3x3 * pow(kitti_calibration.gyroscope_sigma, 2); + // error committed in integrating position from velocities + Matrix33 integration_error_cov = I_3x3 * pow(kitti_calibration.integration_sigma, 2); - boost::shared_ptr IMU_params = PreintegratedImuMeasurements::Params::MakeSharedU(g); - IMU_params->accelerometerCovariance = measured_acc_cov; // acc white noise in continuous - IMU_params->integrationCovariance = integration_error_cov; // integration uncertainty continuous - IMU_params->gyroscopeCovariance = measured_omega_cov; // gyro white noise in continuous - IMU_params->omegaCoriolis = w_coriolis; + auto imu_params = PreintegratedImuMeasurements::Params::MakeSharedU(g); + imu_params->accelerometerCovariance = measured_acc_cov; // acc white noise in continuous + imu_params->integrationCovariance = integration_error_cov; // integration uncertainty continuous + imu_params->gyroscopeCovariance = measured_omega_cov; // gyro white noise in continuous + imu_params->omegaCoriolis = w_coriolis; - std::shared_ptr currentSummarizedMeasurement = nullptr; + std::shared_ptr current_summarized_measurement = nullptr; // Set ISAM2 parameters and create ISAM2 solver object - ISAM2Params isamParams; - isamParams.factorization = ISAM2Params::CHOLESKY; - isamParams.relinearizeSkip = 10; + ISAM2Params isam_params; + isam_params.factorization = ISAM2Params::CHOLESKY; + isam_params.relinearizeSkip = 10; - ISAM2 isam(isamParams); + ISAM2 isam(isam_params); // Create the factor graph and values object that will store new factors and values to add to the incremental graph - NonlinearFactorGraph newFactors; - Values newValues; // values storing the initial estimates of new nodes in the factor graph + NonlinearFactorGraph new_factors; + Values new_values; // values storing the initial estimates of new nodes in the factor graph /// Main loop: /// (1) we read the measurements /// (2) we create the corresponding factors in the graph /// (3) we solve the graph to obtain and optimal estimate of robot trajectory printf("-- Starting main loop: inference is performed at each time step, but we plot trajectory every 10 steps\n"); - size_t imuMeasurementIndex = 0; - for (size_t gpsMeasurementIndex = firstGPSPose; gpsMeasurementIndex < GPS_measurements.size() - 1; gpsMeasurementIndex++) { + size_t j = 0; + for (size_t i = first_gps_pose; i < gps_measurements.size() - 1; i++) { // At each non=IMU measurement we initialize a new node in the graph - auto currentPoseKey = X(gpsMeasurementIndex); - auto currentVelKey = V(gpsMeasurementIndex); - auto currentBiasKey = B(gpsMeasurementIndex); - double t = GPS_measurements[gpsMeasurementIndex].Time; + auto current_pose_key = X(i); + auto current_vel_key = V(i); + auto current_bias_key = B(i); + double t = gps_measurements[i].time; - if (gpsMeasurementIndex == firstGPSPose) { + if (i == first_gps_pose) { // Create initial estimate and prior on initial pose, velocity, and biases - newValues.insert(currentPoseKey, currentPoseGlobal); - newValues.insert(currentVelKey, currentVelocityGlobal); - newValues.insert(currentBiasKey, currentBias); - newFactors.add(PriorFactor(currentPoseKey, currentPoseGlobal, sigma_init_x)); - newFactors.add(PriorFactor(currentVelKey, currentVelocityGlobal, sigma_init_v)); - newFactors.add(PriorFactor(currentBiasKey, currentBias, sigma_init_b)); + new_values.insert(current_pose_key, current_pose_global); + new_values.insert(current_vel_key, current_velocity_global); + new_values.insert(current_bias_key, current_bias); + new_factors.emplace_shared>(current_pose_key, current_pose_global, sigma_init_x); + new_factors.emplace_shared>(current_vel_key, current_velocity_global, sigma_init_v); + new_factors.emplace_shared>(current_bias_key, current_bias, sigma_init_b); } else { - double t_previous = GPS_measurements[gpsMeasurementIndex-1].Time; + double t_previous = gps_measurements[i-1].time; // Summarize IMU data between the previous GPS measurement and now - currentSummarizedMeasurement = std::make_shared(IMU_params, currentBias); - static size_t includedIMUmeasurementCount = 0; - while (imuMeasurementIndex < IMU_measurements.size() && IMU_measurements[imuMeasurementIndex].Time <= t) { - if (IMU_measurements[imuMeasurementIndex].Time >= t_previous) { - currentSummarizedMeasurement->integrateMeasurement(IMU_measurements[imuMeasurementIndex].Accelerometer, IMU_measurements[imuMeasurementIndex].Gyroscope, IMU_measurements[imuMeasurementIndex].dt); - includedIMUmeasurementCount++; + current_summarized_measurement = std::make_shared(imu_params, current_bias); + static size_t included_imu_measurement_count = 0; + while (j < imu_measurements.size() && imu_measurements[j].time <= t) { + if (imu_measurements[j].time >= t_previous) { + current_summarized_measurement->integrateMeasurement(imu_measurements[j].accelerometer, + imu_measurements[j].gyroscope, + imu_measurements[j].dt); + included_imu_measurement_count++; } - imuMeasurementIndex++; + j++; } // Create IMU factor - auto previousPoseKey = X(gpsMeasurementIndex-1); - auto previousVelKey = V(gpsMeasurementIndex-1); - auto previousBiasKey = B(gpsMeasurementIndex-1); + auto previous_pose_key = X(i-1); + auto previous_vel_key = V(i-1); + auto previous_bias_key = B(i-1); - newFactors.add(ImuFactor( - previousPoseKey, previousVelKey, - currentPoseKey, currentVelKey, - previousBiasKey, *currentSummarizedMeasurement)); + new_factors.emplace_shared(previous_pose_key, previous_vel_key, + current_pose_key, current_vel_key, + previous_bias_key, *current_summarized_measurement); // Bias evolution as given in the IMU metadata - noiseModel::Diagonal::shared_ptr sigma_between_b = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(sqrt(includedIMUmeasurementCount) * AccelerometerBiasSigma), Vector3::Constant(sqrt(includedIMUmeasurementCount) * GyroscopeBiasSigma)).finished()); - newFactors.add(BetweenFactor(previousBiasKey, currentBiasKey, imuBias::ConstantBias(), sigma_between_b)); + auto sigma_between_b = noiseModel::Diagonal::Sigmas((Vector(6) << + Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.accelerometer_bias_sigma), + Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.gyroscope_bias_sigma)) + .finished()); + new_factors.emplace_shared>(previous_bias_key, + current_bias_key, + imuBias::ConstantBias(), + sigma_between_b); // Create GPS factor - auto GPSPose = Pose3(currentPoseGlobal.rotation(), GPS_measurements[gpsMeasurementIndex].Position); - if ((gpsMeasurementIndex % GPSskip) == 0) { - newFactors.add(PriorFactor(currentPoseKey, GPSPose, noiseModelGPS)); - newValues.insert(currentPoseKey, GPSPose); + auto gps_pose = Pose3(current_pose_global.rotation(), gps_measurements[i].position); + if ((i % gps_skip) == 0) { + new_factors.emplace_shared>(current_pose_key, gps_pose, noise_model_gps); + new_values.insert(current_pose_key, gps_pose); printf("################ POSE INCLUDED AT TIME %lf ################\n", t); - GPSPose.translation().print(); + gps_pose.translation().print(); printf("\n\n"); } else { - newValues.insert(currentPoseKey, currentPoseGlobal); + new_values.insert(current_pose_key, current_pose_global); } // Add initial values for velocity and bias based on the previous estimates - newValues.insert(currentVelKey, currentVelocityGlobal); - newValues.insert(currentBiasKey, currentBias); + new_values.insert(current_vel_key, current_velocity_global); + new_values.insert(current_bias_key, current_bias); // Update solver // ======================================================================= // We accumulate 2*GPSskip GPS measurements before updating the solver at - //first so that the heading becomes observable. - if (gpsMeasurementIndex > (firstGPSPose + 2*GPSskip)) { + // first so that the heading becomes observable. + if (i > (first_gps_pose + 2*gps_skip)) { printf("################ NEW FACTORS AT TIME %lf ################\n", t); - newFactors.print(); + new_factors.print(); - isam.update(newFactors, newValues); + isam.update(new_factors, new_values); // Reset the newFactors and newValues list - newFactors.resize(0); - newValues.clear(); + new_factors.resize(0); + new_values.clear(); // Extract the result/current estimates Values result = isam.calculateEstimate(); - currentPoseGlobal = result.at(currentPoseKey); - currentVelocityGlobal = result.at(currentVelKey); - currentBias = result.at(currentBiasKey); + current_pose_global = result.at(current_pose_key); + current_velocity_global = result.at(current_vel_key); + current_bias = result.at(current_bias_key); printf("\n################ POSE AT TIME %lf ################\n", t); - currentPoseGlobal.print(); + current_pose_global.print(); printf("\n\n"); } } @@ -270,24 +330,24 @@ int main(int argc, char* argv[]) fprintf(fp_out, "#time(s),x(m),y(m),z(m),qx,qy,qz,qw,gt_x(m),gt_y(m),gt_z(m)\n"); Values result = isam.calculateEstimate(); - for (size_t gpsMeasurementIndex = firstGPSPose; gpsMeasurementIndex < GPS_measurements.size() - 1; gpsMeasurementIndex++) { - auto poseKey = X(gpsMeasurementIndex); - auto velKey = V(gpsMeasurementIndex); - auto biasKey = B(gpsMeasurementIndex); + for (size_t i = first_gps_pose; i < gps_measurements.size() - 1; i++) { + auto pose_key = X(i); + auto vel_key = V(i); + auto bias_key = B(i); - auto pose = result.at(poseKey); - auto velocity = result.at(velKey); - auto bias = result.at(biasKey); + auto pose = result.at(pose_key); + auto velocity = result.at(vel_key); + auto bias = result.at(bias_key); auto pose_quat = pose.rotation().toQuaternion(); - auto gps = GPS_measurements[gpsMeasurementIndex].Position; + auto gps = gps_measurements[i].position; fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", - GPS_measurements[gpsMeasurementIndex].Time, + gps_measurements[i].time, pose.x(), pose.y(), pose.z(), pose_quat.x(), pose_quat.y(), pose_quat.z(), pose_quat.w(), gps(0), gps(1), gps(2)); } fclose(fp_out); -} \ No newline at end of file +} From 00106ba3605201b6d0e0b61076521c974458a6f4 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Wed, 8 Jul 2020 02:30:19 -0700 Subject: [PATCH 124/199] Second attempt at a wrapper fix. 1) Some serialization code was missing from SOn.SOn.h (not sure why this wouldn't have been a problem before building the MATLAB toolbox ...) 2) FrobeniusFacotor stuff needed a couple GTSAM_EXPORT statements --- gtsam/geometry/SOn.h | 17 +++++++++++++++++ gtsam/slam/FrobeniusFactor.h | 4 ++-- 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index a08f87783..74b7b8521 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -30,6 +30,9 @@ #include #include + // For save/load +#include + namespace gtsam { namespace internal { @@ -292,6 +295,10 @@ class SO : public LieGroup, internal::DimensionSO(N)> { boost::none) const; /// @} + template + friend void save(Archive&, SO&, const unsigned int); + template + friend void load(Archive&, SO&, const unsigned int); template friend void serialize(Archive&, SO&, const unsigned int); friend class boost::serialization::access; @@ -329,6 +336,16 @@ template <> SOn LieGroup::between(const SOn& g, DynamicJacobian H1, DynamicJacobian H2) const; +/** Serialization function */ +template +void serialize( + Archive& ar, SOn& Q, + const unsigned int file_version +) { + Matrix& M = Q.matrix_; + ar& M; +} + /* * Define the traits. internal::LieGroup provides both Lie group and Testable */ diff --git a/gtsam/slam/FrobeniusFactor.h b/gtsam/slam/FrobeniusFactor.h index 60fa82ab4..a73445ae0 100644 --- a/gtsam/slam/FrobeniusFactor.h +++ b/gtsam/slam/FrobeniusFactor.h @@ -33,7 +33,7 @@ namespace gtsam { * isotropic. If it is, we extend to 'Dim' dimensions, otherwise we throw an * error. If defaultToUnit == false throws an exception on unexepcted input. */ -boost::shared_ptr ConvertPose3NoiseModel( + GTSAM_EXPORT boost::shared_ptr ConvertPose3NoiseModel( const SharedNoiseModel& model, size_t d, bool defaultToUnit = true); /** @@ -125,7 +125,7 @@ class FrobeniusBetweenFactor : public NoiseModelFactor2 { * the SO(p) matrices down to a Stiefel manifold of p*d matrices. * TODO(frank): template on D=2 or 3 */ -class FrobeniusWormholeFactor : public NoiseModelFactor2 { +class GTSAM_EXPORT FrobeniusWormholeFactor : public NoiseModelFactor2 { Matrix M_; ///< measured rotation between R1 and R2 size_t p_, pp_, dimension_; ///< dimensionality constants Matrix G_; ///< matrix of vectorized generators From aaddf52cb102f2a5ab5440c807a1c0871ff81246 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 8 Jul 2020 12:23:01 -0400 Subject: [PATCH 125/199] Abstracted out serialization code for PreintegrationBase --- gtsam/navigation/ManifoldPreintegration.h | 4 +--- gtsam/navigation/PreintegrationBase.h | 10 ++++++++++ gtsam/navigation/TangentPreintegration.h | 4 +--- 3 files changed, 12 insertions(+), 6 deletions(-) diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 22897b9d4..97ad04744 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -118,10 +118,8 @@ private: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & BOOST_SERIALIZATION_NVP(p_); - ar & BOOST_SERIALIZATION_NVP(deltaTij_); + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); ar & BOOST_SERIALIZATION_NVP(deltaXij_); - ar & BOOST_SERIALIZATION_NVP(biasHat_); ar & bs::make_nvp("delRdelBiasOmega_", bs::make_array(delRdelBiasOmega_.data(), delRdelBiasOmega_.size())); ar & bs::make_nvp("delPdelBiasAcc_", bs::make_array(delPdelBiasAcc_.data(), delPdelBiasAcc_.size())); ar & bs::make_nvp("delPdelBiasOmega_", bs::make_array(delPdelBiasOmega_.data(), delPdelBiasOmega_.size())); diff --git a/gtsam/navigation/PreintegrationBase.h b/gtsam/navigation/PreintegrationBase.h index eb30c1f13..29d7814b5 100644 --- a/gtsam/navigation/PreintegrationBase.h +++ b/gtsam/navigation/PreintegrationBase.h @@ -213,6 +213,16 @@ class GTSAM_EXPORT PreintegrationBase { /// @} #endif + private: + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int /*version*/) { + ar & BOOST_SERIALIZATION_NVP(p_); + ar & BOOST_SERIALIZATION_NVP(biasHat_); + ar & BOOST_SERIALIZATION_NVP(deltaTij_); + } + public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index edf76e562..99aa10b3f 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -132,9 +132,7 @@ private: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & BOOST_SERIALIZATION_NVP(p_); - ar & BOOST_SERIALIZATION_NVP(biasHat_); - ar & BOOST_SERIALIZATION_NVP(deltaTij_); + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); ar & bs::make_nvp("preintegrated_", bs::make_array(preintegrated_.data(), preintegrated_.size())); ar & bs::make_nvp("preintegrated_H_biasAcc_", bs::make_array(preintegrated_H_biasAcc_.data(), preintegrated_H_biasAcc_.size())); ar & bs::make_nvp("preintegrated_H_biasOmega_", bs::make_array(preintegrated_H_biasOmega_.data(), preintegrated_H_biasOmega_.size())); From 283999b017f8c0b41ada170a74030f41ef6c1ca1 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Wed, 8 Jul 2020 11:52:51 -0700 Subject: [PATCH 126/199] Unnecessary include statement --- gtsam/geometry/SOn.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index 74b7b8521..f44c578cc 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -30,9 +30,6 @@ #include #include - // For save/load -#include - namespace gtsam { namespace internal { From 8d921c82a0af925586f1a3e4f58640ad47afa4db Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 8 Jul 2020 16:10:33 -0400 Subject: [PATCH 127/199] Updated PreintegratedImuMeasurements docstring --- gtsam/navigation/ImuFactor.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 8e3f8f0a4..b5cff8147 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -87,8 +87,8 @@ public: /** * Constructor, initializes the class with no measurements - * @param bias Current estimate of acceleration and rotation rate biases - * @param p Parameters, typically fixed in a single application + * @param p Parameters, typically fixed in a single application + * @param biasHat Current estimate of acceleration and rotation rate biases */ PreintegratedImuMeasurements(const boost::shared_ptr& p, const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()) : From f8b48db581730ea484d7307cdac685dcf8b545f9 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Wed, 8 Jul 2020 17:10:43 -0400 Subject: [PATCH 128/199] Fix lambda check in logging optimizer --- cython/gtsam/utils/logging_optimizer.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index b201bb8aa..34f0fe5c9 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -50,5 +50,5 @@ def gtsam_optimize(optimizer: NonlinearOptimizer, def check_convergence(optimizer, current_error, new_error): return (optimizer.iterations() >= params.getMaxIterations()) or ( gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), - current_error, new_error)) + current_error, new_error)) or (optimizer.lambda_() > params.getlambdaUpperBound()) optimize(optimizer, check_convergence, hook) From cc2456678fb97a1d912f8f419b945a46efba9730 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 8 Jul 2020 23:37:32 -0400 Subject: [PATCH 129/199] Replace scoped name with direct name and instantiate base class in constructor --- gtsam/navigation/PreintegratedRotation.cpp | 6 +++--- gtsam/navigation/PreintegrationParams.cpp | 6 +++--- gtsam/navigation/PreintegrationParams.h | 13 +++++++------ 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/gtsam/navigation/PreintegratedRotation.cpp b/gtsam/navigation/PreintegratedRotation.cpp index 8c29d85dd..c5d48b734 100644 --- a/gtsam/navigation/PreintegratedRotation.cpp +++ b/gtsam/navigation/PreintegratedRotation.cpp @@ -25,7 +25,7 @@ using namespace std; namespace gtsam { -void PreintegratedRotation::Params::print(const string& s) const { +void PreintegratedRotationParams::print(const string& s) const { cout << s << endl; cout << "gyroscopeCovariance:\n[\n" << gyroscopeCovariance << "\n]" << endl; if (omegaCoriolis) @@ -34,8 +34,8 @@ void PreintegratedRotation::Params::print(const string& s) const { body_P_sensor->print("body_P_sensor"); } -bool PreintegratedRotation::Params::equals( - const PreintegratedRotation::Params& other, double tol) const { +bool PreintegratedRotationParams::equals( + const PreintegratedRotationParams& other, double tol) const { if (body_P_sensor) { if (!other.body_P_sensor || !assert_equal(*body_P_sensor, *other.body_P_sensor, tol)) diff --git a/gtsam/navigation/PreintegrationParams.cpp b/gtsam/navigation/PreintegrationParams.cpp index 61cd1617c..2298bb696 100644 --- a/gtsam/navigation/PreintegrationParams.cpp +++ b/gtsam/navigation/PreintegrationParams.cpp @@ -27,7 +27,7 @@ namespace gtsam { //------------------------------------------------------------------------------ void PreintegrationParams::print(const string& s) const { - PreintegratedRotation::Params::print(s); + PreintegratedRotationParams::print(s); cout << "accelerometerCovariance:\n[\n" << accelerometerCovariance << "\n]" << endl; cout << "integrationCovariance:\n[\n" << integrationCovariance << "\n]" @@ -39,10 +39,10 @@ void PreintegrationParams::print(const string& s) const { } //------------------------------------------------------------------------------ -bool PreintegrationParams::equals(const PreintegratedRotation::Params& other, +bool PreintegrationParams::equals(const PreintegratedRotationParams& other, double tol) const { auto e = dynamic_cast(&other); - return e != nullptr && PreintegratedRotation::Params::equals(other, tol) && + return e != nullptr && PreintegratedRotationParams::equals(other, tol) && use2ndOrderCoriolis == e->use2ndOrderCoriolis && equal_with_abs_tol(accelerometerCovariance, e->accelerometerCovariance, tol) && diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 4bff625ca..de9950e7d 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -31,7 +31,8 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { /// Default constructor for serialization only PreintegrationParams() - : accelerometerCovariance(I_3x3), + : PreintegratedRotationParams(), + accelerometerCovariance(I_3x3), integrationCovariance(I_3x3), use2ndOrderCoriolis(false), n_gravity(0, 0, -1) {} @@ -39,7 +40,8 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { /// The Params constructor insists on getting the navigation frame gravity vector /// For convenience, two commonly used conventions are provided by named constructors below PreintegrationParams(const Vector3& n_gravity) - : accelerometerCovariance(I_3x3), + : PreintegratedRotationParams(), + accelerometerCovariance(I_3x3), integrationCovariance(I_3x3), use2ndOrderCoriolis(false), n_gravity(n_gravity) {} @@ -54,8 +56,8 @@ struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { return boost::shared_ptr(new PreintegrationParams(Vector3(0, 0, -g))); } - void print(const std::string& s) const; - bool equals(const PreintegratedRotation::Params& other, double tol) const; + void print(const std::string& s="") const; + bool equals(const PreintegratedRotationParams& other, double tol) const; void setAccelerometerCovariance(const Matrix3& cov) { accelerometerCovariance = cov; } void setIntegrationCovariance(const Matrix3& cov) { integrationCovariance = cov; } @@ -73,8 +75,7 @@ protected: template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & boost::serialization::make_nvp("PreintegratedRotation_Params", - boost::serialization::base_object(*this)); + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotationParams); ar & bs::make_nvp("accelerometerCovariance", bs::make_array(accelerometerCovariance.data(), accelerometerCovariance.size())); ar & bs::make_nvp("integrationCovariance", bs::make_array(integrationCovariance.data(), integrationCovariance.size())); ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); From 95b4a49f643efe0a8bdae4c04132cf6b110deab2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 00:22:05 -0400 Subject: [PATCH 130/199] Major updates to CombinedImuFactor to make it Testable as well as serializable --- gtsam/navigation/CombinedImuFactor.cpp | 34 ++++++++ gtsam/navigation/CombinedImuFactor.h | 109 +++++++++++++++++++------ 2 files changed, 116 insertions(+), 27 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 149067269..7a8c73013 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -17,9 +17,11 @@ * @author Vadim Indelman * @author David Jensen * @author Frank Dellaert + * @author Varun Agrawal **/ #include +#include /* External or standard includes */ #include @@ -28,6 +30,31 @@ namespace gtsam { using namespace std; +//------------------------------------------------------------------------------ +// Inner class PreintegrationCombinedParams +//------------------------------------------------------------------------------ +void PreintegrationCombinedParams::print(const string& s) const { + PreintegrationParams::print(s); + cout << "biasAccCovariance:\n[\n" << biasAccCovariance << "\n]" + << endl; + cout << "biasOmegaCovariance:\n[\n" << biasOmegaCovariance << "\n]" + << endl; + cout << "biasAccOmegaInt:\n[\n" << biasAccOmegaInt << "\n]" + << endl; +} + +//------------------------------------------------------------------------------ +bool PreintegrationCombinedParams::equals(const PreintegrationParams& other, + double tol) const { + auto e = dynamic_cast(&other); + return e != nullptr && PreintegrationParams::equals(other, tol) && + equal_with_abs_tol(biasAccCovariance, e->biasAccCovariance, + tol) && + equal_with_abs_tol(biasOmegaCovariance, e->biasOmegaCovariance, + tol) && + equal_with_abs_tol(biasAccOmegaInt, e->biasAccOmegaInt, tol); +} + //------------------------------------------------------------------------------ // Inner class PreintegratedCombinedMeasurements //------------------------------------------------------------------------------ @@ -242,6 +269,13 @@ Vector CombinedImuFactor::evaluateError(const Pose3& pose_i, return r; } +//------------------------------------------------------------------------------ +std::ostream& operator<<(std::ostream& os, const CombinedImuFactor& f) { + f._PIM_.print("combined preintegrated measurements:\n"); + os << " noise model sigmas: " << f.noiseModel_->sigmas().transpose(); + return os; +} + //------------------------------------------------------------------------------ #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 CombinedImuFactor::CombinedImuFactor( diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 6b3bf979a..7a3a801f1 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -17,6 +17,7 @@ * @author Vadim Indelman * @author David Jensen * @author Frank Dellaert + * @author Varun Agrawal **/ #pragma once @@ -26,6 +27,7 @@ #include #include #include +#include namespace gtsam { @@ -61,10 +63,19 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk Matrix6 biasAccOmegaInt; ///< covariance of bias used for pre-integration + /// Default constructor makes unitialized params struct. + /// Used for serialization. + PreintegrationCombinedParams() + : PreintegrationParams(), + biasAccCovariance(I_3x3), + biasOmegaCovariance(I_3x3), + biasAccOmegaInt(I_6x6) {} + /// See two named constructors below for good values of n_gravity in body frame -PreintegrationCombinedParams(const Vector3& n_gravity) : - PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), biasOmegaCovariance( - I_3x3), biasAccOmegaInt(I_6x6) { + PreintegrationCombinedParams(const Vector3& n_gravity) : + PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), + biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) { + } // Default Params for a Z-down navigation frame, such as NED: gravity points along positive Z-axis @@ -77,6 +88,9 @@ PreintegrationCombinedParams(const Vector3& n_gravity) : return boost::shared_ptr(new PreintegrationCombinedParams(Vector3(0, 0, -g))); } + void print(const std::string& s="") const; + bool equals(const PreintegrationParams& other, double tol) const; + void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } void setBiasAccOmegaInt(const Matrix6& cov) { biasAccOmegaInt=cov; } @@ -86,24 +100,25 @@ PreintegrationCombinedParams(const Vector3& n_gravity) : const Matrix6& getBiasAccOmegaInt() const { return biasAccOmegaInt; } private: - /// Default constructor makes unitialized params struct - PreintegrationCombinedParams() {} /** Serialization function */ friend class boost::serialization::access; template - void serialize(ARCHIVE& ar, const unsigned int /*version*/) { - ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotation::Params); - ar& BOOST_SERIALIZATION_NVP(biasAccCovariance); - ar& BOOST_SERIALIZATION_NVP(biasOmegaCovariance); - ar& BOOST_SERIALIZATION_NVP(biasAccOmegaInt); + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + namespace bs = ::boost::serialization; + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams); + ar & bs::make_nvp("biasAccCovariance", + bs::make_array(biasAccCovariance.data(), biasAccCovariance.size())); + ar & bs::make_nvp("biasOmegaCovariance", + bs::make_array(biasOmegaCovariance.data(), biasOmegaCovariance.size())); + ar & bs::make_nvp("biasAccOmegaInt", bs::make_array(biasAccOmegaInt.data(), + biasAccOmegaInt.size())); } public: GTSAM_MAKE_ALIGNED_OPERATOR_NEW }; - /** * PreintegratedCombinedMeasurements integrates the IMU measurements * (rotation rates and accelerations) and the corresponding covariance matrix. @@ -128,7 +143,6 @@ public: */ Eigen::Matrix preintMeasCov_; - friend class CombinedImuFactor; public: @@ -136,11 +150,14 @@ public: /// @{ /// Default constructor only for serialization and Cython wrapper - PreintegratedCombinedMeasurements() {} + PreintegratedCombinedMeasurements() { + preintMeasCov_.setZero(); + } /** * Default constructor, initializes the class with no measurements - * @param bias Current estimate of acceleration and rotation rate biases + * @param p Parameters, typically fixed in a single application + * @param biasHat Current estimate of acceleration and rotation rate biases */ PreintegratedCombinedMeasurements( const boost::shared_ptr& p, @@ -149,6 +166,19 @@ public: preintMeasCov_.setZero(); } + /** + * Construct preintegrated directly from members: base class and preintMeasCov + * @param base PreintegrationType instance + * @param preintMeasCov Covariance matrix used in noise model. + */ + PreintegratedCombinedMeasurements(const PreintegrationType& base, const Eigen::Matrix& preintMeasCov) + : PreintegrationType(base), + preintMeasCov_(preintMeasCov) { + } + + /// Virtual destructor + virtual ~PreintegratedCombinedMeasurements() {} + /// @} /// @name Basic utilities @@ -158,20 +188,25 @@ public: void resetIntegration() override; /// const reference to params, shadows definition in base class - Params& p() const { return *boost::static_pointer_cast(this->p_);} + Params& p() const { return *boost::static_pointer_cast(this->p_); } /// @} /// @name Access instance variables /// @{ + /// Return pre-integrated measurement covariance Matrix preintMeasCov() const { return preintMeasCov_; } /// @} /// @name Testable /// @{ + /// print void print(const std::string& s = "Preintegrated Measurements:") const override; - bool equals(const PreintegratedCombinedMeasurements& expected, double tol = 1e-9) const; + /// equals + bool equals(const PreintegratedCombinedMeasurements& expected, + double tol = 1e-9) const; /// @} + /// @name Main functionality /// @{ @@ -205,8 +240,10 @@ public: friend class boost::serialization::access; template void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + namespace bs = ::boost::serialization; ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); - ar& BOOST_SERIALIZATION_NVP(preintMeasCov_); + ar& bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), + preintMeasCov_.size())); } public: @@ -244,9 +281,6 @@ private: PreintegratedCombinedMeasurements _PIM_; - /** Default constructor - only use for serialization */ - CombinedImuFactor() {} - public: /** Shorthand for a smart pointer to a factor */ @@ -256,6 +290,9 @@ public: typedef boost::shared_ptr shared_ptr; #endif + /** Default constructor - only use for serialization */ + CombinedImuFactor() {} + /** * Constructor * @param pose_i Previous pose key @@ -277,12 +314,17 @@ public: /** implement functions needed for Testable */ + /// @name Testable + /// @{ + GTSAM_EXPORT friend std::ostream& operator<<(std::ostream& os, + const CombinedImuFactor&); /// print virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; /// equals virtual bool equals(const NonlinearFactor& expected, double tol = 1e-9) const; + /// @} /** Access the preintegrated measurements. */ @@ -321,14 +363,12 @@ public: #endif private: - /** Serialization function */ friend class boost::serialization::access; - template - void serialize(ARCHIVE & ar, const unsigned int /*version*/) { - ar & boost::serialization::make_nvp("NoiseModelFactor6", - boost::serialization::base_object(*this)); - ar & BOOST_SERIALIZATION_NVP(_PIM_); + template + void serialize(ARCHIVE& ar, const unsigned int /*version*/) { + ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(NoiseModelFactor6); + ar& BOOST_SERIALIZATION_NVP(_PIM_); } public: @@ -336,4 +376,19 @@ public: }; // class CombinedImuFactor -} /// namespace gtsam +template <> +struct traits + : public Testable {}; + +template <> +struct traits + : public Testable {}; + +template <> +struct traits : public Testable {}; + +} // namespace gtsam + +/// Add Boost serialization export for derived class +BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); +// BOOST_CLASS_EXPORT_GUID(gtsam::CombinedImuFactor, "gtsam_CombinedImuFactor"); From d519d24b67bed4495f23098ec458102fd2e575e7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 00:22:13 -0400 Subject: [PATCH 131/199] Fix typo --- gtsam/navigation/ImuFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index b5cff8147..408cefdf0 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -59,7 +59,7 @@ typedef ManifoldPreintegration PreintegrationType; */ /** - * PreintegratedIMUMeasurements accumulates (integrates) the IMU measurements + * PreintegratedImuMeasurements accumulates (integrates) the IMU measurements * (rotation rates and accelerations) and the corresponding covariance matrix. * The measurements are then used to build the Preintegrated IMU factor. * Integration is done incrementally (ideally, one integrates the measurement From 23e2b29dbe428ccda610cff133142fbc04cd533f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 00:22:42 -0400 Subject: [PATCH 132/199] Added and updated serialization tests to include all IMU factors --- .../tests/testImuFactorSerialization.cpp | 60 +++++++++++++++---- 1 file changed, 49 insertions(+), 11 deletions(-) diff --git a/gtsam/navigation/tests/testImuFactorSerialization.cpp b/gtsam/navigation/tests/testImuFactorSerialization.cpp index 59d0ac199..ed72e18e9 100644 --- a/gtsam/navigation/tests/testImuFactorSerialization.cpp +++ b/gtsam/navigation/tests/testImuFactorSerialization.cpp @@ -16,15 +16,19 @@ * @author Frank Dellaert * @author Richard Roberts * @author Stephen Williams + * @author Varun Agrawal */ -#include -#include #include +#include +#include +#include + #include using namespace std; using namespace gtsam; +using namespace gtsam::serializationTestHelpers; BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained"); @@ -38,23 +42,23 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); -TEST(ImuFactor, serialization) { - using namespace gtsam::serializationTestHelpers; - +template +P getPreintegratedMeasurements() { // Create default parameters with Z-down and above noise paramaters - auto p = PreintegrationParams::MakeSharedD(9.81); - p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3(0,0,0)); + auto p = P::Params::MakeSharedD(9.81); + p->body_P_sensor = Pose3(Rot3::Ypr(0, 0, M_PI), Point3(0, 0, 0)); p->accelerometerCovariance = 1e-7 * I_3x3; p->gyroscopeCovariance = 1e-8 * I_3x3; p->integrationCovariance = 1e-9 * I_3x3; const double deltaT = 0.005; - const imuBias::ConstantBias priorBias( - Vector3(0, 0, 0), Vector3(0, 0.01, 0)); // Biases (acc, rot) - PreintegratedImuMeasurements pim(p, priorBias); + // Biases (acc, rot) + const imuBias::ConstantBias priorBias(Vector3(0, 0, 0), Vector3(0, 0.01, 0)); - // measurements are needed for non-inf noise model, otherwise will throw err + P pim(p, priorBias); + + // measurements are needed for non-inf noise model, otherwise will throw error // when deserialize const Vector3 measuredOmega(0, 0.01, 0); const Vector3 measuredAcc(0, 0, -9.81); @@ -62,6 +66,16 @@ TEST(ImuFactor, serialization) { for (int j = 0; j < 200; ++j) pim.integrateMeasurement(measuredAcc, measuredOmega, deltaT); + return pim; +} + +TEST(ImuFactor, serialization) { + auto pim = getPreintegratedMeasurements(); + + EXPECT(equalsObj(pim)); + EXPECT(equalsXML(pim)); + EXPECT(equalsBinary(pim)); + ImuFactor factor(1, 2, 3, 4, 5, pim); EXPECT(equalsObj(factor)); @@ -69,6 +83,30 @@ TEST(ImuFactor, serialization) { EXPECT(equalsBinary(factor)); } +TEST(ImuFactor2, serialization) { + auto pim = getPreintegratedMeasurements(); + + ImuFactor2 factor(1, 2, 3, pim); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + +TEST(CombinedImuFactor, Serialization) { + auto pim = getPreintegratedMeasurements(); + + EXPECT(equalsObj(pim)); + EXPECT(equalsXML(pim)); + EXPECT(equalsBinary(pim)); + + const CombinedImuFactor factor(1, 2, 3, 4, 5, 6, pim); + + EXPECT(equalsObj(factor)); + EXPECT(equalsXML(factor)); + EXPECT(equalsBinary(factor)); +} + /* ************************************************************************* */ int main() { TestResult tr; From 0c199dd406fde5b27123b762b073a1e8ac98f20a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 00:46:21 -0400 Subject: [PATCH 133/199] revert variable change --- gtsam/slam/SmartFactorBase.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 3bedf599f..c9b510605 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -206,12 +206,12 @@ protected: boost::optional E = boost::none) const { Vector ue = cameras.reprojectionError(point, measured_, Fs, E); if (body_P_sensor_ && Fs) { - const Pose3 sensor_T_body = body_P_sensor_->inverse(); + const Pose3 sensor_P_body = body_P_sensor_->inverse(); for (size_t i = 0; i < Fs->size(); i++) { - const Pose3 world_T_body = cameras[i].pose() * sensor_T_body; + const Pose3 world_P_body = cameras[i].pose() * sensor_P_body; Matrix J(6, 6); // Call compose to compute Jacobian - world_T_body.compose(*body_P_sensor_, J); + world_P_body.compose(*body_P_sensor_, J); Fs->at(i) = Fs->at(i) * J; } } From 7dfc79971aa26a203aa9ef0bacb042a3955994b9 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 11:52:06 -0400 Subject: [PATCH 134/199] reduced tolerance for checking jacobian --- gtsam/slam/tests/testSmartFactorBase.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/tests/testSmartFactorBase.cpp b/gtsam/slam/tests/testSmartFactorBase.cpp index bb04ad56d..fd771f102 100644 --- a/gtsam/slam/tests/testSmartFactorBase.cpp +++ b/gtsam/slam/tests/testSmartFactorBase.cpp @@ -67,9 +67,9 @@ TEST(SmartFactorBase, PinholeWithSensor) { PinholeFactor::Cameras cameras; // Assume body at origin. - Pose3 world_T_body = Pose3(); + Pose3 world_P_body = Pose3(); // Camera coordinates in world frame. - Pose3 wTc = world_T_body * body_P_sensor; + Pose3 wTc = world_P_body * body_P_sensor; cameras.push_back(PinholeCamera(wTc)); // Simple point to project slightly off image center @@ -88,7 +88,9 @@ TEST(SmartFactorBase, PinholeWithSensor) { expectedE << 0.1, 0, 0.01, 0, 0.1, 0; EXPECT(assert_equal(error, expectedError)); - EXPECT(assert_equal(expectedFs, Fs[0])); // We only have the jacobian for the 1 camera + // We only have the jacobian for the 1 camera + // Use of a lower tolerance value due to compiler precision mismatch. + EXPECT(assert_equal(expectedFs, Fs[0], 1e-3)); EXPECT(assert_equal(expectedE, E)); } From 4a0b031a2a07fa15dad643d091a6b3beb4f6bd2a Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Thu, 9 Jul 2020 14:26:18 -0400 Subject: [PATCH 135/199] add return value in gtsam_optimize --- cython/gtsam/utils/logging_optimizer.py | 1 + 1 file changed, 1 insertion(+) diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index 34f0fe5c9..3f0110945 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -52,3 +52,4 @@ def gtsam_optimize(optimizer: NonlinearOptimizer, gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), current_error, new_error)) or (optimizer.lambda_() > params.getlambdaUpperBound()) optimize(optimizer, check_convergence, hook) + return optimizer.values() From 2c544018bf9f6dbd78e55ef441182f43067edafd Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 16:27:21 -0400 Subject: [PATCH 136/199] Eliminated some copy/paste --- gtsam/slam/tests/testDataset.cpp | 150 ++++++++++++++----------------- 1 file changed, 67 insertions(+), 83 deletions(-) diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index 9a3c797b2..cd05b4f98 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -122,45 +122,6 @@ TEST( dataSet, Balbianello) EXPECT(assert_equal(expected,actual,1)); } -/* ************************************************************************* */ -TEST( dataSet, readG2o) -{ - const string g2oFile = findExampleDataFile("pose2example"); - NonlinearFactorGraph::shared_ptr actualGraph; - Values::shared_ptr actualValues; - boost::tie(actualGraph, actualValues) = readG2o(g2oFile); - - Values expectedValues; - expectedValues.insert(0, Pose2(0.000000, 0.000000, 0.000000)); - expectedValues.insert(1, Pose2(1.030390, 0.011350, -0.081596)); - expectedValues.insert(2, Pose2(2.036137, -0.129733, -0.301887)); - expectedValues.insert(3, Pose2(3.015097, -0.442395, -0.345514)); - expectedValues.insert(4, Pose2(3.343949, 0.506678, 1.214715)); - expectedValues.insert(5, Pose2(3.684491, 1.464049, 1.183785)); - expectedValues.insert(6, Pose2(4.064626, 2.414783, 1.176333)); - expectedValues.insert(7, Pose2(4.429778, 3.300180, 1.259169)); - expectedValues.insert(8, Pose2(4.128877, 2.321481, -1.825391)); - expectedValues.insert(9, Pose2(3.884653, 1.327509, -1.953016)); - expectedValues.insert(10, Pose2(3.531067, 0.388263, -2.148934)); - EXPECT(assert_equal(expectedValues,*actualValues,1e-5)); - - noiseModel::Diagonal::shared_ptr model = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699)); - NonlinearFactorGraph expectedGraph; - expectedGraph.emplace_shared >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model); - expectedGraph.emplace_shared >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model); - expectedGraph.emplace_shared >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model); - expectedGraph.emplace_shared >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model); - expectedGraph.emplace_shared >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model); - expectedGraph.emplace_shared >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model); - expectedGraph.emplace_shared >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model); - expectedGraph.emplace_shared >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model); - expectedGraph.emplace_shared >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model); - expectedGraph.emplace_shared >(9,10, Pose2(1.003350, 0.022250, -0.195918), model); - expectedGraph.emplace_shared >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model); - expectedGraph.emplace_shared >(3,10, Pose2(0.044020, 0.988477, -1.553511), model); - EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); -} - /* ************************************************************************* */ TEST(dataSet, readG2o3D) { const string g2oFile = findExampleDataFile("pose3example"); @@ -273,59 +234,82 @@ TEST( dataSet, readG2o3DNonDiagonalNoise) } /* ************************************************************************* */ -TEST( dataSet, readG2oHuber) -{ - const string g2oFile = findExampleDataFile("pose2example"); - NonlinearFactorGraph::shared_ptr actualGraph; - Values::shared_ptr actualValues; - bool is3D = false; - boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D, KernelFunctionTypeHUBER); - - noiseModel::Diagonal::shared_ptr baseModel = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699)); - SharedNoiseModel model = noiseModel::Robust::Create(noiseModel::mEstimator::Huber::Create(1.345), baseModel); - - NonlinearFactorGraph expectedGraph; - expectedGraph.emplace_shared >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model); - expectedGraph.emplace_shared >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model); - expectedGraph.emplace_shared >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model); - expectedGraph.emplace_shared >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model); - expectedGraph.emplace_shared >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model); - expectedGraph.emplace_shared >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model); - expectedGraph.emplace_shared >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model); - expectedGraph.emplace_shared >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model); - expectedGraph.emplace_shared >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model); - expectedGraph.emplace_shared >(9,10, Pose2(1.003350, 0.022250, -0.195918), model); - expectedGraph.emplace_shared >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model); - expectedGraph.emplace_shared >(3,10, Pose2(0.044020, 0.988477, -1.553511), model); - EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); +static NonlinearFactorGraph expectedGraph(const SharedNoiseModel& model) { + NonlinearFactorGraph g; + using Factor = BetweenFactor; + g.emplace_shared(0, 1, Pose2(1.030390, 0.011350, -0.081596), model); + g.emplace_shared(1, 2, Pose2(1.013900, -0.058639, -0.220291), model); + g.emplace_shared(2, 3, Pose2(1.027650, -0.007456, -0.043627), model); + g.emplace_shared(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model); + g.emplace_shared(4, 5, Pose2(1.016030, 0.014565, -0.030930), model); + g.emplace_shared(5, 6, Pose2(1.023890, 0.006808, -0.007452), model); + g.emplace_shared(6, 7, Pose2(0.957734, 0.003159, 0.082836), model); + g.emplace_shared(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model); + g.emplace_shared(8, 9, Pose2(1.023440, 0.013984, -0.127624), model); + g.emplace_shared(9, 10, Pose2(1.003350, 0.022250, -0.195918), model); + g.emplace_shared(5, 9, Pose2(0.033943, 0.032439, 3.073637), model); + g.emplace_shared(3, 10, Pose2(0.044020, 0.988477, -1.553511), model); + return g; } /* ************************************************************************* */ -TEST( dataSet, readG2oTukey) -{ +TEST(dataSet, readG2o) { + const string g2oFile = findExampleDataFile("pose2example"); + NonlinearFactorGraph::shared_ptr actualGraph; + Values::shared_ptr actualValues; + boost::tie(actualGraph, actualValues) = readG2o(g2oFile); + + auto model = noiseModel::Diagonal::Precisions( + Vector3(44.721360, 44.721360, 30.901699)); + EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5)); + + Values expectedValues; + expectedValues.insert(0, Pose2(0.000000, 0.000000, 0.000000)); + expectedValues.insert(1, Pose2(1.030390, 0.011350, -0.081596)); + expectedValues.insert(2, Pose2(2.036137, -0.129733, -0.301887)); + expectedValues.insert(3, Pose2(3.015097, -0.442395, -0.345514)); + expectedValues.insert(4, Pose2(3.343949, 0.506678, 1.214715)); + expectedValues.insert(5, Pose2(3.684491, 1.464049, 1.183785)); + expectedValues.insert(6, Pose2(4.064626, 2.414783, 1.176333)); + expectedValues.insert(7, Pose2(4.429778, 3.300180, 1.259169)); + expectedValues.insert(8, Pose2(4.128877, 2.321481, -1.825391)); + expectedValues.insert(9, Pose2(3.884653, 1.327509, -1.953016)); + expectedValues.insert(10, Pose2(3.531067, 0.388263, -2.148934)); + EXPECT(assert_equal(expectedValues, *actualValues, 1e-5)); +} + +/* ************************************************************************* */ +TEST(dataSet, readG2oHuber) { const string g2oFile = findExampleDataFile("pose2example"); NonlinearFactorGraph::shared_ptr actualGraph; Values::shared_ptr actualValues; bool is3D = false; - boost::tie(actualGraph, actualValues) = readG2o(g2oFile, is3D, KernelFunctionTypeTUKEY); + boost::tie(actualGraph, actualValues) = + readG2o(g2oFile, is3D, KernelFunctionTypeHUBER); - noiseModel::Diagonal::shared_ptr baseModel = noiseModel::Diagonal::Precisions(Vector3(44.721360, 44.721360, 30.901699)); - SharedNoiseModel model = noiseModel::Robust::Create(noiseModel::mEstimator::Tukey::Create(4.6851), baseModel); + auto baseModel = noiseModel::Diagonal::Precisions( + Vector3(44.721360, 44.721360, 30.901699)); + auto model = noiseModel::Robust::Create( + noiseModel::mEstimator::Huber::Create(1.345), baseModel); - NonlinearFactorGraph expectedGraph; - expectedGraph.emplace_shared >(0, 1, Pose2(1.030390, 0.011350, -0.081596), model); - expectedGraph.emplace_shared >(1, 2, Pose2(1.013900, -0.058639, -0.220291), model); - expectedGraph.emplace_shared >(2, 3, Pose2(1.027650, -0.007456, -0.043627), model); - expectedGraph.emplace_shared >(3, 4, Pose2(-0.012016, 1.004360, 1.560229), model); - expectedGraph.emplace_shared >(4, 5, Pose2(1.016030, 0.014565, -0.030930), model); - expectedGraph.emplace_shared >(5, 6, Pose2(1.023890, 0.006808, -0.007452), model); - expectedGraph.emplace_shared >(6, 7, Pose2(0.957734, 0.003159, 0.082836), model); - expectedGraph.emplace_shared >(7, 8, Pose2(-1.023820, -0.013668, -3.084560), model); - expectedGraph.emplace_shared >(8, 9, Pose2(1.023440, 0.013984, -0.127624), model); - expectedGraph.emplace_shared >(9,10, Pose2(1.003350, 0.022250, -0.195918), model); - expectedGraph.emplace_shared >(5, 9, Pose2(0.033943, 0.032439, 3.073637), model); - expectedGraph.emplace_shared >(3,10, Pose2(0.044020, 0.988477, -1.553511), model); - EXPECT(assert_equal(expectedGraph,*actualGraph,1e-5)); + EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5)); +} + +/* ************************************************************************* */ +TEST(dataSet, readG2oTukey) { + const string g2oFile = findExampleDataFile("pose2example"); + NonlinearFactorGraph::shared_ptr actualGraph; + Values::shared_ptr actualValues; + bool is3D = false; + boost::tie(actualGraph, actualValues) = + readG2o(g2oFile, is3D, KernelFunctionTypeTUKEY); + + auto baseModel = noiseModel::Diagonal::Precisions( + Vector3(44.721360, 44.721360, 30.901699)); + auto model = noiseModel::Robust::Create( + noiseModel::mEstimator::Tukey::Create(4.6851), baseModel); + + EXPECT(assert_equal(expectedGraph(model), *actualGraph, 1e-5)); } /* ************************************************************************* */ From dc65a0a1d9e5bdff16c814bb22b2042c2456982a Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 16:27:32 -0400 Subject: [PATCH 137/199] Added g2o test files --- examples/Data/Klaus3.g2o | 6 ++++++ examples/Data/toyExample.g2o | 11 +++++++++++ 2 files changed, 17 insertions(+) create mode 100644 examples/Data/Klaus3.g2o create mode 100755 examples/Data/toyExample.g2o diff --git a/examples/Data/Klaus3.g2o b/examples/Data/Klaus3.g2o new file mode 100644 index 000000000..4c7233fa7 --- /dev/null +++ b/examples/Data/Klaus3.g2o @@ -0,0 +1,6 @@ +VERTEX_SE3:QUAT 0 -3.865747774038187 0.06639337702667497 -0.16064874691945374 0.024595211709139555 0.49179523413089893 -0.06279232989379242 0.8680954132776109 +VERTEX_SE3:QUAT 1 -3.614793159814815 0.04774490041587656 -0.2837650367985949 0.00991721787943912 0.4854918961891193 -0.042343290945895576 0.8731588132957809 +VERTEX_SE3:QUAT 2 -3.255096913553434 0.013296754286114112 -0.5339792269680574 -0.027851108010665374 0.585478168397957 -0.05088341463532465 0.8086102325762403 +EDGE_SE3:QUAT 0 1 0.2509546142233723 -0.01864847661079841 -0.12311628987914114 -0.022048798853273946 -0.01796327847857683 0.010210006313668573 0.9995433591728293 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 +EDGE_SE3:QUAT 0 2 0.6106508604847534 -0.05309662274056086 -0.3733304800486037 -0.054972994022992064 0.10432547598981769 -0.02221474884651081 0.9927742290779572 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 +EDGE_SE3:QUAT 1 2 0.3596962462613811 -0.03444814612976245 -0.25021419016946256 -0.03174661848656213 0.11646825423134777 -0.02951742735854383 0.9922479626852876 100.0 0.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 0.0 100.0 0.0 0.0 0.0 25.0 0.0 0.0 25.0 0.0 25.0 diff --git a/examples/Data/toyExample.g2o b/examples/Data/toyExample.g2o new file mode 100755 index 000000000..5ff1ba74a --- /dev/null +++ b/examples/Data/toyExample.g2o @@ -0,0 +1,11 @@ +VERTEX_SE3:QUAT 0 0 0 0 0 0 0 1 +VERTEX_SE3:QUAT 1 0 0 0 0 0 0 1 +VERTEX_SE3:QUAT 2 0 0 0 0.00499994 0.00499994 0.00499994 0.999963 +VERTEX_SE3:QUAT 3 0 0 0 -0.00499994 -0.00499994 -0.00499994 0.999963 +VERTEX_SE3:QUAT 4 0 0 0 0.00499994 0.00499994 0.00499994 0.999963 +EDGE_SE3:QUAT 1 2 1 2 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 2 3 -3.26795e-07 1 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 3 4 1 1 0 0 0 0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 3 1 6.9282e-07 2 0 0 0 1 1.73205e-07 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 1 4 -1 1 0 0 0 -0.707107 0.707107 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 +EDGE_SE3:QUAT 0 1 0 0 0 0 0 0 1 100 0 0 0 0 0 100 0 0 0 0 100 0 0 0 100 0 0 100 0 100 From 5ab16c8b5167c45ea1706371cd3e2eb37fc7161a Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 17:15:28 -0400 Subject: [PATCH 138/199] Added tests on determinants of read rotations --- gtsam/slam/tests/testDataset.cpp | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/gtsam/slam/tests/testDataset.cpp b/gtsam/slam/tests/testDataset.cpp index cd05b4f98..8088ab18a 100644 --- a/gtsam/slam/tests/testDataset.cpp +++ b/gtsam/slam/tests/testDataset.cpp @@ -233,6 +233,27 @@ TEST( dataSet, readG2o3DNonDiagonalNoise) EXPECT(assert_equal(expectedGraph,*actualGraph,1e-2)); } +/* ************************************************************************* */ +TEST(dataSet, readG2oCheckDeterminants) { + const string g2oFile = findExampleDataFile("toyExample.g2o"); + + // Check determinants in factors + auto factors = parse3DFactors(g2oFile); + EXPECT_LONGS_EQUAL(6, factors.size()); + for (const auto& factor : factors) { + const Rot3 R = factor->measured().rotation(); + EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9); + } + + // Check determinants in initial values + const map poses = parse3DPoses(g2oFile); + EXPECT_LONGS_EQUAL(5, poses.size()); + for (const auto& key_value : poses) { + const Rot3 R = key_value.second.rotation(); + EXPECT_DOUBLES_EQUAL(1.0, R.matrix().determinant(), 1e-9); + } +} + /* ************************************************************************* */ static NonlinearFactorGraph expectedGraph(const SharedNoiseModel& model) { NonlinearFactorGraph g; @@ -479,7 +500,7 @@ TEST( dataSet, writeBALfromValues_Dubrovnik){ SfmData readData; readBAL(filenameToRead, readData); - Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.3,0.1,0.3)); + Pose3 poseChange = Pose3(Rot3::Ypr(-M_PI/10, 0., -M_PI/10), Point3(0.3,0.1,0.3)); Values value; for(size_t i=0; i < readData.number_cameras(); i++){ // for each camera From 4960f755950de0137c5b13aec53c510e8d7f89ed Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 17:16:11 -0400 Subject: [PATCH 139/199] Normalized quaternions before converting to Rot3 to account for limited precision in text files. --- gtsam/slam/dataset.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 66e8fc4c0..1bb03dfe4 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -511,6 +511,11 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, stream.close(); } +/* ************************************************************************* */ +static Rot3 NormalizedRot3(double w, double x, double y, double z) { + const double norm = sqrt(w * w + x * x + y * y + z * z), f = 1.0 / norm; + return Rot3::Quaternion(f * w, f * x, f * y, f * z); +} /* ************************************************************************* */ std::map parse3DPoses(const string& filename) { ifstream is(filename.c_str()); @@ -535,14 +540,15 @@ std::map parse3DPoses(const string& filename) { Key id; double x, y, z, qx, qy, qz, qw; ls >> id >> x >> y >> z >> qx >> qy >> qz >> qw; - poses.emplace(id, Pose3(Rot3::Quaternion(qw, qx, qy, qz), {x, y, z})); + poses.emplace(id, Pose3(NormalizedRot3(qw, qx, qy, qz), {x, y, z})); } } return poses; } /* ************************************************************************* */ -BetweenFactorPose3s parse3DFactors(const string& filename, +BetweenFactorPose3s parse3DFactors( + const string& filename, const noiseModel::Diagonal::shared_ptr& corruptingNoise) { ifstream is(filename.c_str()); if (!is) throw invalid_argument("parse3DFactors: can not find file " + filename); @@ -592,7 +598,7 @@ BetweenFactorPose3s parse3DFactors(const string& filename, mgtsam.block<3, 3>(3, 0) = m.block<3, 3>(3, 0); // off diagonal SharedNoiseModel model = noiseModel::Gaussian::Information(mgtsam); - auto R12 = Rot3::Quaternion(qw, qx, qy, qz); + auto R12 = NormalizedRot3(qw, qx, qy, qz); if (sampler) { R12 = R12.retract(sampler->sample()); } From a484c910ab11ac5153dfa605baf781393ebd15ef Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 17:27:06 -0400 Subject: [PATCH 140/199] Avoided extra conversions to quaternions --- gtsam/slam/dataset.cpp | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index 1bb03dfe4..669935994 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -442,11 +442,11 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, auto p = dynamic_cast*>(&key_value.value); if (!p) continue; const Pose3& pose = p->value(); - Point3 t = pose.translation(); - Rot3 R = pose.rotation(); - stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " << t.y() << " " << t.z() - << " " << R.toQuaternion().x() << " " << R.toQuaternion().y() << " " << R.toQuaternion().z() - << " " << R.toQuaternion().w() << endl; + const Point3 t = pose.translation(); + const auto q = pose.rotation().toQuaternion(); + stream << "VERTEX_SE3:QUAT " << key_value.key << " " << t.x() << " " + << t.y() << " " << t.z() << " " << q.x() << " " << q.y() << " " + << q.z() << " " << q.w() << endl; } // save edges (2D or 3D) @@ -486,13 +486,12 @@ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, throw invalid_argument("writeG2o: invalid noise model!"); } Matrix Info = gaussianModel->R().transpose() * gaussianModel->R(); - Pose3 pose3D = factor3D->measured(); - Point3 p = pose3D.translation(); - Rot3 R = pose3D.rotation(); - - stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2() << " " - << p.x() << " " << p.y() << " " << p.z() << " " << R.toQuaternion().x() - << " " << R.toQuaternion().y() << " " << R.toQuaternion().z() << " " << R.toQuaternion().w(); + const Pose3 pose3D = factor3D->measured(); + const Point3 p = pose3D.translation(); + const auto q = pose3D.rotation().toQuaternion(); + stream << "EDGE_SE3:QUAT " << factor3D->key1() << " " << factor3D->key2() + << " " << p.x() << " " << p.y() << " " << p.z() << " " << q.x() + << " " << q.y() << " " << q.z() << " " << q.w(); Matrix InfoG2o = I_6x6; InfoG2o.block(0,0,3,3) = Info.block(3,3,3,3); // cov translation From f23587fafd9ceb388eeef6e4cec0c685dcf4be2d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 20:02:09 -0400 Subject: [PATCH 141/199] Add indentation --- gtsam/geometry/PinholePose.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 60088577c..79dbb9ce9 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -107,9 +107,9 @@ public: // If needed, apply chain rule if (Dpose) - *Dpose = Dpi_pn * *Dpose; + *Dpose = Dpi_pn * *Dpose; if (Dpoint) - *Dpoint = Dpi_pn * *Dpoint; + *Dpoint = Dpi_pn * *Dpoint; return pi; } From 60c88f67e9b5271d867efd16322080e6e02236ec Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 20:02:30 -0400 Subject: [PATCH 142/199] Handle extrinsics and intrinsics for jacobian --- gtsam/slam/SmartFactorBase.h | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index c9b510605..912de0bc1 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -207,11 +207,17 @@ protected: Vector ue = cameras.reprojectionError(point, measured_, Fs, E); if (body_P_sensor_ && Fs) { const Pose3 sensor_P_body = body_P_sensor_->inverse(); + size_t camera_dim = size_t(traits::dimension); + size_t pose_dim = size_t(traits::dimension); + for (size_t i = 0; i < Fs->size(); i++) { const Pose3 world_P_body = cameras[i].pose() * sensor_P_body; - Matrix J(6, 6); - // Call compose to compute Jacobian - world_P_body.compose(*body_P_sensor_, J); + Matrix J = Matrix::Zero(camera_dim, camera_dim); + // Call compose to compute Jacobian for camera extrinsics + Matrix H(pose_dim, pose_dim); + world_P_body.compose(*body_P_sensor_, H); + // Assign extrinsics + J.block(0, 0, pose_dim, pose_dim) = H; Fs->at(i) = Fs->at(i) * J; } } From 3dcff34b468988b97d47aefe3a0c0b26d78d82f3 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Thu, 9 Jul 2020 20:46:12 -0400 Subject: [PATCH 143/199] Formatted and fixed discrete examples --- examples/CMakeLists.txt | 3 - examples/DiscreteBayesNet_FG.cpp | 119 ++++++++++++++++--------------- examples/UGM_chain.cpp | 74 ++++++++----------- examples/UGM_small.cpp | 19 ++--- 4 files changed, 98 insertions(+), 117 deletions(-) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 7251c2b6f..476f4ae21 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,7 +1,4 @@ set (excluded_examples - DiscreteBayesNet_FG.cpp - UGM_chain.cpp - UGM_small.cpp elaboratePoint2KalmanFilter.cpp ) diff --git a/examples/DiscreteBayesNet_FG.cpp b/examples/DiscreteBayesNet_FG.cpp index 6eb08c12e..9802b5984 100644 --- a/examples/DiscreteBayesNet_FG.cpp +++ b/examples/DiscreteBayesNet_FG.cpp @@ -10,110 +10,111 @@ * -------------------------------------------------------------------------- */ /** - * @file DiscreteBayesNet_FG.cpp + * @file DiscreteBayesNet_graph.cpp * @brief Discrete Bayes Net example using Factor Graphs * @author Abhijit * @date Jun 4, 2012 * - * We use the famous Rain/Cloudy/Sprinkler Example of [Russell & Norvig, 2009, p529] - * You may be familiar with other graphical model packages like BNT (available - * at http://bnt.googlecode.com/svn/trunk/docs/usage.html) where this is used as an - * example. The following demo is same as that in the above link, except that - * everything is using GTSAM. + * We use the famous Rain/Cloudy/Sprinkler Example of [Russell & Norvig, 2009, + * p529] You may be familiar with other graphical model packages like BNT + * (available at http://bnt.googlecode.com/svn/trunk/docs/usage.html) where this + * is used as an example. The following demo is same as that in the above link, + * except that everything is using GTSAM. */ #include -#include +#include + #include using namespace std; using namespace gtsam; int main(int argc, char **argv) { + // Define keys and a print function + Key C(1), S(2), R(3), W(4); + auto print = [=](DiscreteFactor::sharedValues values) { + cout << boolalpha << "Cloudy = " << static_cast((*values)[C]) + << " Sprinkler = " << static_cast((*values)[S]) + << " Rain = " << boolalpha << static_cast((*values)[R]) + << " WetGrass = " << static_cast((*values)[W]) << endl; + }; // We assume binary state variables // we have 0 == "False" and 1 == "True" const size_t nrStates = 2; // define variables - DiscreteKey Cloudy(1, nrStates), Sprinkler(2, nrStates), Rain(3, nrStates), - WetGrass(4, nrStates); + DiscreteKey Cloudy(C, nrStates), Sprinkler(S, nrStates), Rain(R, nrStates), + WetGrass(W, nrStates); // create Factor Graph of the bayes net DiscreteFactorGraph graph; // add factors - graph.add(Cloudy, "0.5 0.5"); //P(Cloudy) - graph.add(Cloudy & Sprinkler, "0.5 0.5 0.9 0.1"); //P(Sprinkler | Cloudy) - graph.add(Cloudy & Rain, "0.8 0.2 0.2 0.8"); //P(Rain | Cloudy) + graph.add(Cloudy, "0.5 0.5"); // P(Cloudy) + graph.add(Cloudy & Sprinkler, "0.5 0.5 0.9 0.1"); // P(Sprinkler | Cloudy) + graph.add(Cloudy & Rain, "0.8 0.2 0.2 0.8"); // P(Rain | Cloudy) graph.add(Sprinkler & Rain & WetGrass, - "1 0 0.1 0.9 0.1 0.9 0.001 0.99"); //P(WetGrass | Sprinkler, Rain) + "1 0 0.1 0.9 0.1 0.9 0.001 0.99"); // P(WetGrass | Sprinkler, Rain) - // Alternatively we can also create a DiscreteBayesNet, add DiscreteConditional - // factors and create a FactorGraph from it. (See testDiscreteBayesNet.cpp) + // Alternatively we can also create a DiscreteBayesNet, add + // DiscreteConditional factors and create a FactorGraph from it. (See + // testDiscreteBayesNet.cpp) // Since this is a relatively small distribution, we can as well print // the whole distribution.. cout << "Distribution of Example: " << endl; cout << setw(11) << "Cloudy(C)" << setw(14) << "Sprinkler(S)" << setw(10) - << "Rain(R)" << setw(14) << "WetGrass(W)" << setw(15) << "P(C,S,R,W)" - << endl; + << "Rain(R)" << setw(14) << "WetGrass(W)" << setw(15) << "P(C,S,R,W)" + << endl; for (size_t a = 0; a < nrStates; a++) for (size_t m = 0; m < nrStates; m++) for (size_t h = 0; h < nrStates; h++) for (size_t c = 0; c < nrStates; c++) { DiscreteFactor::Values values; - values[Cloudy.first] = c; - values[Sprinkler.first] = h; - values[Rain.first] = m; - values[WetGrass.first] = a; + values[C] = c; + values[S] = h; + values[R] = m; + values[W] = a; double prodPot = graph(values); - cout << boolalpha << setw(8) << (bool) c << setw(14) - << (bool) h << setw(12) << (bool) m << setw(13) - << (bool) a << setw(16) << prodPot << endl; + cout << setw(8) << static_cast(c) << setw(14) + << static_cast(h) << setw(12) << static_cast(m) + << setw(13) << static_cast(a) << setw(16) << prodPot + << endl; } - // "Most Probable Explanation", i.e., configuration with largest value - DiscreteSequentialSolver solver(graph); - DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); - cout <<"\nMost Probable Explanation (MPE):" << endl; - cout << boolalpha << "Cloudy = " << (bool)(*optimalDecoding)[Cloudy.first] - << " Sprinkler = " << (bool)(*optimalDecoding)[Sprinkler.first] - << " Rain = " << boolalpha << (bool)(*optimalDecoding)[Rain.first] - << " WetGrass = " << (bool)(*optimalDecoding)[WetGrass.first]<< endl; + DiscreteFactor::sharedValues mpe = graph.eliminateSequential()->optimize(); + cout << "\nMost Probable Explanation (MPE):" << endl; + print(mpe); + // "Inference" We show an inference query like: probability that the Sprinkler + // was on; given that the grass is wet i.e. P( S | C=0) = ? - // "Inference" We show an inference query like: probability that the Sprinkler was on; - // given that the grass is wet i.e. P( S | W=1) =? - cout << "\nInference Query: Probability of Sprinkler being on given Grass is Wet" << endl; + // add evidence that it is not Cloudy + graph.add(Cloudy, "1 0"); - // Method 1: we can compute the joint marginal P(S,W) and from that we can compute - // P(S | W=1) = P(S,W=1)/P(W=1) We do this in following three steps.. + // solve again, now with evidence + DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential(); + DiscreteFactor::sharedValues mpe_with_evidence = chordal->optimize(); - //Step1: Compute P(S,W) - DiscreteFactorGraph jointFG; - jointFG = *solver.jointFactorGraph(DiscreteKeys(Sprinkler & WetGrass).indices()); - DecisionTreeFactor probSW = jointFG.product(); + cout << "\nMPE given C=0:" << endl; + print(mpe_with_evidence); - //Step2: Compute P(W) - DiscreteFactor::shared_ptr probW = solver.marginalFactor(WetGrass.first); - - //Step3: Computer P(S | W=1) = P(S,W=1)/P(W=1) - DiscreteFactor::Values values; - values[WetGrass.first] = 1; - - //print P(S=0|W=1) - values[Sprinkler.first] = 0; - cout << "P(S=0|W=1) = " << probSW(values)/(*probW)(values) << endl; - - //print P(S=1|W=1) - values[Sprinkler.first] = 1; - cout << "P(S=1|W=1) = " << probSW(values)/(*probW)(values) << endl; - - // TODO: Method 2 : One way is to modify the factor graph to - // incorporate the evidence node and compute the marginal - // TODO: graph.addEvidence(Cloudy,0); + // we can also calculate arbitrary marginals: + DiscreteMarginals marginals(graph); + cout << "\nP(S=1|C=0):" << marginals.marginalProbabilities(Sprinkler)[1] + << endl; + cout << "\nP(R=0|C=0):" << marginals.marginalProbabilities(Rain)[0] << endl; + cout << "\nP(W=1|C=0):" << marginals.marginalProbabilities(WetGrass)[1] + << endl; + // We can also sample from it + cout << "\n10 samples:" << endl; + for (size_t i = 0; i < 10; i++) { + DiscreteFactor::sharedValues sample = chordal->sample(); + print(sample); + } return 0; } diff --git a/examples/UGM_chain.cpp b/examples/UGM_chain.cpp index 4ce4e7af4..3a885a844 100644 --- a/examples/UGM_chain.cpp +++ b/examples/UGM_chain.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file small.cpp + * @file UGM_chain.cpp * @brief UGM (undirected graphical model) examples: chain * @author Frank Dellaert * @author Abhijit Kundu @@ -19,10 +19,9 @@ * for more explanation. This code demos the same example using GTSAM. */ -#include -#include -#include #include +#include +#include #include @@ -30,9 +29,8 @@ using namespace std; using namespace gtsam; int main(int argc, char** argv) { - - // Set Number of Nodes in the Graph - const int nrNodes = 60; + // Set Number of Nodes in the Graph + const int nrNodes = 60; // Each node takes 1 of 7 possible states denoted by 0-6 in following order: // ["VideoGames" "Industry" "GradSchool" "VideoGames(with PhD)" @@ -40,70 +38,55 @@ int main(int argc, char** argv) { const size_t nrStates = 7; // define variables - vector nodes; - for (int i = 0; i < nrNodes; i++){ - DiscreteKey dk(i, nrStates); - nodes.push_back(dk); - } + vector nodes; + for (int i = 0; i < nrNodes; i++) { + DiscreteKey dk(i, nrStates); + nodes.push_back(dk); + } // create graph DiscreteFactorGraph graph; // add node potentials graph.add(nodes[0], ".3 .6 .1 0 0 0 0"); - for (int i = 1; i < nrNodes; i++) - graph.add(nodes[i], "1 1 1 1 1 1 1"); + for (int i = 1; i < nrNodes; i++) graph.add(nodes[i], "1 1 1 1 1 1 1"); - const std::string edgePotential = ".08 .9 .01 0 0 0 .01 " - ".03 .95 .01 0 0 0 .01 " - ".06 .06 .75 .05 .05 .02 .01 " - "0 0 0 .3 .6 .09 .01 " - "0 0 0 .02 .95 .02 .01 " - "0 0 0 .01 .01 .97 .01 " - "0 0 0 0 0 0 1"; + const std::string edgePotential = + ".08 .9 .01 0 0 0 .01 " + ".03 .95 .01 0 0 0 .01 " + ".06 .06 .75 .05 .05 .02 .01 " + "0 0 0 .3 .6 .09 .01 " + "0 0 0 .02 .95 .02 .01 " + "0 0 0 .01 .01 .97 .01 " + "0 0 0 0 0 0 1"; // add edge potentials for (int i = 0; i < nrNodes - 1; i++) graph.add(nodes[i] & nodes[i + 1], edgePotential); cout << "Created Factor Graph with " << nrNodes << " variable nodes and " - << graph.size() << " factors (Unary+Edge)."; + << graph.size() << " factors (Unary+Edge)."; // "Decoding", i.e., configuration with largest value // We use sequential variable elimination - DiscreteSequentialSolver solver(graph); - DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); + DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential(); + DiscreteFactor::sharedValues optimalDecoding = chordal->optimize(); optimalDecoding->print("\nMost Probable Explanation (optimalDecoding)\n"); // "Inference" Computing marginals for each node - - - cout << "\nComputing Node Marginals ..(Sequential Elimination)" << endl; - gttic_(Sequential); - for (vector::iterator itr = nodes.begin(); itr != nodes.end(); - ++itr) { - //Compute the marginal - Vector margProbs = solver.marginalProbabilities(*itr); - - //Print the marginals - cout << "Node#" << setw(4) << itr->first << " : "; - print(margProbs); - } - gttoc_(Sequential); - // Here we'll make use of DiscreteMarginals class, which makes use of // bayes-tree based shortcut evaluation of marginals DiscreteMarginals marginals(graph); cout << "\nComputing Node Marginals ..(BayesTree based)" << endl; gttic_(Multifrontal); - for (vector::iterator itr = nodes.begin(); itr != nodes.end(); - ++itr) { - //Compute the marginal - Vector margProbs = marginals.marginalProbabilities(*itr); + for (vector::iterator it = nodes.begin(); it != nodes.end(); + ++it) { + // Compute the marginal + Vector margProbs = marginals.marginalProbabilities(*it); - //Print the marginals - cout << "Node#" << setw(4) << itr->first << " : "; + // Print the marginals + cout << "Node#" << setw(4) << it->first << " : "; print(margProbs); } gttoc_(Multifrontal); @@ -111,4 +94,3 @@ int main(int argc, char** argv) { tictoc_print_(); return 0; } - diff --git a/examples/UGM_small.cpp b/examples/UGM_small.cpp index f5338bc67..27a6205a3 100644 --- a/examples/UGM_small.cpp +++ b/examples/UGM_small.cpp @@ -10,15 +10,16 @@ * -------------------------------------------------------------------------- */ /** - * @file small.cpp + * @file UGM_small.cpp * @brief UGM (undirected graphical model) examples: small * @author Frank Dellaert * * See http://www.di.ens.fr/~mschmidt/Software/UGM/small.html */ +#include #include -#include +#include using namespace std; using namespace gtsam; @@ -61,24 +62,24 @@ int main(int argc, char** argv) { // "Decoding", i.e., configuration with largest value (MPE) // We use sequential variable elimination - DiscreteSequentialSolver solver(graph); - DiscreteFactor::sharedValues optimalDecoding = solver.optimize(); + DiscreteBayesNet::shared_ptr chordal = graph.eliminateSequential(); + DiscreteFactor::sharedValues optimalDecoding = chordal->optimize(); optimalDecoding->print("\noptimalDecoding"); // "Inference" Computing marginals cout << "\nComputing Node Marginals .." << endl; - Vector margProbs; + DiscreteMarginals marginals(graph); - margProbs = solver.marginalProbabilities(Cathy); + Vector margProbs = marginals.marginalProbabilities(Cathy); print(margProbs, "Cathy's Node Marginal:"); - margProbs = solver.marginalProbabilities(Heather); + margProbs = marginals.marginalProbabilities(Heather); print(margProbs, "Heather's Node Marginal"); - margProbs = solver.marginalProbabilities(Mark); + margProbs = marginals.marginalProbabilities(Mark); print(margProbs, "Mark's Node Marginal"); - margProbs = solver.marginalProbabilities(Allison); + margProbs = marginals.marginalProbabilities(Allison); print(margProbs, "Allison's Node Marginal"); return 0; From 904ecf4f1f341db840f1edfed0e9e42fedef25d2 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 23:11:20 -0400 Subject: [PATCH 144/199] Use built in Matrix serialization --- gtsam/navigation/CombinedImuFactor.h | 18 ++++++------------ gtsam/navigation/ImuFactor.h | 2 +- gtsam/navigation/ManifoldPreintegration.h | 10 +++++----- gtsam/navigation/PreintegratedRotation.h | 2 +- gtsam/navigation/PreintegrationParams.h | 4 ++-- gtsam/navigation/TangentPreintegration.h | 6 +++--- 6 files changed, 18 insertions(+), 24 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 7a3a801f1..f47ce8846 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -63,11 +63,10 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { Matrix3 biasOmegaCovariance; ///< continuous-time "Covariance" describing gyroscope bias random walk Matrix6 biasAccOmegaInt; ///< covariance of bias used for pre-integration - /// Default constructor makes unitialized params struct. + /// Default constructor makes uninitialized params struct. /// Used for serialization. PreintegrationCombinedParams() - : PreintegrationParams(), - biasAccCovariance(I_3x3), + : biasAccCovariance(I_3x3), biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) {} @@ -107,12 +106,9 @@ private: void serialize(ARCHIVE& ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationParams); - ar & bs::make_nvp("biasAccCovariance", - bs::make_array(biasAccCovariance.data(), biasAccCovariance.size())); - ar & bs::make_nvp("biasOmegaCovariance", - bs::make_array(biasOmegaCovariance.data(), biasOmegaCovariance.size())); - ar & bs::make_nvp("biasAccOmegaInt", bs::make_array(biasAccOmegaInt.data(), - biasAccOmegaInt.size())); + ar & BOOST_SERIALIZATION_NVP(biasAccCovariance); + ar & BOOST_SERIALIZATION_NVP(biasOmegaCovariance); + ar & BOOST_SERIALIZATION_NVP(biasAccOmegaInt); } public: @@ -242,8 +238,7 @@ public: void serialize(ARCHIVE& ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); - ar& bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), - preintMeasCov_.size())); + ar& BOOST_SERIALIZATION_NVP(preintMeasCov_); } public: @@ -391,4 +386,3 @@ struct traits : public Testable {}; /// Add Boost serialization export for derived class BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); -// BOOST_CLASS_EXPORT_GUID(gtsam::CombinedImuFactor, "gtsam_CombinedImuFactor"); diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 408cefdf0..7e080ffd5 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -164,7 +164,7 @@ private: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); - ar & bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), preintMeasCov_.size())); + ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); } }; diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 97ad04744..a290972e4 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -120,11 +120,11 @@ private: namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); ar & BOOST_SERIALIZATION_NVP(deltaXij_); - ar & bs::make_nvp("delRdelBiasOmega_", bs::make_array(delRdelBiasOmega_.data(), delRdelBiasOmega_.size())); - ar & bs::make_nvp("delPdelBiasAcc_", bs::make_array(delPdelBiasAcc_.data(), delPdelBiasAcc_.size())); - ar & bs::make_nvp("delPdelBiasOmega_", bs::make_array(delPdelBiasOmega_.data(), delPdelBiasOmega_.size())); - ar & bs::make_nvp("delVdelBiasAcc_", bs::make_array(delVdelBiasAcc_.data(), delVdelBiasAcc_.size())); - ar & bs::make_nvp("delVdelBiasOmega_", bs::make_array(delVdelBiasOmega_.data(), delVdelBiasOmega_.size())); + ar & BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(delPdelBiasAcc_); + ar & BOOST_SERIALIZATION_NVP(delPdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(delVdelBiasAcc_); + ar & BOOST_SERIALIZATION_NVP(delVdelBiasOmega_); } }; diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 12938a625..9346f749a 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -61,7 +61,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & bs::make_nvp("gyroscopeCovariance", bs::make_array(gyroscopeCovariance.data(), gyroscopeCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance); ar & BOOST_SERIALIZATION_NVP(omegaCoriolis); ar & BOOST_SERIALIZATION_NVP(body_P_sensor); } diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index de9950e7d..9ae66e678 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -76,8 +76,8 @@ protected: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegratedRotationParams); - ar & bs::make_nvp("accelerometerCovariance", bs::make_array(accelerometerCovariance.data(), accelerometerCovariance.size())); - ar & bs::make_nvp("integrationCovariance", bs::make_array(integrationCovariance.data(), integrationCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(accelerometerCovariance); + ar & BOOST_SERIALIZATION_NVP(integrationCovariance); ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); ar & BOOST_SERIALIZATION_NVP(n_gravity); } diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 99aa10b3f..1b51b4e1e 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -133,9 +133,9 @@ private: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationBase); - ar & bs::make_nvp("preintegrated_", bs::make_array(preintegrated_.data(), preintegrated_.size())); - ar & bs::make_nvp("preintegrated_H_biasAcc_", bs::make_array(preintegrated_H_biasAcc_.data(), preintegrated_H_biasAcc_.size())); - ar & bs::make_nvp("preintegrated_H_biasOmega_", bs::make_array(preintegrated_H_biasOmega_.data(), preintegrated_H_biasOmega_.size())); + ar & BOOST_SERIALIZATION_NVP(preintegrated_); + ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasAcc_); + ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasOmega_); } public: From 018e6ba68cda05707fc250f3eab80c930710196f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 23:12:35 -0400 Subject: [PATCH 145/199] Generic Eigen::Matrix serialization for boost --- gtsam/base/Matrix.h | 41 ++++++++++++++++++++++++++++++++++------- 1 file changed, 34 insertions(+), 7 deletions(-) diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index fa70e5b00..b1c6268a7 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -549,16 +549,32 @@ namespace boost { namespace serialization { // split version - sends sizes ahead - template - void save(Archive & ar, const gtsam::Matrix & m, unsigned int /*version*/) { + template + void save(Archive & ar, + const Eigen::Matrix & m, + const unsigned int /*version*/) { const size_t rows = m.rows(), cols = m.cols(); ar << BOOST_SERIALIZATION_NVP(rows); ar << BOOST_SERIALIZATION_NVP(cols); ar << make_nvp("data", make_array(m.data(), m.size())); } - template - void load(Archive & ar, gtsam::Matrix & m, unsigned int /*version*/) { + template + void load(Archive & ar, + Eigen::Matrix & m, + const unsigned int /*version*/) { size_t rows, cols; ar >> BOOST_SERIALIZATION_NVP(rows); ar >> BOOST_SERIALIZATION_NVP(cols); @@ -566,8 +582,19 @@ namespace boost { ar >> make_nvp("data", make_array(m.data(), m.size())); } + // templated version of BOOST_SERIALIZATION_SPLIT_FREE(Eigen::Matrix); + template + void serialize(Archive & ar, + Eigen::Matrix & m, + const unsigned int version) { + split_free(ar, m, version); + } + } // namespace serialization } // namespace boost - -BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Matrix); - From b1dda699a336ff868d498401b138869bbf9441b8 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 9 Jul 2020 23:49:23 -0400 Subject: [PATCH 146/199] add compiler flags to suppress warnings if built in release mode --- gtsam/CMakeLists.txt | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 3d1bbd2a7..2ca83e093 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -106,6 +106,11 @@ add_library(gtsam ${gtsam_srcs}) target_link_libraries(gtsam PUBLIC ${GTSAM_BOOST_LIBRARIES}) target_link_libraries(gtsam PUBLIC ${GTSAM_ADDITIONAL_LIBRARIES}) +if(${CMAKE_BUILD_TYPE} STREQUAL "Release") + # Suppress warnings if Release build + target_compile_options(gtsam PRIVATE -w) +endif() + # Apply build flags: gtsam_apply_build_flags(gtsam) From ca1427640459c23c07043746713b10559835cd9d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 00:15:12 -0400 Subject: [PATCH 147/199] Add MATLAB root and Mex paths to cmake output, align GTSAM specific output --- CMakeLists.txt | 50 +++++++++++++++++++++++++++----------------------- 1 file changed, 27 insertions(+), 23 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index a810ac9df..f6f012118 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -537,54 +537,54 @@ endif() print_build_options_for_target(gtsam) -message(STATUS " Use System Eigen : ${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") +message(STATUS " Use System Eigen : ${GTSAM_USE_SYSTEM_EIGEN} (Using version: ${GTSAM_EIGEN_VERSION})") if(GTSAM_USE_TBB) - message(STATUS " Use Intel TBB : Yes") + message(STATUS " Use Intel TBB : Yes") elseif(TBB_FOUND) - message(STATUS " Use Intel TBB : TBB found but GTSAM_WITH_TBB is disabled") + message(STATUS " Use Intel TBB : TBB found but GTSAM_WITH_TBB is disabled") else() - message(STATUS " Use Intel TBB : TBB not found") + message(STATUS " Use Intel TBB : TBB not found") endif() if(GTSAM_USE_EIGEN_MKL) - message(STATUS " Eigen will use MKL : Yes") + message(STATUS " Eigen will use MKL : Yes") elseif(MKL_FOUND) - message(STATUS " Eigen will use MKL : MKL found but GTSAM_WITH_EIGEN_MKL is disabled") + message(STATUS " Eigen will use MKL : MKL found but GTSAM_WITH_EIGEN_MKL is disabled") else() - message(STATUS " Eigen will use MKL : MKL not found") + message(STATUS " Eigen will use MKL : MKL not found") endif() if(GTSAM_USE_EIGEN_MKL_OPENMP) - message(STATUS " Eigen will use MKL and OpenMP : Yes") + message(STATUS " Eigen will use MKL and OpenMP : Yes") elseif(OPENMP_FOUND AND NOT GTSAM_WITH_EIGEN_MKL) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL is disabled") + message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL is disabled") elseif(OPENMP_FOUND AND NOT MKL_FOUND) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but MKL not found") + message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but MKL not found") elseif(OPENMP_FOUND) - message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL_OPENMP is disabled") + message(STATUS " Eigen will use MKL and OpenMP : OpenMP found but GTSAM_WITH_EIGEN_MKL_OPENMP is disabled") else() - message(STATUS " Eigen will use MKL and OpenMP : OpenMP not found") + message(STATUS " Eigen will use MKL and OpenMP : OpenMP not found") endif() -message(STATUS " Default allocator : ${GTSAM_DEFAULT_ALLOCATOR}") +message(STATUS " Default allocator : ${GTSAM_DEFAULT_ALLOCATOR}") if(GTSAM_THROW_CHEIRALITY_EXCEPTION) - message(STATUS " Cheirality exceptions enabled : YES") + message(STATUS " Cheirality exceptions enabled : YES") else() - message(STATUS " Cheirality exceptions enabled : NO") + message(STATUS " Cheirality exceptions enabled : NO") endif() if(NOT MSVC AND NOT XCODE_VERSION) if(CCACHE_FOUND AND GTSAM_BUILD_WITH_CCACHE) - message(STATUS " Build with ccache : Yes") + message(STATUS " Build with ccache : Yes") elseif(CCACHE_FOUND) - message(STATUS " Build with ccache : ccache found but GTSAM_BUILD_WITH_CCACHE is disabled") + message(STATUS " Build with ccache : ccache found but GTSAM_BUILD_WITH_CCACHE is disabled") else() - message(STATUS " Build with ccache : No") + message(STATUS " Build with ccache : No") endif() endif() message(STATUS "Packaging flags ") -message(STATUS " CPack Source Generator : ${CPACK_SOURCE_GENERATOR}") -message(STATUS " CPack Generator : ${CPACK_GENERATOR}") +message(STATUS " CPack Source Generator : ${CPACK_SOURCE_GENERATOR}") +message(STATUS " CPack Generator : ${CPACK_GENERATOR}") message(STATUS "GTSAM flags ") print_config_flag(${GTSAM_USE_QUATERNIONS} "Quaternions as default Rot3 ") @@ -595,13 +595,17 @@ print_config_flag(${GTSAM_ALLOW_DEPRECATED_SINCE_V4} "Deprecated in GTSAM 4 al print_config_flag(${GTSAM_TYPEDEF_POINTS_TO_VECTORS} "Point3 is typedef to Vector3 ") print_config_flag(${GTSAM_SUPPORT_NESTED_DISSECTION} "Metis-based Nested Dissection ") print_config_flag(${GTSAM_TANGENT_PREINTEGRATION} "Use tangent-space preintegration") -print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") +print_config_flag(${GTSAM_BUILD_WRAP} "Build Wrap ") message(STATUS "MATLAB toolbox flags ") -print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install matlab toolbox ") +print_config_flag(${GTSAM_INSTALL_MATLAB_TOOLBOX} "Install MATLAB toolbox ") +if (${GTSAM_INSTALL_MATLAB_TOOLBOX}) + message(STATUS " MATLAB root : ${MATLAB_ROOT}") + message(STATUS " MEX binary : ${MEX_COMMAND}") +endif() message(STATUS "Cython toolbox flags ") -print_config_flag(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") +print_config_flag(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") if(GTSAM_INSTALL_CYTHON_TOOLBOX) message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") endif() From 10a131fc365146f970e33dc0c3939dc9189385f3 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 00:19:54 -0400 Subject: [PATCH 148/199] Quote variable so it works on Windows --- gtsam/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index 2ca83e093..c4ad0a755 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -106,7 +106,7 @@ add_library(gtsam ${gtsam_srcs}) target_link_libraries(gtsam PUBLIC ${GTSAM_BOOST_LIBRARIES}) target_link_libraries(gtsam PUBLIC ${GTSAM_ADDITIONAL_LIBRARIES}) -if(${CMAKE_BUILD_TYPE} STREQUAL "Release") +if("${CMAKE_BUILD_TYPE}" STREQUAL "Release") # Suppress warnings if Release build target_compile_options(gtsam PRIVATE -w) endif() From 7259f899d9a37b575853cc2d0ce415e6966d6c6e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 09:26:48 -0400 Subject: [PATCH 149/199] Use static matrix and constexpr --- gtsam/slam/SmartFactorBase.h | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 912de0bc1..1c80b8744 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -207,17 +207,18 @@ protected: Vector ue = cameras.reprojectionError(point, measured_, Fs, E); if (body_P_sensor_ && Fs) { const Pose3 sensor_P_body = body_P_sensor_->inverse(); - size_t camera_dim = size_t(traits::dimension); - size_t pose_dim = size_t(traits::dimension); + constexpr int camera_dim = traits::dimension; + constexpr int pose_dim = traits::dimension; for (size_t i = 0; i < Fs->size(); i++) { const Pose3 world_P_body = cameras[i].pose() * sensor_P_body; - Matrix J = Matrix::Zero(camera_dim, camera_dim); + Eigen::Matrix J; + J.setZero(); + Eigen::Matrix H; // Call compose to compute Jacobian for camera extrinsics - Matrix H(pose_dim, pose_dim); world_P_body.compose(*body_P_sensor_, H); - // Assign extrinsics - J.block(0, 0, pose_dim, pose_dim) = H; + // Assign extrinsics part of the Jacobian + J.template block(0, 0) = H; Fs->at(i) = Fs->at(i) * J; } } From b735174707aa379cdc47e3dce5a7c74f20e7c36f Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 10:03:38 -0400 Subject: [PATCH 150/199] use boost serialization macro instead of make_array --- gtsam/navigation/ImuFactor.h | 2 +- gtsam/navigation/ManifoldPreintegration.h | 10 +++++----- gtsam/navigation/PreintegratedRotation.h | 2 +- gtsam/navigation/PreintegrationParams.h | 4 ++-- gtsam/navigation/TangentPreintegration.h | 6 +++--- 5 files changed, 12 insertions(+), 12 deletions(-) diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index 8e3f8f0a4..a69fab6e9 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -164,7 +164,7 @@ private: void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(PreintegrationType); - ar & bs::make_nvp("preintMeasCov_", bs::make_array(preintMeasCov_.data(), preintMeasCov_.size())); + ar & BOOST_SERIALIZATION_NVP(preintMeasCov_); } }; diff --git a/gtsam/navigation/ManifoldPreintegration.h b/gtsam/navigation/ManifoldPreintegration.h index 22897b9d4..ee983a78f 100644 --- a/gtsam/navigation/ManifoldPreintegration.h +++ b/gtsam/navigation/ManifoldPreintegration.h @@ -122,11 +122,11 @@ private: ar & BOOST_SERIALIZATION_NVP(deltaTij_); ar & BOOST_SERIALIZATION_NVP(deltaXij_); ar & BOOST_SERIALIZATION_NVP(biasHat_); - ar & bs::make_nvp("delRdelBiasOmega_", bs::make_array(delRdelBiasOmega_.data(), delRdelBiasOmega_.size())); - ar & bs::make_nvp("delPdelBiasAcc_", bs::make_array(delPdelBiasAcc_.data(), delPdelBiasAcc_.size())); - ar & bs::make_nvp("delPdelBiasOmega_", bs::make_array(delPdelBiasOmega_.data(), delPdelBiasOmega_.size())); - ar & bs::make_nvp("delVdelBiasAcc_", bs::make_array(delVdelBiasAcc_.data(), delVdelBiasAcc_.size())); - ar & bs::make_nvp("delVdelBiasOmega_", bs::make_array(delVdelBiasOmega_.data(), delVdelBiasOmega_.size())); + ar & BOOST_SERIALIZATION_NVP(delRdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(delPdelBiasAcc_); + ar & BOOST_SERIALIZATION_NVP(delPdelBiasOmega_); + ar & BOOST_SERIALIZATION_NVP(delVdelBiasAcc_); + ar & BOOST_SERIALIZATION_NVP(delVdelBiasOmega_); } }; diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 12938a625..9346f749a 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -61,7 +61,7 @@ struct GTSAM_EXPORT PreintegratedRotationParams { template void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; - ar & bs::make_nvp("gyroscopeCovariance", bs::make_array(gyroscopeCovariance.data(), gyroscopeCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance); ar & BOOST_SERIALIZATION_NVP(omegaCoriolis); ar & BOOST_SERIALIZATION_NVP(body_P_sensor); } diff --git a/gtsam/navigation/PreintegrationParams.h b/gtsam/navigation/PreintegrationParams.h index 4bff625ca..d997ccbed 100644 --- a/gtsam/navigation/PreintegrationParams.h +++ b/gtsam/navigation/PreintegrationParams.h @@ -75,8 +75,8 @@ protected: namespace bs = ::boost::serialization; ar & boost::serialization::make_nvp("PreintegratedRotation_Params", boost::serialization::base_object(*this)); - ar & bs::make_nvp("accelerometerCovariance", bs::make_array(accelerometerCovariance.data(), accelerometerCovariance.size())); - ar & bs::make_nvp("integrationCovariance", bs::make_array(integrationCovariance.data(), integrationCovariance.size())); + ar & BOOST_SERIALIZATION_NVP(accelerometerCovariance); + ar & BOOST_SERIALIZATION_NVP(integrationCovariance); ar & BOOST_SERIALIZATION_NVP(use2ndOrderCoriolis); ar & BOOST_SERIALIZATION_NVP(n_gravity); } diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index edf76e562..29318a6bb 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -135,9 +135,9 @@ private: ar & BOOST_SERIALIZATION_NVP(p_); ar & BOOST_SERIALIZATION_NVP(biasHat_); ar & BOOST_SERIALIZATION_NVP(deltaTij_); - ar & bs::make_nvp("preintegrated_", bs::make_array(preintegrated_.data(), preintegrated_.size())); - ar & bs::make_nvp("preintegrated_H_biasAcc_", bs::make_array(preintegrated_H_biasAcc_.data(), preintegrated_H_biasAcc_.size())); - ar & bs::make_nvp("preintegrated_H_biasOmega_", bs::make_array(preintegrated_H_biasOmega_.data(), preintegrated_H_biasOmega_.size())); + ar & BOOST_SERIALIZATION_NVP(preintegrated_); + ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasAcc_); + ar & BOOST_SERIALIZATION_NVP(preintegrated_H_biasOmega_); } public: From 3f4731a9482d71ce65174140713b9c0384a38eec Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 10 Jul 2020 15:00:57 -0400 Subject: [PATCH 151/199] Added wrapping for the PCG solver in Cython --- gtsam.h | 16 ++++++++++++++++ gtsam/linear/PCGSolver.cpp | 11 +++++++++++ gtsam/linear/PCGSolver.h | 4 ++++ 3 files changed, 31 insertions(+) diff --git a/gtsam.h b/gtsam.h index 614db91c7..d65186439 100644 --- a/gtsam.h +++ b/gtsam.h @@ -1937,6 +1937,22 @@ virtual class ConjugateGradientParameters : gtsam::IterativeOptimizationParamete void print() const; }; +#include +virtual class PreconditionerParameters { + PreconditionerParameters(); +}; + +virtual class DummyPreconditionerParameters : gtsam::PreconditionerParameters { + DummyPreconditionerParameters(); +}; + +#include +virtual class PCGSolverParameters : gtsam::ConjugateGradientParameters { + PCGSolverParameters(); + void print(string s); + void setPreconditionerParams(gtsam::PreconditionerParameters* preconditioner); +}; + #include virtual class SubgraphSolverParameters : gtsam::ConjugateGradientParameters { SubgraphSolverParameters(); diff --git a/gtsam/linear/PCGSolver.cpp b/gtsam/linear/PCGSolver.cpp index 08307c5ab..a7af7d8d8 100644 --- a/gtsam/linear/PCGSolver.cpp +++ b/gtsam/linear/PCGSolver.cpp @@ -45,6 +45,17 @@ PCGSolver::PCGSolver(const PCGSolverParameters &p) { preconditioner_ = createPreconditioner(p.preconditioner_); } +void PCGSolverParameters::setPreconditionerParams(const boost::shared_ptr preconditioner) { + preconditioner_ = preconditioner; +} + +void PCGSolverParameters::print(const std::string &s) const { + std::cout << s << std::endl;; + std::ostringstream os; + print(os); + std::cout << os.str() << std::endl; +} + /*****************************************************************************/ VectorValues PCGSolver::optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map &lambda, diff --git a/gtsam/linear/PCGSolver.h b/gtsam/linear/PCGSolver.h index f5b278ae5..3e72c7cbe 100644 --- a/gtsam/linear/PCGSolver.h +++ b/gtsam/linear/PCGSolver.h @@ -48,7 +48,11 @@ public: return *preconditioner_; } + void print(const std::string &s) const; + boost::shared_ptr preconditioner_; + + void setPreconditionerParams(const boost::shared_ptr preconditioner); }; /** From 7f293eb84e66b6468c92257e52741fbdfd8d13b0 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Fri, 10 Jul 2020 15:01:54 -0400 Subject: [PATCH 152/199] add comments --- gtsam/linear/PCGSolver.h | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/linear/PCGSolver.h b/gtsam/linear/PCGSolver.h index 3e72c7cbe..7752902ba 100644 --- a/gtsam/linear/PCGSolver.h +++ b/gtsam/linear/PCGSolver.h @@ -48,6 +48,7 @@ public: return *preconditioner_; } + // needed for python wrapper void print(const std::string &s) const; boost::shared_ptr preconditioner_; From 1fadf1e7ef032e5e6a6d74e5a1a5e8cf7865ce3d Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 21:43:30 -0400 Subject: [PATCH 153/199] suppress warnings only for 3rd party code for Release builds --- gtsam/CMakeLists.txt | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index c4ad0a755..a927ca3a0 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -15,7 +15,7 @@ set (gtsam_subdirs sfm slam smart - navigation + navigation ) set(gtsam_srcs) @@ -106,11 +106,6 @@ add_library(gtsam ${gtsam_srcs}) target_link_libraries(gtsam PUBLIC ${GTSAM_BOOST_LIBRARIES}) target_link_libraries(gtsam PUBLIC ${GTSAM_ADDITIONAL_LIBRARIES}) -if("${CMAKE_BUILD_TYPE}" STREQUAL "Release") - # Suppress warnings if Release build - target_compile_options(gtsam PRIVATE -w) -endif() - # Apply build flags: gtsam_apply_build_flags(gtsam) @@ -191,11 +186,17 @@ install( list(APPEND GTSAM_EXPORTED_TARGETS gtsam) set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) -# make sure that ccolamd compiles even in face of warnings +# Make sure that ccolamd compiles even in face of warnings +# and suppress all warnings from 3rd party code if Release build if(WIN32) - set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-w") + set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-w") else() + if("${CMAKE_BUILD_TYPE}" STREQUAL "Release") + # Suppress all warnings from 3rd party sources. + set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-w") + else() set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-Wno-error") + endif() endif() # Create the matlab toolbox for the gtsam library From e41dbfc26cff7c0f6d0dd44ba61280a779438298 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 21:45:01 -0400 Subject: [PATCH 154/199] fix init issues with Vector3, use static matrices where possible --- examples/IMUKittiExampleGPS.cpp | 22 ++++++++++++++-------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/examples/IMUKittiExampleGPS.cpp b/examples/IMUKittiExampleGPS.cpp index 7cfccbc11..f1d89b47a 100644 --- a/examples/IMUKittiExampleGPS.cpp +++ b/examples/IMUKittiExampleGPS.cpp @@ -163,7 +163,7 @@ int main(int argc, char* argv[]) { vector gps_measurements; loadKittiData(kitti_calibration, imu_measurements, gps_measurements); - Vector6 BodyP = (Vector(6) << kitti_calibration.body_ptx, kitti_calibration.body_pty, kitti_calibration.body_ptz, + Vector6 BodyP = (Vector6() << kitti_calibration.body_ptx, kitti_calibration.body_pty, kitti_calibration.body_ptz, kitti_calibration.body_prx, kitti_calibration.body_pry, kitti_calibration.body_prz) .finished(); auto body_T_imu = Pose3::Expmap(BodyP); @@ -173,28 +173,29 @@ int main(int argc, char* argv[]) { } // Configure different variables - double t_offset = gps_measurements[0].time; + // double t_offset = gps_measurements[0].time; size_t first_gps_pose = 1; size_t gps_skip = 10; // Skip this many GPS measurements each time double g = 9.8; - auto w_coriolis = Vector3(); // zero vector + auto w_coriolis = Vector3::Zero(); // zero vector // Configure noise models - auto noise_model_gps = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), + auto noise_model_gps = noiseModel::Diagonal::Precisions((Vector6() << Vector3::Constant(0), Vector3::Constant(1.0/0.07)) .finished()); // Set initial conditions for the estimated trajectory // initial pose is the reference frame (navigation frame) auto current_pose_global = Pose3(Rot3(), gps_measurements[first_gps_pose].position); - auto current_velocity_global = Vector3(); // the vehicle is stationary at the beginning at position 0,0,0 + // the vehicle is stationary at the beginning at position 0,0,0 + Vector3 current_velocity_global = Vector3::Zero(); auto current_bias = imuBias::ConstantBias(); // init with zero bias - auto sigma_init_x = noiseModel::Diagonal::Precisions((Vector(6) << Vector3::Constant(0), + auto sigma_init_x = noiseModel::Diagonal::Precisions((Vector6() << Vector3::Constant(0), Vector3::Constant(1.0)) .finished()); auto sigma_init_v = noiseModel::Diagonal::Sigmas(Vector3::Constant(1000.0)); - auto sigma_init_b = noiseModel::Diagonal::Sigmas((Vector(6) << Vector3::Constant(0.100), + auto sigma_init_b = noiseModel::Diagonal::Sigmas((Vector6() << Vector3::Constant(0.100), Vector3::Constant(5.00e-05)) .finished()); @@ -270,7 +271,7 @@ int main(int argc, char* argv[]) { previous_bias_key, *current_summarized_measurement); // Bias evolution as given in the IMU metadata - auto sigma_between_b = noiseModel::Diagonal::Sigmas((Vector(6) << + auto sigma_between_b = noiseModel::Diagonal::Sigmas((Vector6() << Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.accelerometer_bias_sigma), Vector3::Constant(sqrt(included_imu_measurement_count) * kitti_calibration.gyroscope_bias_sigma)) .finished()); @@ -342,6 +343,11 @@ int main(int argc, char* argv[]) { auto pose_quat = pose.rotation().toQuaternion(); auto gps = gps_measurements[i].position; + cout << "State at #" << i << endl; + cout << "Pose:" << endl << pose << endl; + cout << "Velocity:" << endl << velocity << endl; + cout << "Bias:" << endl << bias << endl; + fprintf(fp_out, "%f,%f,%f,%f,%f,%f,%f,%f,%f,%f,%f\n", gps_measurements[i].time, pose.x(), pose.y(), pose.z(), From 09ddd433a60f4c89286202d08ade957bbd06269b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 10 Jul 2020 21:51:36 -0400 Subject: [PATCH 155/199] added note about code source and eigen resize for both static and dynamic matrices --- gtsam/base/Matrix.h | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index b1c6268a7..37ae1dd9a 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -548,6 +548,20 @@ GTSAM_EXPORT Vector columnNormSquare(const Matrix &A); namespace boost { namespace serialization { + /** + * Ref. https://stackoverflow.com/questions/18382457/eigen-and-boostserialize/22903063#22903063 + * + * Eigen supports calling resize() on both static and dynamic matrices. + * This allows for a uniform API, with resize having no effect if the static matrix + * is already the correct size. + * https://eigen.tuxfamily.org/dox/group__TutorialMatrixClass.html#TutorialMatrixSizesResizing + * + * We use all the Matrix template parameters to ensure wide compatibility. + * + * eigen_typekit in ROS uses the same code + * http://docs.ros.org/lunar/api/eigen_typekit/html/eigen__mqueue_8cpp_source.html + */ + // split version - sends sizes ahead template Date: Fri, 10 Jul 2020 23:01:18 -0400 Subject: [PATCH 156/199] Explicit type definition to handle warning --- examples/SFMExample.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/SFMExample.cpp b/examples/SFMExample.cpp index 7f0c79e0e..fddca8169 100644 --- a/examples/SFMExample.cpp +++ b/examples/SFMExample.cpp @@ -109,7 +109,7 @@ int main(int argc, char* argv[]) { Symbol('x', i), corrupted_pose); } for (size_t j = 0; j < points.size(); ++j) { - auto corrupted_point = points[j] + Point3(-0.25, 0.20, 0.15); + Point3 corrupted_point = points[j] + Point3(-0.25, 0.20, 0.15); initialEstimate.insert(Symbol('l', j), corrupted_point); } initialEstimate.print("Initial Estimates:\n"); From 8e5f1447e3d57b4722f1089b1fc5152e966cfc00 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 11 Jul 2020 11:54:40 -0400 Subject: [PATCH 157/199] Add check to ensure we are calling lambda on a LM --- cython/gtsam/tests/test_logging_optimizer.py | 15 +++++++++++++++ cython/gtsam/utils/logging_optimizer.py | 3 ++- 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/cython/gtsam/tests/test_logging_optimizer.py b/cython/gtsam/tests/test_logging_optimizer.py index 69665db65..2560a72a2 100644 --- a/cython/gtsam/tests/test_logging_optimizer.py +++ b/cython/gtsam/tests/test_logging_optimizer.py @@ -43,6 +43,11 @@ class TestOptimizeComet(GtsamTestCase): self.optimizer = gtsam.GaussNewtonOptimizer( graph, initial, self.params) + self.lmparams = gtsam.LevenbergMarquardtParams() + self.lmoptimizer = gtsam.LevenbergMarquardtOptimizer( + graph, initial, self.lmparams + ) + # setup output capture self.capturedOutput = StringIO() sys.stdout = self.capturedOutput @@ -65,6 +70,16 @@ class TestOptimizeComet(GtsamTestCase): actual = self.optimizer.values() self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6) + def test_lm_simple_printing(self): + """Make sure we are properly terminating LM""" + def hook(_, error): + print(error) + + gtsam_optimize(self.lmoptimizer, self.lmparams, hook) + + actual = self.lmoptimizer.values() + self.gtsamAssertEquals(actual.atRot3(KEY), self.expected, tol=1e-6) + @unittest.skip("Not a test we want run every time, as needs comet.ml account") def test_comet(self): """Test with a comet hook.""" diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index a48413212..27b9b3a3a 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -46,6 +46,7 @@ def gtsam_optimize(optimizer, def check_convergence(optimizer, current_error, new_error): return (optimizer.iterations() >= params.getMaxIterations()) or ( gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), - current_error, new_error)) or (optimizer.lambda_() > params.getlambdaUpperBound()) + current_error, new_error)) or ( + type(optimizer).__name__ == "LevenbergMarquardtOptimizer" and optimizer.lambda_() > params.getlambdaUpperBound()) optimize(optimizer, check_convergence, hook) return optimizer.values() From 7b23f570f9758d4bf407436d6c42c88d7f9d5ad7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 11 Jul 2020 14:33:40 -0400 Subject: [PATCH 158/199] correct compiler flag for Windows --- gtsam/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/CMakeLists.txt b/gtsam/CMakeLists.txt index a927ca3a0..16dca6736 100644 --- a/gtsam/CMakeLists.txt +++ b/gtsam/CMakeLists.txt @@ -189,7 +189,7 @@ set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE) # Make sure that ccolamd compiles even in face of warnings # and suppress all warnings from 3rd party code if Release build if(WIN32) - set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "-w") + set_source_files_properties(${3rdparty_srcs} PROPERTIES COMPILE_FLAGS "/w") else() if("${CMAKE_BUILD_TYPE}" STREQUAL "Release") # Suppress all warnings from 3rd party sources. From 25513379e319132bb0b79c4873500e22ec330945 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 11 Jul 2020 14:37:54 -0400 Subject: [PATCH 159/199] Add unit test --- cython/gtsam/tests/test_NonlinearOptimizer.py | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/cython/gtsam/tests/test_NonlinearOptimizer.py b/cython/gtsam/tests/test_NonlinearOptimizer.py index efefb218a..985dc30a2 100644 --- a/cython/gtsam/tests/test_NonlinearOptimizer.py +++ b/cython/gtsam/tests/test_NonlinearOptimizer.py @@ -17,7 +17,8 @@ import unittest import gtsam from gtsam import (DoglegOptimizer, DoglegParams, GaussNewtonOptimizer, GaussNewtonParams, LevenbergMarquardtOptimizer, - LevenbergMarquardtParams, NonlinearFactorGraph, Ordering, + LevenbergMarquardtParams, PCGSolverParameters, + DummyPreconditionerParameters, NonlinearFactorGraph, Ordering, Point2, PriorFactorPoint2, Values) from gtsam.utils.test_case import GtsamTestCase @@ -61,6 +62,16 @@ class TestScenario(GtsamTestCase): fg, initial_values, lmParams).optimize() self.assertAlmostEqual(0, fg.error(actual2)) + # Levenberg-Marquardt + lmParams = LevenbergMarquardtParams.CeresDefaults() + lmParams.setLinearSolverType("ITERATIVE") + cgParams = PCGSolverParameters() + cgParams.setPreconditionerParams(DummyPreconditionerParameters()) + lmParams.setIterativeParams(cgParams) + actual2 = LevenbergMarquardtOptimizer( + fg, initial_values, lmParams).optimize() + self.assertAlmostEqual(0, fg.error(actual2)) + # Dogleg dlParams = DoglegParams() dlParams.setOrdering(ordering) From 566467de5ddec015f419d3be6237899955e4017d Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sat, 11 Jul 2020 16:50:25 -0400 Subject: [PATCH 160/199] use isinstance --- cython/gtsam/utils/logging_optimizer.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cython/gtsam/utils/logging_optimizer.py b/cython/gtsam/utils/logging_optimizer.py index 27b9b3a3a..3d9175951 100644 --- a/cython/gtsam/utils/logging_optimizer.py +++ b/cython/gtsam/utils/logging_optimizer.py @@ -47,6 +47,6 @@ def gtsam_optimize(optimizer, return (optimizer.iterations() >= params.getMaxIterations()) or ( gtsam.checkConvergence(params.getRelativeErrorTol(), params.getAbsoluteErrorTol(), params.getErrorTol(), current_error, new_error)) or ( - type(optimizer).__name__ == "LevenbergMarquardtOptimizer" and optimizer.lambda_() > params.getlambdaUpperBound()) + isinstance(optimizer, gtsam.LevenbergMarquardtOptimizer) and optimizer.lambda_() > params.getlambdaUpperBound()) optimize(optimizer, check_convergence, hook) return optimizer.values() From 289ab6271dcfe4c9c956507d6f19c1a15f811942 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sat, 11 Jul 2020 21:44:38 -0400 Subject: [PATCH 161/199] added cmake policy for AppleClang compiler identification --- cmake/GtsamBuildTypes.cmake | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index 15a02b6e8..088ba7ad2 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -1,3 +1,8 @@ +# Set cmake policy to recognize the AppleClang compiler +# independently from the Clang compiler. +if(POLICY CMP0025) + cmake_policy(SET CMP0025 NEW) +endif() # function: list_append_cache(var [new_values ...]) # Like "list(APPEND ...)" but working for CACHE variables. From 8b9c199d0b079bacf29997c7c496520b471a49b6 Mon Sep 17 00:00:00 2001 From: Fan Jiang Date: Sun, 12 Jul 2020 10:28:23 -0400 Subject: [PATCH 162/199] Move the declaration to cpp --- gtsam/navigation/CombinedImuFactor.h | 2 -- gtsam/navigation/tests/testImuFactorSerialization.cpp | 3 +++ 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index f47ce8846..f7ea25371 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -384,5 +384,3 @@ struct traits : public Testable {}; } // namespace gtsam -/// Add Boost serialization export for derived class -BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); diff --git a/gtsam/navigation/tests/testImuFactorSerialization.cpp b/gtsam/navigation/tests/testImuFactorSerialization.cpp index ed72e18e9..6a9e727f2 100644 --- a/gtsam/navigation/tests/testImuFactorSerialization.cpp +++ b/gtsam/navigation/tests/testImuFactorSerialization.cpp @@ -42,6 +42,9 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); +/// Add Boost serialization export for derived class +BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); + template P getPreintegratedMeasurements() { // Create default parameters with Z-down and above noise paramaters From a500b4147312d0756e73c82c03bb2da46d0a3e79 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 11:39:47 -0400 Subject: [PATCH 163/199] Better way of exporting Boost serialization guid --- gtsam/navigation/CombinedImuFactor.cpp | 3 +++ gtsam/navigation/CombinedImuFactor.h | 2 ++ gtsam/navigation/tests/testImuFactorSerialization.cpp | 3 --- 3 files changed, 5 insertions(+), 3 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 7a8c73013..7f58f7e64 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -313,3 +313,6 @@ void CombinedImuFactor::Predict(const Pose3& pose_i, const Vector3& vel_i, } /// namespace gtsam +/// Boost serialization export definition for derived class +BOOST_CLASS_EXPORT_IMPLEMENT(gtsam::PreintegrationCombinedParams); + diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index f7ea25371..8b6dcd3f2 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -384,3 +384,5 @@ struct traits : public Testable {}; } // namespace gtsam +/// Add Boost serialization export key (declaration) for derived class +BOOST_CLASS_EXPORT_KEY(gtsam::PreintegrationCombinedParams); diff --git a/gtsam/navigation/tests/testImuFactorSerialization.cpp b/gtsam/navigation/tests/testImuFactorSerialization.cpp index 6a9e727f2..ed72e18e9 100644 --- a/gtsam/navigation/tests/testImuFactorSerialization.cpp +++ b/gtsam/navigation/tests/testImuFactorSerialization.cpp @@ -42,9 +42,6 @@ BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel"); BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal"); -/// Add Boost serialization export for derived class -BOOST_CLASS_EXPORT_GUID(gtsam::PreintegrationCombinedParams, "gtsam_PreintegrationCombinedParams"); - template P getPreintegratedMeasurements() { // Create default parameters with Z-down and above noise paramaters From 58362579bb6d22ca9b94d4c0a3daf63bda0508a2 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 12:27:10 -0400 Subject: [PATCH 164/199] Resurrecting DiscreteBayesTree tests --- gtsam/discrete/DiscreteBayesNet.h | 3 +- gtsam/discrete/DiscreteBayesTree.cpp | 13 +- gtsam/discrete/DiscreteBayesTree.h | 3 + .../discrete/tests/testDiscreteBayesTree.cpp | 499 +++++++++--------- 4 files changed, 257 insertions(+), 261 deletions(-) diff --git a/gtsam/discrete/DiscreteBayesNet.h b/gtsam/discrete/DiscreteBayesNet.h index dcc336f89..237caf745 100644 --- a/gtsam/discrete/DiscreteBayesNet.h +++ b/gtsam/discrete/DiscreteBayesNet.h @@ -20,13 +20,14 @@ #include #include #include +#include #include #include namespace gtsam { /** A Bayes net made from linear-Discrete densities */ - class GTSAM_EXPORT DiscreteBayesNet: public FactorGraph + class GTSAM_EXPORT DiscreteBayesNet: public BayesNet { public: diff --git a/gtsam/discrete/DiscreteBayesTree.cpp b/gtsam/discrete/DiscreteBayesTree.cpp index bed50a470..8fcc34e25 100644 --- a/gtsam/discrete/DiscreteBayesTree.cpp +++ b/gtsam/discrete/DiscreteBayesTree.cpp @@ -29,10 +29,19 @@ namespace gtsam { template class BayesTreeCliqueBase; template class BayesTree; + /* ************************************************************************* */ + double DiscreteBayesTreeClique::evaluate( + const DiscreteConditional::Values& values) const { + // evaluate all conditionals and multiply + double result = (*conditional_)(values); + for (const auto& child : children) { + result *= child->evaluate(values); + } + return result; + } /* ************************************************************************* */ - bool DiscreteBayesTree::equals(const This& other, double tol) const - { + bool DiscreteBayesTree::equals(const This& other, double tol) const { return Base::equals(other, tol); } diff --git a/gtsam/discrete/DiscreteBayesTree.h b/gtsam/discrete/DiscreteBayesTree.h index 0df6ab476..aa8f4657c 100644 --- a/gtsam/discrete/DiscreteBayesTree.h +++ b/gtsam/discrete/DiscreteBayesTree.h @@ -42,6 +42,9 @@ namespace gtsam { typedef boost::weak_ptr weak_ptr; DiscreteBayesTreeClique() {} DiscreteBayesTreeClique(const boost::shared_ptr& conditional) : Base(conditional) {} + + //** evaluate conditional probability of subtree for given Values */ + double evaluate(const DiscreteConditional::Values & values) const; }; /* ************************************************************************* */ diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 93126f642..f58fd2b19 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -1,261 +1,245 @@ -///* ---------------------------------------------------------------------------- -// -// * GTSAM Copyright 2010, Georgia Tech Research Corporation, -// * Atlanta, Georgia 30332-0415 -// * All Rights Reserved -// * Authors: Frank Dellaert, et al. (see THANKS for the full author list) -// -// * See LICENSE for the license information -// -// * -------------------------------------------------------------------------- */ -// -///* -// * @file testDiscreteBayesTree.cpp -// * @date sept 15, 2012 -// * @author Frank Dellaert -// */ -// -//#include -//#include -//#include -// -//#include -//using namespace boost::assign; -// +/* ---------------------------------------------------------------------------- + +* GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +* Atlanta, Georgia 30332-0415 +* All Rights Reserved +* Authors: Frank Dellaert, et al. (see THANKS for the full author list) + +* See LICENSE for the license information + +* -------------------------------------------------------------------------- */ + +/* + * @file testDiscreteBayesTree.cpp + * @date sept 15, 2012 + * @author Frank Dellaert + */ + +#include +#include +#include +#include +#include + +#include +using namespace boost::assign; + #include -// -//using namespace std; -//using namespace gtsam; -// -//static bool debug = false; -// -///** -// * Custom clique class to debug shortcuts -// */ -////class Clique: public BayesTreeCliqueBaseOrdered { -//// -////protected: -//// -////public: -//// -//// typedef BayesTreeCliqueBaseOrdered Base; -//// typedef boost::shared_ptr shared_ptr; -//// -//// // Constructors -//// Clique() { -//// } -//// Clique(const DiscreteConditional::shared_ptr& conditional) : -//// Base(conditional) { -//// } -//// Clique( -//// const std::pair& result) : -//// Base(result) { -//// } -//// -//// /// print index signature only -//// void printSignature(const std::string& s = "Clique: ", -//// const KeyFormatter& indexFormatter = DefaultKeyFormatter) const { -//// ((IndexConditionalOrdered::shared_ptr) conditional_)->print(s, indexFormatter); -//// } -//// -//// /// evaluate value of sub-tree -//// double evaluate(const DiscreteConditional::Values & values) { -//// double result = (*(this->conditional_))(values); -//// // evaluate all children and multiply into result -//// for(boost::shared_ptr c: children_) -//// result *= c->evaluate(values); -//// return result; -//// } -//// -////}; -// -////typedef BayesTreeOrdered DiscreteBayesTree; -//// -/////* ************************************************************************* */ -////double evaluate(const DiscreteBayesTree& tree, -//// const DiscreteConditional::Values & values) { -//// return tree.root()->evaluate(values); -////} -// -///* ************************************************************************* */ -// -//TEST_UNSAFE( DiscreteBayesTree, thinTree ) { -// -// const int nrNodes = 15; -// const size_t nrStates = 2; -// -// // define variables -// vector key; -// for (int i = 0; i < nrNodes; i++) { -// DiscreteKey key_i(i, nrStates); -// key.push_back(key_i); -// } -// -// // create a thin-tree Bayesnet, a la Jean-Guillaume -// DiscreteBayesNet bayesNet; -// bayesNet.add(key[14] % "1/3"); -// -// bayesNet.add(key[13] | key[14] = "1/3 3/1"); -// bayesNet.add(key[12] | key[14] = "3/1 3/1"); -// -// bayesNet.add((key[11] | key[13], key[14]) = "1/4 2/3 3/2 4/1"); -// bayesNet.add((key[10] | key[13], key[14]) = "1/4 3/2 2/3 4/1"); -// bayesNet.add((key[9] | key[12], key[14]) = "4/1 2/3 F 1/4"); -// bayesNet.add((key[8] | key[12], key[14]) = "T 1/4 3/2 4/1"); -// -// bayesNet.add((key[7] | key[11], key[13]) = "1/4 2/3 3/2 4/1"); -// bayesNet.add((key[6] | key[11], key[13]) = "1/4 3/2 2/3 4/1"); -// bayesNet.add((key[5] | key[10], key[13]) = "4/1 2/3 3/2 1/4"); -// bayesNet.add((key[4] | key[10], key[13]) = "2/3 1/4 3/2 4/1"); -// -// bayesNet.add((key[3] | key[9], key[12]) = "1/4 2/3 3/2 4/1"); -// bayesNet.add((key[2] | key[9], key[12]) = "1/4 8/2 2/3 4/1"); -// bayesNet.add((key[1] | key[8], key[12]) = "4/1 2/3 3/2 1/4"); -// bayesNet.add((key[0] | key[8], key[12]) = "2/3 1/4 3/2 4/1"); -// -//// if (debug) { -//// GTSAM_PRINT(bayesNet); -//// bayesNet.saveGraph("/tmp/discreteBayesNet.dot"); -//// } -// -// // create a BayesTree out of a Bayes net -// DiscreteBayesTree bayesTree(bayesNet); -// if (debug) { -// GTSAM_PRINT(bayesTree); -// bayesTree.saveGraph("/tmp/discreteBayesTree.dot"); -// } -// -// // Check whether BN and BT give the same answer on all configurations -// // Also calculate all some marginals -// Vector marginals = zero(15); -// double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0, -// joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0, -// joint_4_11 = 0; -// vector allPosbValues = cartesianProduct( -// key[0] & key[1] & key[2] & key[3] & key[4] & key[5] & key[6] & key[7] -// & key[8] & key[9] & key[10] & key[11] & key[12] & key[13] & key[14]); -// for (size_t i = 0; i < allPosbValues.size(); ++i) { -// DiscreteFactor::Values x = allPosbValues[i]; -// double expected = evaluate(bayesNet, x); -// double actual = evaluate(bayesTree, x); -// DOUBLES_EQUAL(expected, actual, 1e-9); -// // collect marginals -// for (size_t i = 0; i < 15; i++) -// if (x[i]) -// marginals[i] += actual; -// // calculate shortcut 8 and 0 -// if (x[12] && x[14]) -// joint_12_14 += actual; -// if (x[9] && x[12] & x[14]) -// joint_9_12_14 += actual; -// if (x[8] && x[12] & x[14]) -// joint_8_12_14 += actual; -// if (x[8] && x[12]) -// joint_8_12 += actual; -// if (x[8] && x[2]) -// joint82 += actual; -// if (x[1] && x[2]) -// joint12 += actual; -// if (x[2] && x[4]) -// joint24 += actual; -// if (x[4] && x[5]) -// joint45 += actual; -// if (x[4] && x[6]) -// joint46 += actual; -// if (x[4] && x[11]) -// joint_4_11 += actual; -// } -// DiscreteFactor::Values all1 = allPosbValues.back(); -// -// Clique::shared_ptr R = bayesTree.root(); -// -// // check separator marginal P(S0) -// Clique::shared_ptr c = bayesTree[0]; -// DiscreteFactorGraph separatorMarginal0 = c->separatorMarginal(R, -// EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); -// -// // check separator marginal P(S9), should be P(14) -// c = bayesTree[9]; -// DiscreteFactorGraph separatorMarginal9 = c->separatorMarginal(R, -// EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); -// -// // check separator marginal of root, should be empty -// c = bayesTree[11]; -// DiscreteFactorGraph separatorMarginal11 = c->separatorMarginal(R, -// EliminateDiscrete); -// EXPECT_LONGS_EQUAL(0, separatorMarginal11.size()); -// -// // check shortcut P(S9||R) to root -// c = bayesTree[9]; -// DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); -// EXPECT_LONGS_EQUAL(0, shortcut.size()); -// -// // check shortcut P(S8||R) to root -// c = bayesTree[8]; -// shortcut = c->shortcut(R, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_12_14/marginals[14], evaluate(shortcut,all1), -// 1e-9); -// -// // check shortcut P(S2||R) to root -// c = bayesTree[2]; -// shortcut = c->shortcut(R, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_9_12_14/marginals[14], evaluate(shortcut,all1), -// 1e-9); -// -// // check shortcut P(S0||R) to root -// c = bayesTree[0]; -// shortcut = c->shortcut(R, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_8_12_14/marginals[14], evaluate(shortcut,all1), -// 1e-9); -// -// // calculate all shortcuts to root -// DiscreteBayesTree::Nodes cliques = bayesTree.nodes(); -// for(Clique::shared_ptr c: cliques) { -// DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); -// if (debug) { -// c->printSignature(); -// shortcut.print("shortcut:"); -// } -// } -// -// // Check all marginals -// DiscreteFactor::shared_ptr marginalFactor; -// for (size_t i = 0; i < 15; i++) { -// marginalFactor = bayesTree.marginalFactor(i, EliminateDiscrete); -// double actual = (*marginalFactor)(all1); -// EXPECT_DOUBLES_EQUAL(marginals[i], actual, 1e-9); -// } -// -// DiscreteBayesNet::shared_ptr actualJoint; -// -// // Check joint P(8,2) TODO: not disjoint ! -//// actualJoint = bayesTree.jointBayesNet(8, 2, EliminateDiscrete); -//// EXPECT_DOUBLES_EQUAL(joint82, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(1,2) TODO: not disjoint ! -//// actualJoint = bayesTree.jointBayesNet(1, 2, EliminateDiscrete); -//// EXPECT_DOUBLES_EQUAL(joint12, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(2,4) -// actualJoint = bayesTree.jointBayesNet(2, 4, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint24, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(4,5) TODO: not disjoint ! -//// actualJoint = bayesTree.jointBayesNet(4, 5, EliminateDiscrete); -//// EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(4,6) TODO: not disjoint ! -//// actualJoint = bayesTree.jointBayesNet(4, 6, EliminateDiscrete); -//// EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); -// -// // Check joint P(4,11) -// actualJoint = bayesTree.jointBayesNet(4, 11, EliminateDiscrete); -// EXPECT_DOUBLES_EQUAL(joint_4_11, evaluate(*actualJoint,all1), 1e-9); -// -//} + +#include + +using namespace std; +using namespace gtsam; + +static bool debug = false; + +// /** +// * Custom clique class to debug shortcuts +// */ +// struct Clique : public BayesTreeCliqueBase { +// typedef BayesTreeCliqueBase Base; +// typedef boost::shared_ptr shared_ptr; + +// // Constructors +// Clique() {} +// explicit Clique(const DiscreteConditional::shared_ptr& conditional) +// : Base(conditional) {} +// Clique(const std::pair& +// result) +// : Base(result) {} + +// /// print index signature only +// void printSignature( +// const std::string& s = "Clique: ", +// const KeyFormatter& indexFormatter = DefaultKeyFormatter) const { +// ((IndexConditionalOrdered::shared_ptr)conditional_) +// ->print(s, indexFormatter); +// } + +// /// evaluate value of sub-tree +// double evaluate(const DiscreteConditional::Values& values) { +// double result = (*(this->conditional_))(values); +// // evaluate all children and multiply into result +// for (boost::shared_ptr c : children_) result *= +// c->evaluate(values); return result; +// } +// }; + +// typedef BayesTreeOrdered DiscreteBayesTree; + +/* ************************************************************************* */ + +TEST_UNSAFE(DiscreteBayesTree, thinTree) { + const int nrNodes = 15; + const size_t nrStates = 2; + + // define variables + vector key; + for (int i = 0; i < nrNodes; i++) { + DiscreteKey key_i(i, nrStates); + key.push_back(key_i); + } + + // create a thin-tree Bayesnet, a la Jean-Guillaume + DiscreteBayesNet bayesNet; + bayesNet.add(key[14] % "1/3"); + + bayesNet.add(key[13] | key[14] = "1/3 3/1"); + bayesNet.add(key[12] | key[14] = "3/1 3/1"); + + bayesNet.add((key[11] | key[13], key[14]) = "1/4 2/3 3/2 4/1"); + bayesNet.add((key[10] | key[13], key[14]) = "1/4 3/2 2/3 4/1"); + bayesNet.add((key[9] | key[12], key[14]) = "4/1 2/3 F 1/4"); + bayesNet.add((key[8] | key[12], key[14]) = "T 1/4 3/2 4/1"); + + bayesNet.add((key[7] | key[11], key[13]) = "1/4 2/3 3/2 4/1"); + bayesNet.add((key[6] | key[11], key[13]) = "1/4 3/2 2/3 4/1"); + bayesNet.add((key[5] | key[10], key[13]) = "4/1 2/3 3/2 1/4"); + bayesNet.add((key[4] | key[10], key[13]) = "2/3 1/4 3/2 4/1"); + + bayesNet.add((key[3] | key[9], key[12]) = "1/4 2/3 3/2 4/1"); + bayesNet.add((key[2] | key[9], key[12]) = "1/4 8/2 2/3 4/1"); + bayesNet.add((key[1] | key[8], key[12]) = "4/1 2/3 3/2 1/4"); + bayesNet.add((key[0] | key[8], key[12]) = "2/3 1/4 3/2 4/1"); + + if (debug) { + GTSAM_PRINT(bayesNet); + bayesNet.saveGraph("/tmp/discreteBayesNet.dot"); + } + + // create a BayesTree out of a Bayes net + auto bayesTree = DiscreteFactorGraph(bayesNet).eliminateMultifrontal(); + if (debug) { + GTSAM_PRINT(*bayesTree); + bayesTree->saveGraph("/tmp/discreteBayesTree.dot"); + } + + auto R = bayesTree->roots().front(); + + // Check whether BN and BT give the same answer on all configurations + vector allPosbValues = cartesianProduct( + key[0] & key[1] & key[2] & key[3] & key[4] & key[5] & key[6] & key[7] & + key[8] & key[9] & key[10] & key[11] & key[12] & key[13] & key[14]); + for (size_t i = 0; i < allPosbValues.size(); ++i) { + DiscreteFactor::Values x = allPosbValues[i]; + double expected = bayesNet.evaluate(x); + double actual = R->evaluate(x); + DOUBLES_EQUAL(expected, actual, 1e-9); + } + + // Calculate all some marginals + Vector marginals = zero(15); + double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0, + joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0, + joint_4_11 = 0; + for (size_t i = 0; i < allPosbValues.size(); ++i) { + DiscreteFactor::Values x = allPosbValues[i]; + double px = R->evaluate(x); + for (size_t i = 0; i < 15; i++) + if (x[i]) marginals[i] += px; + // calculate shortcut 8 and 0 + if (x[12] && x[14]) joint_12_14 += px; + if (x[9] && x[12] & x[14]) joint_9_12_14 += px; + if (x[8] && x[12] & x[14]) joint_8_12_14 += px; + if (x[8] && x[12]) joint_8_12 += px; + if (x[8] && x[2]) joint82 += px; + if (x[1] && x[2]) joint12 += px; + if (x[2] && x[4]) joint24 += px; + if (x[4] && x[5]) joint45 += px; + if (x[4] && x[6]) joint46 += px; + if (x[4] && x[11]) joint_4_11 += px; + } + DiscreteFactor::Values all1 = allPosbValues.back(); + + + // check separator marginal P(S0) + auto c = (*bayesTree)[0]; + DiscreteFactorGraph separatorMarginal0 = + c->separatorMarginal(EliminateDiscrete); + EXPECT_DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); + + // // check separator marginal P(S9), should be P(14) + // c = (*bayesTree)[9]; + // DiscreteFactorGraph separatorMarginal9 = + // c->separatorMarginal(EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); + + // // check separator marginal of root, should be empty + // c = (*bayesTree)[11]; + // DiscreteFactorGraph separatorMarginal11 = + // c->separatorMarginal(EliminateDiscrete); + // EXPECT_LONGS_EQUAL(0, separatorMarginal11.size()); + + // // check shortcut P(S9||R) to root + // c = (*bayesTree)[9]; + // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); + // EXPECT_LONGS_EQUAL(0, shortcut.size()); + + // // check shortcut P(S8||R) to root + // c = (*bayesTree)[8]; + // shortcut = c->shortcut(R, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint_12_14 / marginals[14], evaluate(shortcut, all1), + // 1e-9); + + // // check shortcut P(S2||R) to root + // c = (*bayesTree)[2]; + // shortcut = c->shortcut(R, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint_9_12_14 / marginals[14], evaluate(shortcut, + // all1), + // 1e-9); + + // // check shortcut P(S0||R) to root + // c = (*bayesTree)[0]; + // shortcut = c->shortcut(R, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint_8_12_14 / marginals[14], evaluate(shortcut, + // all1), + // 1e-9); + + // // calculate all shortcuts to root + // DiscreteBayesTree::Nodes cliques = bayesTree->nodes(); + // for (auto c : cliques) { + // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); + // if (debug) { + // c->printSignature(); + // shortcut.print("shortcut:"); + // } + // } + + // // Check all marginals + // DiscreteFactor::shared_ptr marginalFactor; + // for (size_t i = 0; i < 15; i++) { + // marginalFactor = bayesTree->marginalFactor(i, EliminateDiscrete); + // double actual = (*marginalFactor)(all1); + // EXPECT_DOUBLES_EQUAL(marginals[i], actual, 1e-9); + // } + + // DiscreteBayesNet::shared_ptr actualJoint; + + // Check joint P(8,2) TODO: not disjoint ! + // actualJoint = bayesTree->jointBayesNet(8, 2, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint82, evaluate(*actualJoint,all1), 1e-9); + + // Check joint P(1,2) TODO: not disjoint ! + // actualJoint = bayesTree->jointBayesNet(1, 2, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint12, evaluate(*actualJoint,all1), 1e-9); + + // Check joint P(2,4) + // actualJoint = bayesTree->jointBayesNet(2, 4, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint24, evaluate(*actualJoint, all1), 1e-9); + + // Check joint P(4,5) TODO: not disjoint ! + // actualJoint = bayesTree->jointBayesNet(4, 5, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); + + // Check joint P(4,6) TODO: not disjoint ! + // actualJoint = bayesTree->jointBayesNet(4, 6, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); + + // Check joint P(4,11) + // actualJoint = bayesTree->jointBayesNet(4, 11, EliminateDiscrete); + // EXPECT_DOUBLES_EQUAL(joint_4_11, evaluate(*actualJoint, all1), 1e-9); +} /* ************************************************************************* */ int main() { @@ -263,4 +247,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - From eb1a2b8fb3a6b3656da0acd1efc982f5fe6cc3c3 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 12 Jul 2020 14:31:29 -0400 Subject: [PATCH 165/199] modified test --- tests/testNonlinearOptimizer.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/tests/testNonlinearOptimizer.cpp b/tests/testNonlinearOptimizer.cpp index 5d4c3f844..a549dc726 100644 --- a/tests/testNonlinearOptimizer.cpp +++ b/tests/testNonlinearOptimizer.cpp @@ -459,11 +459,12 @@ TEST(NonlinearOptimizer, RobustMeanCalculation) { init.insert(0, 100.0); expected.insert(0, 3.33333333); - LevenbergMarquardtParams params; + DoglegParams params_dl; + params_dl.setRelativeErrorTol(1e-10); auto gn_result = GaussNewtonOptimizer(fg, init).optimize(); - auto lm_result = LevenbergMarquardtOptimizer(fg, init, params).optimize(); - auto dl_result = DoglegOptimizer(fg, init).optimize(); + auto lm_result = LevenbergMarquardtOptimizer(fg, init).optimize(); + auto dl_result = DoglegOptimizer(fg, init, params_dl).optimize(); EXPECT(assert_equal(expected, gn_result, tol)); EXPECT(assert_equal(expected, lm_result, tol)); From 3f4bf163e73a5f04cb8291e40fc1892ab80bb83e Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 14:59:17 -0400 Subject: [PATCH 166/199] Checked in pdf for easy reference --- gtsam/discrete/tests/testDiscreteBayesTree.pdf | Bin 0 -> 10622 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 gtsam/discrete/tests/testDiscreteBayesTree.pdf diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.pdf b/gtsam/discrete/tests/testDiscreteBayesTree.pdf new file mode 100644 index 0000000000000000000000000000000000000000..e8167d455477f97aadb2101d26120a6c145891f5 GIT binary patch literal 10622 zcma)i2RK~a^S>5?=p|~bPPEvu87l@l5hq-FA~Taz0X!;D zXB&5006&7Hg#!Qpc;xIH-Jx*A(-Gnhy$iL3SwV5c#c|x+;ZTSZ&i#ym6xG-nfg2&) z-^s*TB<~T)Dken$La#-jq59a?RRcmTBJ!>$$b6K!d|;-Pw=p{v+e6>N@FAQ%os>(Q zfqj%}cROMy(b81iEU78^rDfB%`o=TH61qzh+iwJxu-#)j@8bv2^d%3uNhi(p3b-6+ zCPpTBv|k#nq)v=g58W;`G8yd*a7*kPO@rfd6~<}dHtf8siRb}(rJ>!5%~!9Yc_D0^ zwaiD@AJCzTKbJZ2X|wA4X^rV8&L=Wape4sriH;|NALi@}9r87N)yF2&dHRY7?(N<# zc{AsyKi80*JZ4&Uaj~<9({y{3d-5CH_w@Vn=HBQ)<0}<0_ZnFmk8$I*w~k`%cwo~Z zGo2FkHACiGURroYJ$)qtm}4t;$y#qZcy*QPG>xD6y_4-&jVz=U`xZgQ*%;VLivU&`1}PK||UGDx>Q9u{jm6CK^L<*ef=hu#&~d?MMFK0N61HO}zUJ&=~I zQ(c27RxUr^!&h|0#L@BZ9bSE#;C(jPl;qa1&OH9OoWFy~TICU0^n>N0_8!tDb(^^L zQ6<`>wqX%AqIE!!!LCCYu$Rb&C@!u|JFlUyBY<_)m~dE`QT0%8~vExZX+ zAFzh4`VJ?)w<`oW7Mt@pqw+*QdO}0Is1w1+QhG&*zoQ(QF&duh}O4`A5 ziXXedCD!QVCdr})CAW2IhEbzb1s}PZ8E>wvc60;DQ=ZAmwcTvG$?COS#J1uQ3@563b2~v#|h8Mf<{^7lySTh6}mgo7&Asw zs$HAGxO`q7B{vzGdlEi^7uls`En=nPtHkrkQrLkeXnNT^3Xy4Z4}AwbsvdfBalZYSCHT-%@((y{Wv=^{RXZJEnRT-GHFC zFMCL-xfmV0*>V;h_B84436?Jh>hv!w5GO7$3~TM#T=!^GYdW+F%1=a04rkZrd1+OjkJTJz=V{Ag-9U zbuKC(D@nkP#MCPx`jEme7{;V;Z|KTTt&#h}B;iQW)^&W$GuMu$a!rB5r_bNDD(FS> zeqga(y~`HCuJos@(mYjQ|O03%skp*OOSb`dMX?iL1lGln~KStlaEifwy{h@mK{Ayf{@b_qBR#0a1=YcrdLu@KKix(-Z>@-tJTOci==dV7S zGgCyl)$nx_;qAplsAw#@$x^8ndsf=`2%%}tD#zjKDeH?<8(^nl0l1{1jF*_hQk|0l z)MY*(W*(N3+h5#r4FetDX$H=ajozs_CF^?jKnnZzr$USl)}|7g!IWDQ!Xt0URVl?v z{LE9~4_;S8Pp!YG9~yZom%nF!t$Of1Y93zT)j(=5!p(i6h$-Cc+OrpKJD-pb6)*TxgamkH{R26h_y?62XO`SK0`}BFIfCQa!+#Qz{sV?y6xJ?HsQsao% zj!!I$p3rp?Tc6SZ4ylxT8^k1)<#uo5IXs%JlqIiZj*SBtuu3uJF6tOZzZ2{os+~UE zTi=t&oqBd12kLC~GglzKA+roJwIH8}*LlMJ+e)Z*1g<9D`q+#~~MhFrRz|SuX z-~;jjOs=?P5TYR1-2lkc`Xi6Z!(kpSe-rP=99Ps|>(fTe42L+oxgh7V^!`Ow1h~UJ zpubu&2(G(OPdiJfmb^5Q_;dAIP&b$d+!E>rKx$I!Zz~f*wEvafg@23nU+EpGsvo}t zKmZ|LKB0f)`%OV_KW*K2pM;O+90!~d1niQy71LNuM);g$3?uRzg7YN%w6e`P$PK6M z*`LhfNE^r{X<6O1BGK#%qvpUUCtTR}hdTGj8vs{Ylu7^d`lV{FQp$;Fnk-a}Ptz0AV|(XcI|yT1{=~&Zd6bo52_@i%jbQV&UM+Ha~VdEc=|28@(@y?G_-3UQh|g1 zBCbePE;kqqNqBg-czHl>G}4OlLyu)1YRICL6bq&i`m^VJOW2(W*!M6?;yIkXq{KPx zA29`~J+tEb@D18tO1%uv>sx&AB6g5Pn;bvO#1z_Fp)vr#9Wxetap8IKm_~qERnHxF z-{k@1mB3OBo3H-?M?s5@khR$}C;Se+n2gRDqE$=HgLBB=`l( zeutzc*r&eCf0<`&e}cz7&=dNirw9!5?U3pE(yD;d2+xxGgAS#D6W z;@@v-Oi-vLLSIcV#S5|!<>Z3#gUCOm*Ju9;-O%jWn)hSKF}ho2vQzbAzh`p`!XYy z(d^Yqe5rN?PQEmrQgDJLWj`?1TqXNS*@_5rI94nCTq;_OpXLQl7#4G2CM1lDG03eS;$(Jl?PSu}Qci zi^zHONH12}fc@-73U7_N#%D-_xk)EsOmewW?~Y`50!Eh2bprbkUDTG9J8DVubNMWF zF)u09^7Voh)3P6b>-9TgOsarr9n`C`bo)S~HiUEoFvr*$SxiYU?c0_@Mp~3LOk>g~ zpK6(?*lW6s1(A`pyp_8l&0NlU<}My2^L1$Io4aAVWFrOtdUBJW)ecjgM_Gh{m($W& z_o&shkK*^P=MS0EQ*7w*`FC;I`Q+&*mnatcDK5`4PHJdkA_dd?Uu;a0`&E13*FBQeCdOwQ*1vV!8}i53D_fN}D?Ge8Fj1FQ(D$-&qQnsgHnfR}Hb1+PKS_I_ERB zb*~67116)k;BBCsW$n=y%Nzw9)^EX3pS8>$uL4Jvxs(d|I$m%2Uerz8DT()u*$r{D z&t3r2RhBuaWhl4@H~7Nwg55@5-zS#fp37VDaAV0@$D|#GRM70Td)S26&i8Z}Q-(1s zojyuo#4A9(fytNkq}x`VJsD&)Vj>LY+K$){0%LL1hU}AgSl83(OyNkx+m%x(k%ClR z%s6h7yU~qaOJwM=p~n>K$h?7$&5NnoVIdFJ4UCOxRPX5BniBFoeZI+h`KHG5urQ`e z*Qw>{_-0X6%&R2G7P<{)%y9ey*Q+Xnuh&0*s@^P(;;7ipoQjpF5jI#S? zR1B?=`ZiATHQcl}J)R;G2Iq>q0fE%>2J{D=TB$LNN_*Lt*q5vss4#gi^ zGP6|Pj%hEXz~qeTdCi+Xuk$!@73#Ji9Q2?`7R9$BZFQo-mfVeCz$s}54VB9~roGDFS$m<7J5XKdqO2}qTGfUSg6 z;agHCg`GtQeVx}Q>Mu~4k6NEwFj~?nE|VB+2da+NJ9~Yh6BIk_`y?w6CrHgou1{`! zUL60LiA&w-VOjqD^1V@+ug4p)8IiBMi|)yPN70I6{+u<^#cvUn-y%T&jdCyej6`hz z_64RmY5~fHG4}hYd)+>xH79dSS)Qz6nwHugM(r=l4JsBW9L>?IEha}#&-wNTqo$sgMW+LK%f?xHmSZVdQdrsz(qe*F&pJ@%ab(%FsYbUZ%HzOiOu(-J+ zmUQ&w-1WU>W2uePF>3c|kyC*WeeuGUc(%3tC0x zD6f>HJKGRJxAo|{4EYqs4b3g@^E!ij1`g!ukUie02wiBJx0@WhNULs|H?CltXdAd~ za`3I&=CY@9ojSF~i7`veI0X}7@{q&QypNmrz|6tdRpaihfr6=(YxIM#lytZb=oreg z8!@*-AOqvO(LQprH&oR|(P!2p7%c2v=vizU?pxBEOGvw4dmCo_j{9OJL4@j}MYro7Ow8Zve63*b-G^HJfCt6{#UaKg z_vqbZz;nb0m}q<-yH`gKLxifdEZ^Ajr!iyq^dwn1mK%FIr;y^C>1QN|wR0{S=%qk()0_Q_nguVMAd)WnNpc{r zRyM9@Zgt&f^qqxGPF!&o=m&|Y(j)?i=nUG69Gol`%WNzbX>9kn_&BKt*JKGFhkn5r z)W^q-drQ34mb?$SPk)9JL)J1%7*a$bTzKE?r409RGy3r85N=Z_$FTqK`xdPA_<6qr zuagJHLHao4e#sa)wB*DDCRDT6p*3^P_ff?Gio;-FGmtG9Wd`4A2z4JqJ8v4ezayY1 z={^H9)3 zHX(DNsDvHgFZ3U^g+=F2vN@J*ru4`A%+8E>k#@W)({=P%dxczhdwdZKXop9bHmT8rbD>Tzm)#lzAxAH>mQcw$`3a!%0 z9;YPsdoMdJ%PhlQ2b=Vkm|q5q^_iOUls~jCg&T4|OYc-oPPJmLP@8%%MSp61TDgZi z6f5um-{b5{DP_`V<^i?7Y?pb~mqyixYF*D+-*wYh&~Y77bZ!DUw=IdvNX<1Nr`Xd# zEZpm<+%_SMv(A+T`2|cy{Vcm{$tl^R_VeBz8A^q5eLIE9*o&C7Pov+)6@l8{(O7o* zv^VBrW2HR+4pCHm(O8PLlYT1~-hX7Ngvt&(7g3^@V>f=mWN5_x#0Tyq70Pv>*9^f; zG-8>A_$oJR!f^2vHnFvQi^i7AovIfwjE2U@%YqehxhP(3IId$0V8+dYP@@a>7A;(| z`RDI;(o@Wijay3tv@m4Ix}X7xOU0M;4lv1&YTo_qslj7=uld2z2df<7v4e%UrMvGliZ|xhoi-& ziG(=Xg{$z5-jhkn3u883>?({7h4mLUpjl|Ue?1J7ywDK2ky<+r(U=%JB-$H21BRCn z$N&y0vcUbXQ^N*{+aPKvHkMdC`EgGzyY$pbiiz_}NWWRHmmfwstd{FePY->0tsNL< zyIFYr{Eqhevbl+o4FUFH&t!V>;UQyOtkGhdlAq67yv#XasAo7jnBwm9nHhV&_@V-5 zxQVSQK$r<*ZJ3Edg4JP7nsqqh@K9l?mYcn`M7V%Hbzj3;9bcdx#H}5VRq=9rHT;m~ zXs9PEYw;F{z~UP)poxw!1hW+YYSzF`p$0@vA>82$1^IBVw&fA^-c5zFW+w&pO?FXV>m>ZnU zT_@w(kE)6E=97b;#V0jeUYE!B$3F4+d@o=>!d%2P-g^;T{2Xf~xnEBpdbY1Peo2vI zr|kO8IrawBH~P+KahIl^IG@lkayz1hSIPN$&BlmTx!5I=Rc{qCOJ7rO?C3ewa!Rx> z)zMlvwbx5vnOFN;ak(ruMFr|NjA zIu{jQCv)L>yWMd_)k{xm#)9i&g&M=z9DhxywUu*Y{4-7^Q%qtRYsnqOwI$0^8sAf` z_mM^3X*K|Xj=F^ zoDjAkQMP;2@uETCK~=PblzZ+E@ur0&(p$5;1#$s|OA z-z$7c)II?kc<5BBR_dZFIo_J8&W!uN_$BF;6Qy2r~YxZcDS4WGQQ zoC~Zu2nnWrtH=Z(;Uw6b=Qfm`eUPGUqOS1dMr7<{=`k0Rm30Sql4s& z)8hsb>Vc_qFp~|EdtsG>vN4;r;}h02bBwmHy=yxr3g;FkdgeMN6w9A>USk4IoCoF& zPNJE`+ZXQ?7|JI#KpWT}r5zY4x37MifRuOO?lT?Y^mZD}zP#l-mZoiFuG+;M{<&PO z&O}^UT-B8GxNm=nyH-1kMg8eI88%KagK3W5OH!O*m6qE;XRLm-ib4$yG=?x zJa)DgXIB4)hVfavdSHO%qBhZ(Z4X;NRg)AystgjjcA9#Uh;DUP zlx=YZ4cavB-2g`#9GW0QA^@Es#uNkHjVXq3NA0NoNaHw809yP8@qK16PXkkY19QTm zhYc3G|I`#Qb~4s1v7%ryYeII5Wy05mG0A6>9GZpFOlAopW@HHz`ASiK;!N!O;Y|L) z;!G?1WJjlSf;)!jIaM)_iea5|)Y-=oE0i&kbQ^dR z6Nj5*hUnjTA5)Gj?GJ@;MFvV3I*cAxkvr9*R&p^^%FY{72MS7J$sS<37H8M!X&5^M zl}Q;Yk8ugvti5CwJmG3sh)GpW>VJHRLa)1w`zJ7fJe2+k4DbsA1%4gOgOJDT|2n@0 z{dEriUkBKTBk|w(w8`**^J4%Z%4ZREP}e4eaqT-xXWo>l=mBe$Kg#1_=0eFhv6CZO z^Ga184RLDy%wXXb=hDF^%(^U>9%Rkq;=rHasK<9@5?g;gSKcc6K}I!^4>S#9J5$I zW*~!!$a>RGa6SE&d16Q_{qzXxtY{bevB+l=*&H470 z%|%Lhy|?;;!p-<)Le^|N@vUBin?)o0xEk2uqFn+yDtAOmqxfZEyEB7hsjFjrl)-Jwo;0HGfpkPU@j4dmJo-UI~$kci3O5fmhd z^veT(;5JC!AH#WAxL=_~ItYvg`Rkjb`@$#aV2S{5dCCP;(NluZ1ii&fi95$wbQ_yHR^!Li!w!?1n|Hs0k?r#dkVe7s+OHtnYN6 z;fISji)bju;f!tzrN1?vJIwUNqjqtFJS zll{lMzuXOBZIICKX_2tyKb`O&hQDiPZ4E`@h6n`E2ngUo+#r*`p@5*jU_cz?+beq^ zph+GO0)|Bl{SRCI3dMh0A{gm5KcLM2WlNJdRp)lVjo{;q*1lB>jGjBvuL{yR&vFaI zP+C}I(@@~u4AngJxjJiTR{L`{Vw|vV%5;91r!B+yPg+hNsVEyy5l8Wz0@BEbK3=S> zIoTvW=G-acN?jJOVS9(aXhW3TPi>q9iaB6Hk!<88J_oieoeR*Yx226_TH{bY8KR0a zraZPENl(SL3N95RpZ&UNSSHamnRI=6T2P*eIzGvYvmBcwT#X$s)6Gz$`JtgNVQ!^F zi24f|leK~|rK(qOf-Z5$a5MP9a!61Z1en88}5mX`Wa62UOj7)T0MU^f%>QGK z-&ixEWDMzI2uJ-#Z1@2$|Ann1<@=}WBC&P1t5qx8Ss}yKRebx6o_ipn_P;qV`0pbi zR$}F0iKt0qvxL~eVE_;}NPrs%V6%01cX7MJgQyHZP;KB47h5|^H*Of*hW$svkwH|f zx!b{8Sfk5`ZPx@#2lYt;o5X|OE@T(>KEC~2( zsrTVfYaAc|%!>p3eE|gc`FZ&P)_|WhVIe+**^n2&`4iq_&+86lq_i&uhV8?f@j?&&a6gYz+fkIqOw8b#sTn-LE_XF`giz+>%*VT@L5} E0IK=vy8r+H literal 0 HcmV?d00001 From 968b207135bede702bcedd1f6398642fcc7547f6 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 14:59:43 -0400 Subject: [PATCH 167/199] added printSignature and evaluate --- gtsam/discrete/DiscreteBayesTree.cpp | 10 ++++ gtsam/discrete/DiscreteBayesTree.h | 85 ++++++++++++++++------------ gtsam/discrete/DiscreteConditional.h | 9 +++ gtsam/inference/Conditional.h | 3 +- 4 files changed, 71 insertions(+), 36 deletions(-) diff --git a/gtsam/discrete/DiscreteBayesTree.cpp b/gtsam/discrete/DiscreteBayesTree.cpp index 8fcc34e25..990d10dbe 100644 --- a/gtsam/discrete/DiscreteBayesTree.cpp +++ b/gtsam/discrete/DiscreteBayesTree.cpp @@ -45,6 +45,16 @@ namespace gtsam { return Base::equals(other, tol); } + /* ************************************************************************* */ + double DiscreteBayesTree::evaluate( + const DiscreteConditional::Values& values) const { + double result = 1.0; + for (const auto& root : roots_) { + result *= root->evaluate(values); + } + return result; + } + } // \namespace gtsam diff --git a/gtsam/discrete/DiscreteBayesTree.h b/gtsam/discrete/DiscreteBayesTree.h index aa8f4657c..3d6e016fd 100644 --- a/gtsam/discrete/DiscreteBayesTree.h +++ b/gtsam/discrete/DiscreteBayesTree.h @@ -11,7 +11,8 @@ /** * @file DiscreteBayesTree.h - * @brief Discrete Bayes Tree, the result of eliminating a DiscreteJunctionTree + * @brief Discrete Bayes Tree, the result of eliminating a + * DiscreteJunctionTree * @brief DiscreteBayesTree * @author Frank Dellaert * @author Richard Roberts @@ -22,48 +23,62 @@ #include #include #include +#include #include +#include + namespace gtsam { - // Forward declarations - class DiscreteConditional; - class VectorValues; +// Forward declarations +class DiscreteConditional; +class VectorValues; - /* ************************************************************************* */ - /** A clique in a DiscreteBayesTree */ - class GTSAM_EXPORT DiscreteBayesTreeClique : - public BayesTreeCliqueBase - { - public: - typedef DiscreteBayesTreeClique This; - typedef BayesTreeCliqueBase Base; - typedef boost::shared_ptr shared_ptr; - typedef boost::weak_ptr weak_ptr; - DiscreteBayesTreeClique() {} - DiscreteBayesTreeClique(const boost::shared_ptr& conditional) : Base(conditional) {} +/* ************************************************************************* */ +/** A clique in a DiscreteBayesTree */ +class GTSAM_EXPORT DiscreteBayesTreeClique + : public BayesTreeCliqueBase { + public: + typedef DiscreteBayesTreeClique This; + typedef BayesTreeCliqueBase + Base; + typedef boost::shared_ptr shared_ptr; + typedef boost::weak_ptr weak_ptr; + DiscreteBayesTreeClique() {} + DiscreteBayesTreeClique( + const boost::shared_ptr& conditional) + : Base(conditional) {} - //** evaluate conditional probability of subtree for given Values */ - double evaluate(const DiscreteConditional::Values & values) const; - }; + /// print index signature only + void printSignature( + const std::string& s = "Clique: ", + const KeyFormatter& formatter = DefaultKeyFormatter) const { + conditional_->printSignature(s, formatter); + } - /* ************************************************************************* */ - /** A Bayes tree representing a Discrete density */ - class GTSAM_EXPORT DiscreteBayesTree : - public BayesTree - { - private: - typedef BayesTree Base; + //** evaluate conditional probability of subtree for given Values */ + double evaluate(const DiscreteConditional::Values& values) const; +}; - public: - typedef DiscreteBayesTree This; - typedef boost::shared_ptr shared_ptr; +/* ************************************************************************* */ +/** A Bayes tree representing a Discrete density */ +class GTSAM_EXPORT DiscreteBayesTree + : public BayesTree { + private: + typedef BayesTree Base; - /** Default constructor, creates an empty Bayes tree */ - DiscreteBayesTree() {} + public: + typedef DiscreteBayesTree This; + typedef boost::shared_ptr shared_ptr; - /** Check equality */ - bool equals(const This& other, double tol = 1e-9) const; - }; + /** Default constructor, creates an empty Bayes tree */ + DiscreteBayesTree() {} -} + /** Check equality */ + bool equals(const This& other, double tol = 1e-9) const; + + //** evaluate probability for given Values */ + double evaluate(const DiscreteConditional::Values& values) const; +}; + +} // namespace gtsam diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 3da8d0a82..225e6e1d3 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -24,6 +24,8 @@ #include #include +#include + namespace gtsam { /** @@ -92,6 +94,13 @@ public: /// @name Standard Interface /// @{ + /// print index signature only + void printSignature( + const std::string& s = "Discrete Conditional: ", + const KeyFormatter& formatter = DefaultKeyFormatter) const { + static_cast(this)->print(s, formatter); + } + /// Evaluate, just look up in AlgebraicDecisonTree virtual double operator()(const Values& values) const { return Potentials::operator()(values); diff --git a/gtsam/inference/Conditional.h b/gtsam/inference/Conditional.h index 1d486030c..295122879 100644 --- a/gtsam/inference/Conditional.h +++ b/gtsam/inference/Conditional.h @@ -65,6 +65,8 @@ namespace gtsam { Conditional(size_t nrFrontals) : nrFrontals_(nrFrontals) {} /// @} + + public: /// @name Testable /// @{ @@ -76,7 +78,6 @@ namespace gtsam { /// @} - public: /// @name Standard Interface /// @{ From ae808d039cda45df8334d1857773c9c06c2943a0 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 15:00:34 -0400 Subject: [PATCH 168/199] Fixed link issue --- gtsam/discrete/tests/testDiscreteFactorGraph.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp index 0fbf44097..7a0e1eaf7 100644 --- a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp +++ b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp @@ -19,6 +19,7 @@ #include #include #include +#include #include From d456dddc6f1860f76b3ff8a7be555d55a430fb6d Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 15:00:54 -0400 Subject: [PATCH 169/199] Cleaned up formatting --- gtsam/inference/BayesTreeCliqueBase-inst.h | 54 ++++++++++++---------- 1 file changed, 29 insertions(+), 25 deletions(-) diff --git a/gtsam/inference/BayesTreeCliqueBase-inst.h b/gtsam/inference/BayesTreeCliqueBase-inst.h index e762786f5..a02fe274e 100644 --- a/gtsam/inference/BayesTreeCliqueBase-inst.h +++ b/gtsam/inference/BayesTreeCliqueBase-inst.h @@ -136,57 +136,61 @@ namespace gtsam { } } - /* ************************************************************************* */ + /* *********************************************************************** */ // separator marginal, uses separator marginal of parent recursively // P(C) = P(F|S) P(S) - /* ************************************************************************* */ - template + /* *********************************************************************** */ + template typename BayesTreeCliqueBase::FactorGraphType - BayesTreeCliqueBase::separatorMarginal(Eliminate function) const - { + BayesTreeCliqueBase::separatorMarginal( + Eliminate function) const { gttic(BayesTreeCliqueBase_separatorMarginal); // Check if the Separator marginal was already calculated - if (!cachedSeparatorMarginal_) - { + if (!cachedSeparatorMarginal_) { gttic(BayesTreeCliqueBase_separatorMarginal_cachemiss); + // If this is the root, there is no separator - if (parent_.expired() /*(if we're the root)*/) - { + if (parent_.expired() /*(if we're the root)*/) { // we are root, return empty FactorGraphType empty; cachedSeparatorMarginal_ = empty; - } - else - { + } else { + // Flatten recursion in timing outline + gttoc(BayesTreeCliqueBase_separatorMarginal_cachemiss); + gttoc(BayesTreeCliqueBase_separatorMarginal); + // Obtain P(S) = \int P(Cp) = \int P(Fp|Sp) P(Sp) // initialize P(Cp) with the parent separator marginal derived_ptr parent(parent_.lock()); - gttoc(BayesTreeCliqueBase_separatorMarginal_cachemiss); // Flatten recursion in timing outline - gttoc(BayesTreeCliqueBase_separatorMarginal); - FactorGraphType p_Cp(parent->separatorMarginal(function)); // P(Sp) + FactorGraphType p_Cp(parent->separatorMarginal(function)); // P(Sp) + gttic(BayesTreeCliqueBase_separatorMarginal); gttic(BayesTreeCliqueBase_separatorMarginal_cachemiss); + // now add the parent conditional - p_Cp += parent->conditional_; // P(Fp|Sp) + p_Cp += parent->conditional_; // P(Fp|Sp) // The variables we want to keepSet are exactly the ones in S - KeyVector indicesS(this->conditional()->beginParents(), this->conditional()->endParents()); - cachedSeparatorMarginal_ = *p_Cp.marginalMultifrontalBayesNet(Ordering(indicesS), function); + KeyVector indicesS(this->conditional()->beginParents(), + this->conditional()->endParents()); + auto separatorMarginal = + p_Cp.marginalMultifrontalBayesNet(Ordering(indicesS), function); + cachedSeparatorMarginal_.reset(*separatorMarginal); } } // return the shortcut P(S||B) - return *cachedSeparatorMarginal_; // return the cached version + return *cachedSeparatorMarginal_; // return the cached version } - /* ************************************************************************* */ - // marginal2, uses separator marginal of parent recursively + /* *********************************************************************** */ + // marginal2, uses separator marginal of parent // P(C) = P(F|S) P(S) - /* ************************************************************************* */ - template + /* *********************************************************************** */ + template typename BayesTreeCliqueBase::FactorGraphType - BayesTreeCliqueBase::marginal2(Eliminate function) const - { + BayesTreeCliqueBase::marginal2( + Eliminate function) const { gttic(BayesTreeCliqueBase_marginal2); // initialize with separator marginal P(S) FactorGraphType p_C = this->separatorMarginal(function); From 468c7aee0cd9b5933178b7304a6acce34eeb8692 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 15:01:00 -0400 Subject: [PATCH 170/199] Fixed tests --- .../discrete/tests/testDiscreteBayesTree.cpp | 191 ++++++++---------- 1 file changed, 81 insertions(+), 110 deletions(-) diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index f58fd2b19..150a41c24 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -33,41 +33,6 @@ using namespace gtsam; static bool debug = false; -// /** -// * Custom clique class to debug shortcuts -// */ -// struct Clique : public BayesTreeCliqueBase { -// typedef BayesTreeCliqueBase Base; -// typedef boost::shared_ptr shared_ptr; - -// // Constructors -// Clique() {} -// explicit Clique(const DiscreteConditional::shared_ptr& conditional) -// : Base(conditional) {} -// Clique(const std::pair& -// result) -// : Base(result) {} - -// /// print index signature only -// void printSignature( -// const std::string& s = "Clique: ", -// const KeyFormatter& indexFormatter = DefaultKeyFormatter) const { -// ((IndexConditionalOrdered::shared_ptr)conditional_) -// ->print(s, indexFormatter); -// } - -// /// evaluate value of sub-tree -// double evaluate(const DiscreteConditional::Values& values) { -// double result = (*(this->conditional_))(values); -// // evaluate all children and multiply into result -// for (boost::shared_ptr c : children_) result *= -// c->evaluate(values); return result; -// } -// }; - -// typedef BayesTreeOrdered DiscreteBayesTree; - /* ************************************************************************* */ TEST_UNSAFE(DiscreteBayesTree, thinTree) { @@ -124,24 +89,24 @@ TEST_UNSAFE(DiscreteBayesTree, thinTree) { for (size_t i = 0; i < allPosbValues.size(); ++i) { DiscreteFactor::Values x = allPosbValues[i]; double expected = bayesNet.evaluate(x); - double actual = R->evaluate(x); + double actual = bayesTree->evaluate(x); DOUBLES_EQUAL(expected, actual, 1e-9); } - // Calculate all some marginals + // Calculate all some marginals for Values==all1 Vector marginals = zero(15); double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0, joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0, - joint_4_11 = 0; + joint_4_11 = 0, joint_11_13 = 0, joint_11_13_14 = 0, + joint_11_12_13_14 = 0, joint_9_11_12_13 = 0, joint_8_11_12_13 = 0; for (size_t i = 0; i < allPosbValues.size(); ++i) { DiscreteFactor::Values x = allPosbValues[i]; - double px = R->evaluate(x); + double px = bayesTree->evaluate(x); for (size_t i = 0; i < 15; i++) if (x[i]) marginals[i] += px; - // calculate shortcut 8 and 0 if (x[12] && x[14]) joint_12_14 += px; - if (x[9] && x[12] & x[14]) joint_9_12_14 += px; - if (x[8] && x[12] & x[14]) joint_8_12_14 += px; + if (x[9] && x[12] && x[14]) joint_9_12_14 += px; + if (x[8] && x[12] && x[14]) joint_8_12_14 += px; if (x[8] && x[12]) joint_8_12 += px; if (x[8] && x[2]) joint82 += px; if (x[1] && x[2]) joint12 += px; @@ -149,96 +114,102 @@ TEST_UNSAFE(DiscreteBayesTree, thinTree) { if (x[4] && x[5]) joint45 += px; if (x[4] && x[6]) joint46 += px; if (x[4] && x[11]) joint_4_11 += px; + if (x[11] && x[13]) { + joint_11_13 += px; + if (x[8] && x[12]) joint_8_11_12_13 += px; + if (x[9] && x[12]) joint_9_11_12_13 += px; + if (x[14]) { + joint_11_13_14 += px; + if (x[12]) { + joint_11_12_13_14 += px; + } + } + } } DiscreteFactor::Values all1 = allPosbValues.back(); - // check separator marginal P(S0) auto c = (*bayesTree)[0]; DiscreteFactorGraph separatorMarginal0 = c->separatorMarginal(EliminateDiscrete); - EXPECT_DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); + DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); - // // check separator marginal P(S9), should be P(14) - // c = (*bayesTree)[9]; - // DiscreteFactorGraph separatorMarginal9 = - // c->separatorMarginal(EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); + // check separator marginal P(S9), should be P(14) + c = (*bayesTree)[9]; + DiscreteFactorGraph separatorMarginal9 = + c->separatorMarginal(EliminateDiscrete); + DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); - // // check separator marginal of root, should be empty - // c = (*bayesTree)[11]; - // DiscreteFactorGraph separatorMarginal11 = - // c->separatorMarginal(EliminateDiscrete); - // EXPECT_LONGS_EQUAL(0, separatorMarginal11.size()); + // check separator marginal of root, should be empty + c = (*bayesTree)[11]; + DiscreteFactorGraph separatorMarginal11 = + c->separatorMarginal(EliminateDiscrete); + LONGS_EQUAL(0, separatorMarginal11.size()); - // // check shortcut P(S9||R) to root - // c = (*bayesTree)[9]; - // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); - // EXPECT_LONGS_EQUAL(0, shortcut.size()); + // check shortcut P(S9||R) to root + c = (*bayesTree)[9]; + DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); + LONGS_EQUAL(1, shortcut.size()); + DOUBLES_EQUAL(joint_11_13_14 / joint_11_13, shortcut.evaluate(all1), 1e-9); - // // check shortcut P(S8||R) to root - // c = (*bayesTree)[8]; - // shortcut = c->shortcut(R, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint_12_14 / marginals[14], evaluate(shortcut, all1), - // 1e-9); + // check shortcut P(S8||R) to root + c = (*bayesTree)[8]; + shortcut = c->shortcut(R, EliminateDiscrete); + DOUBLES_EQUAL(joint_11_12_13_14 / joint_11_13, shortcut.evaluate(all1), 1e-9); - // // check shortcut P(S2||R) to root - // c = (*bayesTree)[2]; - // shortcut = c->shortcut(R, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint_9_12_14 / marginals[14], evaluate(shortcut, - // all1), - // 1e-9); + // check shortcut P(S2||R) to root + c = (*bayesTree)[2]; + shortcut = c->shortcut(R, EliminateDiscrete); + DOUBLES_EQUAL(joint_9_11_12_13 / joint_11_13, shortcut.evaluate(all1), 1e-9); - // // check shortcut P(S0||R) to root - // c = (*bayesTree)[0]; - // shortcut = c->shortcut(R, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint_8_12_14 / marginals[14], evaluate(shortcut, - // all1), - // 1e-9); + // check shortcut P(S0||R) to root + c = (*bayesTree)[0]; + shortcut = c->shortcut(R, EliminateDiscrete); + DOUBLES_EQUAL(joint_8_11_12_13 / joint_11_13, shortcut.evaluate(all1), 1e-9); - // // calculate all shortcuts to root - // DiscreteBayesTree::Nodes cliques = bayesTree->nodes(); - // for (auto c : cliques) { - // DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); - // if (debug) { - // c->printSignature(); - // shortcut.print("shortcut:"); - // } - // } + // calculate all shortcuts to root + DiscreteBayesTree::Nodes cliques = bayesTree->nodes(); + for (auto c : cliques) { + DiscreteBayesNet shortcut = c.second->shortcut(R, EliminateDiscrete); + if (debug) { + c.second->conditional_->printSignature(); + shortcut.print("shortcut:"); + } + } - // // Check all marginals - // DiscreteFactor::shared_ptr marginalFactor; - // for (size_t i = 0; i < 15; i++) { - // marginalFactor = bayesTree->marginalFactor(i, EliminateDiscrete); - // double actual = (*marginalFactor)(all1); - // EXPECT_DOUBLES_EQUAL(marginals[i], actual, 1e-9); - // } + // Check all marginals + DiscreteFactor::shared_ptr marginalFactor; + for (size_t i = 0; i < 15; i++) { + marginalFactor = bayesTree->marginalFactor(i, EliminateDiscrete); + double actual = (*marginalFactor)(all1); + DOUBLES_EQUAL(marginals[i], actual, 1e-9); + } - // DiscreteBayesNet::shared_ptr actualJoint; + DiscreteBayesNet::shared_ptr actualJoint; - // Check joint P(8,2) TODO: not disjoint ! - // actualJoint = bayesTree->jointBayesNet(8, 2, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint82, evaluate(*actualJoint,all1), 1e-9); + // Check joint P(8, 2) + actualJoint = bayesTree->jointBayesNet(8, 2, EliminateDiscrete); + DOUBLES_EQUAL(joint82, actualJoint->evaluate(all1), 1e-9); - // Check joint P(1,2) TODO: not disjoint ! - // actualJoint = bayesTree->jointBayesNet(1, 2, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint12, evaluate(*actualJoint,all1), 1e-9); + // Check joint P(1, 2) + actualJoint = bayesTree->jointBayesNet(1, 2, EliminateDiscrete); + DOUBLES_EQUAL(joint12, actualJoint->evaluate(all1), 1e-9); - // Check joint P(2,4) - // actualJoint = bayesTree->jointBayesNet(2, 4, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint24, evaluate(*actualJoint, all1), 1e-9); + // Check joint P(2, 4) + actualJoint = bayesTree->jointBayesNet(2, 4, EliminateDiscrete); + DOUBLES_EQUAL(joint24, actualJoint->evaluate(all1), 1e-9); - // Check joint P(4,5) TODO: not disjoint ! - // actualJoint = bayesTree->jointBayesNet(4, 5, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); + // Check joint P(4, 5) + actualJoint = bayesTree->jointBayesNet(4, 5, EliminateDiscrete); + DOUBLES_EQUAL(joint45, actualJoint->evaluate(all1), 1e-9); - // Check joint P(4,6) TODO: not disjoint ! - // actualJoint = bayesTree->jointBayesNet(4, 6, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint46, evaluate(*actualJoint,all1), 1e-9); + // Check joint P(4, 6) + actualJoint = bayesTree->jointBayesNet(4, 6, EliminateDiscrete); + DOUBLES_EQUAL(joint46, actualJoint->evaluate(all1), 1e-9); - // Check joint P(4,11) - // actualJoint = bayesTree->jointBayesNet(4, 11, EliminateDiscrete); - // EXPECT_DOUBLES_EQUAL(joint_4_11, evaluate(*actualJoint, all1), 1e-9); + // Check joint P(4, 11) + actualJoint = bayesTree->jointBayesNet(4, 11, EliminateDiscrete); + DOUBLES_EQUAL(joint_4_11, actualJoint->evaluate(all1), 1e-9); } /* ************************************************************************* */ From 362b64499a8abdbe6584f1746a5c6d1754020c3b Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 19:03:05 -0400 Subject: [PATCH 171/199] perform equality comparison on root of class hierarchy --- gtsam/navigation/CombinedImuFactor.cpp | 2 +- gtsam/navigation/CombinedImuFactor.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/navigation/CombinedImuFactor.cpp b/gtsam/navigation/CombinedImuFactor.cpp index 7f58f7e64..d7b4b7bf1 100644 --- a/gtsam/navigation/CombinedImuFactor.cpp +++ b/gtsam/navigation/CombinedImuFactor.cpp @@ -44,7 +44,7 @@ void PreintegrationCombinedParams::print(const string& s) const { } //------------------------------------------------------------------------------ -bool PreintegrationCombinedParams::equals(const PreintegrationParams& other, +bool PreintegrationCombinedParams::equals(const PreintegratedRotationParams& other, double tol) const { auto e = dynamic_cast(&other); return e != nullptr && PreintegrationParams::equals(other, tol) && diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index 8b6dcd3f2..a89568433 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -88,7 +88,7 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { } void print(const std::string& s="") const; - bool equals(const PreintegrationParams& other, double tol) const; + bool equals(const PreintegratedRotationParams& other, double tol) const; void setBiasAccCovariance(const Matrix3& cov) { biasAccCovariance=cov; } void setBiasOmegaCovariance(const Matrix3& cov) { biasOmegaCovariance=cov; } From c68ab6b3bedf9576416b816089482c1a2e14ce50 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 19:54:23 -0400 Subject: [PATCH 172/199] correct vector init --- gtsam/discrete/tests/testDiscreteBayesTree.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 150a41c24..9950c014e 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -35,7 +35,7 @@ static bool debug = false; /* ************************************************************************* */ -TEST_UNSAFE(DiscreteBayesTree, thinTree) { +TEST_UNSAFE(DiscreteBayesTree, ThinTree) { const int nrNodes = 15; const size_t nrStates = 2; @@ -94,7 +94,7 @@ TEST_UNSAFE(DiscreteBayesTree, thinTree) { } // Calculate all some marginals for Values==all1 - Vector marginals = zero(15); + Vector marginals = Vector::Zero(15); double joint_12_14 = 0, joint_9_12_14 = 0, joint_8_12_14 = 0, joint_8_12 = 0, joint82 = 0, joint12 = 0, joint24 = 0, joint45 = 0, joint46 = 0, joint_4_11 = 0, joint_11_13 = 0, joint_11_13_14 = 0, From c67779fdce5f0897ce36c85b1b2ea65896513862 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 19:54:42 -0400 Subject: [PATCH 173/199] delete extra pdf file --- gtsam/discrete/tests/testDiscreteBayesTree.pdf | Bin 10622 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 gtsam/discrete/tests/testDiscreteBayesTree.pdf diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.pdf b/gtsam/discrete/tests/testDiscreteBayesTree.pdf deleted file mode 100644 index e8167d455477f97aadb2101d26120a6c145891f5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10622 zcma)i2RK~a^S>5?=p|~bPPEvu87l@l5hq-FA~Taz0X!;D zXB&5006&7Hg#!Qpc;xIH-Jx*A(-Gnhy$iL3SwV5c#c|x+;ZTSZ&i#ym6xG-nfg2&) z-^s*TB<~T)Dken$La#-jq59a?RRcmTBJ!>$$b6K!d|;-Pw=p{v+e6>N@FAQ%os>(Q zfqj%}cROMy(b81iEU78^rDfB%`o=TH61qzh+iwJxu-#)j@8bv2^d%3uNhi(p3b-6+ zCPpTBv|k#nq)v=g58W;`G8yd*a7*kPO@rfd6~<}dHtf8siRb}(rJ>!5%~!9Yc_D0^ zwaiD@AJCzTKbJZ2X|wA4X^rV8&L=Wape4sriH;|NALi@}9r87N)yF2&dHRY7?(N<# zc{AsyKi80*JZ4&Uaj~<9({y{3d-5CH_w@Vn=HBQ)<0}<0_ZnFmk8$I*w~k`%cwo~Z zGo2FkHACiGURroYJ$)qtm}4t;$y#qZcy*QPG>xD6y_4-&jVz=U`xZgQ*%;VLivU&`1}PK||UGDx>Q9u{jm6CK^L<*ef=hu#&~d?MMFK0N61HO}zUJ&=~I zQ(c27RxUr^!&h|0#L@BZ9bSE#;C(jPl;qa1&OH9OoWFy~TICU0^n>N0_8!tDb(^^L zQ6<`>wqX%AqIE!!!LCCYu$Rb&C@!u|JFlUyBY<_)m~dE`QT0%8~vExZX+ zAFzh4`VJ?)w<`oW7Mt@pqw+*QdO}0Is1w1+QhG&*zoQ(QF&duh}O4`A5 ziXXedCD!QVCdr})CAW2IhEbzb1s}PZ8E>wvc60;DQ=ZAmwcTvG$?COS#J1uQ3@563b2~v#|h8Mf<{^7lySTh6}mgo7&Asw zs$HAGxO`q7B{vzGdlEi^7uls`En=nPtHkrkQrLkeXnNT^3Xy4Z4}AwbsvdfBalZYSCHT-%@((y{Wv=^{RXZJEnRT-GHFC zFMCL-xfmV0*>V;h_B84436?Jh>hv!w5GO7$3~TM#T=!^GYdW+F%1=a04rkZrd1+OjkJTJz=V{Ag-9U zbuKC(D@nkP#MCPx`jEme7{;V;Z|KTTt&#h}B;iQW)^&W$GuMu$a!rB5r_bNDD(FS> zeqga(y~`HCuJos@(mYjQ|O03%skp*OOSb`dMX?iL1lGln~KStlaEifwy{h@mK{Ayf{@b_qBR#0a1=YcrdLu@KKix(-Z>@-tJTOci==dV7S zGgCyl)$nx_;qAplsAw#@$x^8ndsf=`2%%}tD#zjKDeH?<8(^nl0l1{1jF*_hQk|0l z)MY*(W*(N3+h5#r4FetDX$H=ajozs_CF^?jKnnZzr$USl)}|7g!IWDQ!Xt0URVl?v z{LE9~4_;S8Pp!YG9~yZom%nF!t$Of1Y93zT)j(=5!p(i6h$-Cc+OrpKJD-pb6)*TxgamkH{R26h_y?62XO`SK0`}BFIfCQa!+#Qz{sV?y6xJ?HsQsao% zj!!I$p3rp?Tc6SZ4ylxT8^k1)<#uo5IXs%JlqIiZj*SBtuu3uJF6tOZzZ2{os+~UE zTi=t&oqBd12kLC~GglzKA+roJwIH8}*LlMJ+e)Z*1g<9D`q+#~~MhFrRz|SuX z-~;jjOs=?P5TYR1-2lkc`Xi6Z!(kpSe-rP=99Ps|>(fTe42L+oxgh7V^!`Ow1h~UJ zpubu&2(G(OPdiJfmb^5Q_;dAIP&b$d+!E>rKx$I!Zz~f*wEvafg@23nU+EpGsvo}t zKmZ|LKB0f)`%OV_KW*K2pM;O+90!~d1niQy71LNuM);g$3?uRzg7YN%w6e`P$PK6M z*`LhfNE^r{X<6O1BGK#%qvpUUCtTR}hdTGj8vs{Ylu7^d`lV{FQp$;Fnk-a}Ptz0AV|(XcI|yT1{=~&Zd6bo52_@i%jbQV&UM+Ha~VdEc=|28@(@y?G_-3UQh|g1 zBCbePE;kqqNqBg-czHl>G}4OlLyu)1YRICL6bq&i`m^VJOW2(W*!M6?;yIkXq{KPx zA29`~J+tEb@D18tO1%uv>sx&AB6g5Pn;bvO#1z_Fp)vr#9Wxetap8IKm_~qERnHxF z-{k@1mB3OBo3H-?M?s5@khR$}C;Se+n2gRDqE$=HgLBB=`l( zeutzc*r&eCf0<`&e}cz7&=dNirw9!5?U3pE(yD;d2+xxGgAS#D6W z;@@v-Oi-vLLSIcV#S5|!<>Z3#gUCOm*Ju9;-O%jWn)hSKF}ho2vQzbAzh`p`!XYy z(d^Yqe5rN?PQEmrQgDJLWj`?1TqXNS*@_5rI94nCTq;_OpXLQl7#4G2CM1lDG03eS;$(Jl?PSu}Qci zi^zHONH12}fc@-73U7_N#%D-_xk)EsOmewW?~Y`50!Eh2bprbkUDTG9J8DVubNMWF zF)u09^7Voh)3P6b>-9TgOsarr9n`C`bo)S~HiUEoFvr*$SxiYU?c0_@Mp~3LOk>g~ zpK6(?*lW6s1(A`pyp_8l&0NlU<}My2^L1$Io4aAVWFrOtdUBJW)ecjgM_Gh{m($W& z_o&shkK*^P=MS0EQ*7w*`FC;I`Q+&*mnatcDK5`4PHJdkA_dd?Uu;a0`&E13*FBQeCdOwQ*1vV!8}i53D_fN}D?Ge8Fj1FQ(D$-&qQnsgHnfR}Hb1+PKS_I_ERB zb*~67116)k;BBCsW$n=y%Nzw9)^EX3pS8>$uL4Jvxs(d|I$m%2Uerz8DT()u*$r{D z&t3r2RhBuaWhl4@H~7Nwg55@5-zS#fp37VDaAV0@$D|#GRM70Td)S26&i8Z}Q-(1s zojyuo#4A9(fytNkq}x`VJsD&)Vj>LY+K$){0%LL1hU}AgSl83(OyNkx+m%x(k%ClR z%s6h7yU~qaOJwM=p~n>K$h?7$&5NnoVIdFJ4UCOxRPX5BniBFoeZI+h`KHG5urQ`e z*Qw>{_-0X6%&R2G7P<{)%y9ey*Q+Xnuh&0*s@^P(;;7ipoQjpF5jI#S? zR1B?=`ZiATHQcl}J)R;G2Iq>q0fE%>2J{D=TB$LNN_*Lt*q5vss4#gi^ zGP6|Pj%hEXz~qeTdCi+Xuk$!@73#Ji9Q2?`7R9$BZFQo-mfVeCz$s}54VB9~roGDFS$m<7J5XKdqO2}qTGfUSg6 z;agHCg`GtQeVx}Q>Mu~4k6NEwFj~?nE|VB+2da+NJ9~Yh6BIk_`y?w6CrHgou1{`! zUL60LiA&w-VOjqD^1V@+ug4p)8IiBMi|)yPN70I6{+u<^#cvUn-y%T&jdCyej6`hz z_64RmY5~fHG4}hYd)+>xH79dSS)Qz6nwHugM(r=l4JsBW9L>?IEha}#&-wNTqo$sgMW+LK%f?xHmSZVdQdrsz(qe*F&pJ@%ab(%FsYbUZ%HzOiOu(-J+ zmUQ&w-1WU>W2uePF>3c|kyC*WeeuGUc(%3tC0x zD6f>HJKGRJxAo|{4EYqs4b3g@^E!ij1`g!ukUie02wiBJx0@WhNULs|H?CltXdAd~ za`3I&=CY@9ojSF~i7`veI0X}7@{q&QypNmrz|6tdRpaihfr6=(YxIM#lytZb=oreg z8!@*-AOqvO(LQprH&oR|(P!2p7%c2v=vizU?pxBEOGvw4dmCo_j{9OJL4@j}MYro7Ow8Zve63*b-G^HJfCt6{#UaKg z_vqbZz;nb0m}q<-yH`gKLxifdEZ^Ajr!iyq^dwn1mK%FIr;y^C>1QN|wR0{S=%qk()0_Q_nguVMAd)WnNpc{r zRyM9@Zgt&f^qqxGPF!&o=m&|Y(j)?i=nUG69Gol`%WNzbX>9kn_&BKt*JKGFhkn5r z)W^q-drQ34mb?$SPk)9JL)J1%7*a$bTzKE?r409RGy3r85N=Z_$FTqK`xdPA_<6qr zuagJHLHao4e#sa)wB*DDCRDT6p*3^P_ff?Gio;-FGmtG9Wd`4A2z4JqJ8v4ezayY1 z={^H9)3 zHX(DNsDvHgFZ3U^g+=F2vN@J*ru4`A%+8E>k#@W)({=P%dxczhdwdZKXop9bHmT8rbD>Tzm)#lzAxAH>mQcw$`3a!%0 z9;YPsdoMdJ%PhlQ2b=Vkm|q5q^_iOUls~jCg&T4|OYc-oPPJmLP@8%%MSp61TDgZi z6f5um-{b5{DP_`V<^i?7Y?pb~mqyixYF*D+-*wYh&~Y77bZ!DUw=IdvNX<1Nr`Xd# zEZpm<+%_SMv(A+T`2|cy{Vcm{$tl^R_VeBz8A^q5eLIE9*o&C7Pov+)6@l8{(O7o* zv^VBrW2HR+4pCHm(O8PLlYT1~-hX7Ngvt&(7g3^@V>f=mWN5_x#0Tyq70Pv>*9^f; zG-8>A_$oJR!f^2vHnFvQi^i7AovIfwjE2U@%YqehxhP(3IId$0V8+dYP@@a>7A;(| z`RDI;(o@Wijay3tv@m4Ix}X7xOU0M;4lv1&YTo_qslj7=uld2z2df<7v4e%UrMvGliZ|xhoi-& ziG(=Xg{$z5-jhkn3u883>?({7h4mLUpjl|Ue?1J7ywDK2ky<+r(U=%JB-$H21BRCn z$N&y0vcUbXQ^N*{+aPKvHkMdC`EgGzyY$pbiiz_}NWWRHmmfwstd{FePY->0tsNL< zyIFYr{Eqhevbl+o4FUFH&t!V>;UQyOtkGhdlAq67yv#XasAo7jnBwm9nHhV&_@V-5 zxQVSQK$r<*ZJ3Edg4JP7nsqqh@K9l?mYcn`M7V%Hbzj3;9bcdx#H}5VRq=9rHT;m~ zXs9PEYw;F{z~UP)poxw!1hW+YYSzF`p$0@vA>82$1^IBVw&fA^-c5zFW+w&pO?FXV>m>ZnU zT_@w(kE)6E=97b;#V0jeUYE!B$3F4+d@o=>!d%2P-g^;T{2Xf~xnEBpdbY1Peo2vI zr|kO8IrawBH~P+KahIl^IG@lkayz1hSIPN$&BlmTx!5I=Rc{qCOJ7rO?C3ewa!Rx> z)zMlvwbx5vnOFN;ak(ruMFr|NjA zIu{jQCv)L>yWMd_)k{xm#)9i&g&M=z9DhxywUu*Y{4-7^Q%qtRYsnqOwI$0^8sAf` z_mM^3X*K|Xj=F^ zoDjAkQMP;2@uETCK~=PblzZ+E@ur0&(p$5;1#$s|OA z-z$7c)II?kc<5BBR_dZFIo_J8&W!uN_$BF;6Qy2r~YxZcDS4WGQQ zoC~Zu2nnWrtH=Z(;Uw6b=Qfm`eUPGUqOS1dMr7<{=`k0Rm30Sql4s& z)8hsb>Vc_qFp~|EdtsG>vN4;r;}h02bBwmHy=yxr3g;FkdgeMN6w9A>USk4IoCoF& zPNJE`+ZXQ?7|JI#KpWT}r5zY4x37MifRuOO?lT?Y^mZD}zP#l-mZoiFuG+;M{<&PO z&O}^UT-B8GxNm=nyH-1kMg8eI88%KagK3W5OH!O*m6qE;XRLm-ib4$yG=?x zJa)DgXIB4)hVfavdSHO%qBhZ(Z4X;NRg)AystgjjcA9#Uh;DUP zlx=YZ4cavB-2g`#9GW0QA^@Es#uNkHjVXq3NA0NoNaHw809yP8@qK16PXkkY19QTm zhYc3G|I`#Qb~4s1v7%ryYeII5Wy05mG0A6>9GZpFOlAopW@HHz`ASiK;!N!O;Y|L) z;!G?1WJjlSf;)!jIaM)_iea5|)Y-=oE0i&kbQ^dR z6Nj5*hUnjTA5)Gj?GJ@;MFvV3I*cAxkvr9*R&p^^%FY{72MS7J$sS<37H8M!X&5^M zl}Q;Yk8ugvti5CwJmG3sh)GpW>VJHRLa)1w`zJ7fJe2+k4DbsA1%4gOgOJDT|2n@0 z{dEriUkBKTBk|w(w8`**^J4%Z%4ZREP}e4eaqT-xXWo>l=mBe$Kg#1_=0eFhv6CZO z^Ga184RLDy%wXXb=hDF^%(^U>9%Rkq;=rHasK<9@5?g;gSKcc6K}I!^4>S#9J5$I zW*~!!$a>RGa6SE&d16Q_{qzXxtY{bevB+l=*&H470 z%|%Lhy|?;;!p-<)Le^|N@vUBin?)o0xEk2uqFn+yDtAOmqxfZEyEB7hsjFjrl)-Jwo;0HGfpkPU@j4dmJo-UI~$kci3O5fmhd z^veT(;5JC!AH#WAxL=_~ItYvg`Rkjb`@$#aV2S{5dCCP;(NluZ1ii&fi95$wbQ_yHR^!Li!w!?1n|Hs0k?r#dkVe7s+OHtnYN6 z;fISji)bju;f!tzrN1?vJIwUNqjqtFJS zll{lMzuXOBZIICKX_2tyKb`O&hQDiPZ4E`@h6n`E2ngUo+#r*`p@5*jU_cz?+beq^ zph+GO0)|Bl{SRCI3dMh0A{gm5KcLM2WlNJdRp)lVjo{;q*1lB>jGjBvuL{yR&vFaI zP+C}I(@@~u4AngJxjJiTR{L`{Vw|vV%5;91r!B+yPg+hNsVEyy5l8Wz0@BEbK3=S> zIoTvW=G-acN?jJOVS9(aXhW3TPi>q9iaB6Hk!<88J_oieoeR*Yx226_TH{bY8KR0a zraZPENl(SL3N95RpZ&UNSSHamnRI=6T2P*eIzGvYvmBcwT#X$s)6Gz$`JtgNVQ!^F zi24f|leK~|rK(qOf-Z5$a5MP9a!61Z1en88}5mX`Wa62UOj7)T0MU^f%>QGK z-&ixEWDMzI2uJ-#Z1@2$|Ann1<@=}WBC&P1t5qx8Ss}yKRebx6o_ipn_P;qV`0pbi zR$}F0iKt0qvxL~eVE_;}NPrs%V6%01cX7MJgQyHZP;KB47h5|^H*Of*hW$svkwH|f zx!b{8Sfk5`ZPx@#2lYt;o5X|OE@T(>KEC~2( zsrTVfYaAc|%!>p3eE|gc`FZ&P)_|WhVIe+**^n2&`4iq_&+86lq_i&uhV8?f@j?&&a6gYz+fkIqOw8b#sTn-LE_XF`giz+>%*VT@L5} E0IK=vy8r+H From 80b42dcbefeae96b53a5598b3a470734c5e5df68 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Sun, 12 Jul 2020 20:55:13 -0400 Subject: [PATCH 174/199] Revert "delete extra pdf file" This reverts commit c67779fdce5f0897ce36c85b1b2ea65896513862. --- gtsam/discrete/tests/testDiscreteBayesTree.pdf | Bin 0 -> 10622 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 gtsam/discrete/tests/testDiscreteBayesTree.pdf diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.pdf b/gtsam/discrete/tests/testDiscreteBayesTree.pdf new file mode 100644 index 0000000000000000000000000000000000000000..e8167d455477f97aadb2101d26120a6c145891f5 GIT binary patch literal 10622 zcma)i2RK~a^S>5?=p|~bPPEvu87l@l5hq-FA~Taz0X!;D zXB&5006&7Hg#!Qpc;xIH-Jx*A(-Gnhy$iL3SwV5c#c|x+;ZTSZ&i#ym6xG-nfg2&) z-^s*TB<~T)Dken$La#-jq59a?RRcmTBJ!>$$b6K!d|;-Pw=p{v+e6>N@FAQ%os>(Q zfqj%}cROMy(b81iEU78^rDfB%`o=TH61qzh+iwJxu-#)j@8bv2^d%3uNhi(p3b-6+ zCPpTBv|k#nq)v=g58W;`G8yd*a7*kPO@rfd6~<}dHtf8siRb}(rJ>!5%~!9Yc_D0^ zwaiD@AJCzTKbJZ2X|wA4X^rV8&L=Wape4sriH;|NALi@}9r87N)yF2&dHRY7?(N<# zc{AsyKi80*JZ4&Uaj~<9({y{3d-5CH_w@Vn=HBQ)<0}<0_ZnFmk8$I*w~k`%cwo~Z zGo2FkHACiGURroYJ$)qtm}4t;$y#qZcy*QPG>xD6y_4-&jVz=U`xZgQ*%;VLivU&`1}PK||UGDx>Q9u{jm6CK^L<*ef=hu#&~d?MMFK0N61HO}zUJ&=~I zQ(c27RxUr^!&h|0#L@BZ9bSE#;C(jPl;qa1&OH9OoWFy~TICU0^n>N0_8!tDb(^^L zQ6<`>wqX%AqIE!!!LCCYu$Rb&C@!u|JFlUyBY<_)m~dE`QT0%8~vExZX+ zAFzh4`VJ?)w<`oW7Mt@pqw+*QdO}0Is1w1+QhG&*zoQ(QF&duh}O4`A5 ziXXedCD!QVCdr})CAW2IhEbzb1s}PZ8E>wvc60;DQ=ZAmwcTvG$?COS#J1uQ3@563b2~v#|h8Mf<{^7lySTh6}mgo7&Asw zs$HAGxO`q7B{vzGdlEi^7uls`En=nPtHkrkQrLkeXnNT^3Xy4Z4}AwbsvdfBalZYSCHT-%@((y{Wv=^{RXZJEnRT-GHFC zFMCL-xfmV0*>V;h_B84436?Jh>hv!w5GO7$3~TM#T=!^GYdW+F%1=a04rkZrd1+OjkJTJz=V{Ag-9U zbuKC(D@nkP#MCPx`jEme7{;V;Z|KTTt&#h}B;iQW)^&W$GuMu$a!rB5r_bNDD(FS> zeqga(y~`HCuJos@(mYjQ|O03%skp*OOSb`dMX?iL1lGln~KStlaEifwy{h@mK{Ayf{@b_qBR#0a1=YcrdLu@KKix(-Z>@-tJTOci==dV7S zGgCyl)$nx_;qAplsAw#@$x^8ndsf=`2%%}tD#zjKDeH?<8(^nl0l1{1jF*_hQk|0l z)MY*(W*(N3+h5#r4FetDX$H=ajozs_CF^?jKnnZzr$USl)}|7g!IWDQ!Xt0URVl?v z{LE9~4_;S8Pp!YG9~yZom%nF!t$Of1Y93zT)j(=5!p(i6h$-Cc+OrpKJD-pb6)*TxgamkH{R26h_y?62XO`SK0`}BFIfCQa!+#Qz{sV?y6xJ?HsQsao% zj!!I$p3rp?Tc6SZ4ylxT8^k1)<#uo5IXs%JlqIiZj*SBtuu3uJF6tOZzZ2{os+~UE zTi=t&oqBd12kLC~GglzKA+roJwIH8}*LlMJ+e)Z*1g<9D`q+#~~MhFrRz|SuX z-~;jjOs=?P5TYR1-2lkc`Xi6Z!(kpSe-rP=99Ps|>(fTe42L+oxgh7V^!`Ow1h~UJ zpubu&2(G(OPdiJfmb^5Q_;dAIP&b$d+!E>rKx$I!Zz~f*wEvafg@23nU+EpGsvo}t zKmZ|LKB0f)`%OV_KW*K2pM;O+90!~d1niQy71LNuM);g$3?uRzg7YN%w6e`P$PK6M z*`LhfNE^r{X<6O1BGK#%qvpUUCtTR}hdTGj8vs{Ylu7^d`lV{FQp$;Fnk-a}Ptz0AV|(XcI|yT1{=~&Zd6bo52_@i%jbQV&UM+Ha~VdEc=|28@(@y?G_-3UQh|g1 zBCbePE;kqqNqBg-czHl>G}4OlLyu)1YRICL6bq&i`m^VJOW2(W*!M6?;yIkXq{KPx zA29`~J+tEb@D18tO1%uv>sx&AB6g5Pn;bvO#1z_Fp)vr#9Wxetap8IKm_~qERnHxF z-{k@1mB3OBo3H-?M?s5@khR$}C;Se+n2gRDqE$=HgLBB=`l( zeutzc*r&eCf0<`&e}cz7&=dNirw9!5?U3pE(yD;d2+xxGgAS#D6W z;@@v-Oi-vLLSIcV#S5|!<>Z3#gUCOm*Ju9;-O%jWn)hSKF}ho2vQzbAzh`p`!XYy z(d^Yqe5rN?PQEmrQgDJLWj`?1TqXNS*@_5rI94nCTq;_OpXLQl7#4G2CM1lDG03eS;$(Jl?PSu}Qci zi^zHONH12}fc@-73U7_N#%D-_xk)EsOmewW?~Y`50!Eh2bprbkUDTG9J8DVubNMWF zF)u09^7Voh)3P6b>-9TgOsarr9n`C`bo)S~HiUEoFvr*$SxiYU?c0_@Mp~3LOk>g~ zpK6(?*lW6s1(A`pyp_8l&0NlU<}My2^L1$Io4aAVWFrOtdUBJW)ecjgM_Gh{m($W& z_o&shkK*^P=MS0EQ*7w*`FC;I`Q+&*mnatcDK5`4PHJdkA_dd?Uu;a0`&E13*FBQeCdOwQ*1vV!8}i53D_fN}D?Ge8Fj1FQ(D$-&qQnsgHnfR}Hb1+PKS_I_ERB zb*~67116)k;BBCsW$n=y%Nzw9)^EX3pS8>$uL4Jvxs(d|I$m%2Uerz8DT()u*$r{D z&t3r2RhBuaWhl4@H~7Nwg55@5-zS#fp37VDaAV0@$D|#GRM70Td)S26&i8Z}Q-(1s zojyuo#4A9(fytNkq}x`VJsD&)Vj>LY+K$){0%LL1hU}AgSl83(OyNkx+m%x(k%ClR z%s6h7yU~qaOJwM=p~n>K$h?7$&5NnoVIdFJ4UCOxRPX5BniBFoeZI+h`KHG5urQ`e z*Qw>{_-0X6%&R2G7P<{)%y9ey*Q+Xnuh&0*s@^P(;;7ipoQjpF5jI#S? zR1B?=`ZiATHQcl}J)R;G2Iq>q0fE%>2J{D=TB$LNN_*Lt*q5vss4#gi^ zGP6|Pj%hEXz~qeTdCi+Xuk$!@73#Ji9Q2?`7R9$BZFQo-mfVeCz$s}54VB9~roGDFS$m<7J5XKdqO2}qTGfUSg6 z;agHCg`GtQeVx}Q>Mu~4k6NEwFj~?nE|VB+2da+NJ9~Yh6BIk_`y?w6CrHgou1{`! zUL60LiA&w-VOjqD^1V@+ug4p)8IiBMi|)yPN70I6{+u<^#cvUn-y%T&jdCyej6`hz z_64RmY5~fHG4}hYd)+>xH79dSS)Qz6nwHugM(r=l4JsBW9L>?IEha}#&-wNTqo$sgMW+LK%f?xHmSZVdQdrsz(qe*F&pJ@%ab(%FsYbUZ%HzOiOu(-J+ zmUQ&w-1WU>W2uePF>3c|kyC*WeeuGUc(%3tC0x zD6f>HJKGRJxAo|{4EYqs4b3g@^E!ij1`g!ukUie02wiBJx0@WhNULs|H?CltXdAd~ za`3I&=CY@9ojSF~i7`veI0X}7@{q&QypNmrz|6tdRpaihfr6=(YxIM#lytZb=oreg z8!@*-AOqvO(LQprH&oR|(P!2p7%c2v=vizU?pxBEOGvw4dmCo_j{9OJL4@j}MYro7Ow8Zve63*b-G^HJfCt6{#UaKg z_vqbZz;nb0m}q<-yH`gKLxifdEZ^Ajr!iyq^dwn1mK%FIr;y^C>1QN|wR0{S=%qk()0_Q_nguVMAd)WnNpc{r zRyM9@Zgt&f^qqxGPF!&o=m&|Y(j)?i=nUG69Gol`%WNzbX>9kn_&BKt*JKGFhkn5r z)W^q-drQ34mb?$SPk)9JL)J1%7*a$bTzKE?r409RGy3r85N=Z_$FTqK`xdPA_<6qr zuagJHLHao4e#sa)wB*DDCRDT6p*3^P_ff?Gio;-FGmtG9Wd`4A2z4JqJ8v4ezayY1 z={^H9)3 zHX(DNsDvHgFZ3U^g+=F2vN@J*ru4`A%+8E>k#@W)({=P%dxczhdwdZKXop9bHmT8rbD>Tzm)#lzAxAH>mQcw$`3a!%0 z9;YPsdoMdJ%PhlQ2b=Vkm|q5q^_iOUls~jCg&T4|OYc-oPPJmLP@8%%MSp61TDgZi z6f5um-{b5{DP_`V<^i?7Y?pb~mqyixYF*D+-*wYh&~Y77bZ!DUw=IdvNX<1Nr`Xd# zEZpm<+%_SMv(A+T`2|cy{Vcm{$tl^R_VeBz8A^q5eLIE9*o&C7Pov+)6@l8{(O7o* zv^VBrW2HR+4pCHm(O8PLlYT1~-hX7Ngvt&(7g3^@V>f=mWN5_x#0Tyq70Pv>*9^f; zG-8>A_$oJR!f^2vHnFvQi^i7AovIfwjE2U@%YqehxhP(3IId$0V8+dYP@@a>7A;(| z`RDI;(o@Wijay3tv@m4Ix}X7xOU0M;4lv1&YTo_qslj7=uld2z2df<7v4e%UrMvGliZ|xhoi-& ziG(=Xg{$z5-jhkn3u883>?({7h4mLUpjl|Ue?1J7ywDK2ky<+r(U=%JB-$H21BRCn z$N&y0vcUbXQ^N*{+aPKvHkMdC`EgGzyY$pbiiz_}NWWRHmmfwstd{FePY->0tsNL< zyIFYr{Eqhevbl+o4FUFH&t!V>;UQyOtkGhdlAq67yv#XasAo7jnBwm9nHhV&_@V-5 zxQVSQK$r<*ZJ3Edg4JP7nsqqh@K9l?mYcn`M7V%Hbzj3;9bcdx#H}5VRq=9rHT;m~ zXs9PEYw;F{z~UP)poxw!1hW+YYSzF`p$0@vA>82$1^IBVw&fA^-c5zFW+w&pO?FXV>m>ZnU zT_@w(kE)6E=97b;#V0jeUYE!B$3F4+d@o=>!d%2P-g^;T{2Xf~xnEBpdbY1Peo2vI zr|kO8IrawBH~P+KahIl^IG@lkayz1hSIPN$&BlmTx!5I=Rc{qCOJ7rO?C3ewa!Rx> z)zMlvwbx5vnOFN;ak(ruMFr|NjA zIu{jQCv)L>yWMd_)k{xm#)9i&g&M=z9DhxywUu*Y{4-7^Q%qtRYsnqOwI$0^8sAf` z_mM^3X*K|Xj=F^ zoDjAkQMP;2@uETCK~=PblzZ+E@ur0&(p$5;1#$s|OA z-z$7c)II?kc<5BBR_dZFIo_J8&W!uN_$BF;6Qy2r~YxZcDS4WGQQ zoC~Zu2nnWrtH=Z(;Uw6b=Qfm`eUPGUqOS1dMr7<{=`k0Rm30Sql4s& z)8hsb>Vc_qFp~|EdtsG>vN4;r;}h02bBwmHy=yxr3g;FkdgeMN6w9A>USk4IoCoF& zPNJE`+ZXQ?7|JI#KpWT}r5zY4x37MifRuOO?lT?Y^mZD}zP#l-mZoiFuG+;M{<&PO z&O}^UT-B8GxNm=nyH-1kMg8eI88%KagK3W5OH!O*m6qE;XRLm-ib4$yG=?x zJa)DgXIB4)hVfavdSHO%qBhZ(Z4X;NRg)AystgjjcA9#Uh;DUP zlx=YZ4cavB-2g`#9GW0QA^@Es#uNkHjVXq3NA0NoNaHw809yP8@qK16PXkkY19QTm zhYc3G|I`#Qb~4s1v7%ryYeII5Wy05mG0A6>9GZpFOlAopW@HHz`ASiK;!N!O;Y|L) z;!G?1WJjlSf;)!jIaM)_iea5|)Y-=oE0i&kbQ^dR z6Nj5*hUnjTA5)Gj?GJ@;MFvV3I*cAxkvr9*R&p^^%FY{72MS7J$sS<37H8M!X&5^M zl}Q;Yk8ugvti5CwJmG3sh)GpW>VJHRLa)1w`zJ7fJe2+k4DbsA1%4gOgOJDT|2n@0 z{dEriUkBKTBk|w(w8`**^J4%Z%4ZREP}e4eaqT-xXWo>l=mBe$Kg#1_=0eFhv6CZO z^Ga184RLDy%wXXb=hDF^%(^U>9%Rkq;=rHasK<9@5?g;gSKcc6K}I!^4>S#9J5$I zW*~!!$a>RGa6SE&d16Q_{qzXxtY{bevB+l=*&H470 z%|%Lhy|?;;!p-<)Le^|N@vUBin?)o0xEk2uqFn+yDtAOmqxfZEyEB7hsjFjrl)-Jwo;0HGfpkPU@j4dmJo-UI~$kci3O5fmhd z^veT(;5JC!AH#WAxL=_~ItYvg`Rkjb`@$#aV2S{5dCCP;(NluZ1ii&fi95$wbQ_yHR^!Li!w!?1n|Hs0k?r#dkVe7s+OHtnYN6 z;fISji)bju;f!tzrN1?vJIwUNqjqtFJS zll{lMzuXOBZIICKX_2tyKb`O&hQDiPZ4E`@h6n`E2ngUo+#r*`p@5*jU_cz?+beq^ zph+GO0)|Bl{SRCI3dMh0A{gm5KcLM2WlNJdRp)lVjo{;q*1lB>jGjBvuL{yR&vFaI zP+C}I(@@~u4AngJxjJiTR{L`{Vw|vV%5;91r!B+yPg+hNsVEyy5l8Wz0@BEbK3=S> zIoTvW=G-acN?jJOVS9(aXhW3TPi>q9iaB6Hk!<88J_oieoeR*Yx226_TH{bY8KR0a zraZPENl(SL3N95RpZ&UNSSHamnRI=6T2P*eIzGvYvmBcwT#X$s)6Gz$`JtgNVQ!^F zi24f|leK~|rK(qOf-Z5$a5MP9a!61Z1en88}5mX`Wa62UOj7)T0MU^f%>QGK z-&ixEWDMzI2uJ-#Z1@2$|Ann1<@=}WBC&P1t5qx8Ss}yKRebx6o_ipn_P;qV`0pbi zR$}F0iKt0qvxL~eVE_;}NPrs%V6%01cX7MJgQyHZP;KB47h5|^H*Of*hW$svkwH|f zx!b{8Sfk5`ZPx@#2lYt;o5X|OE@T(>KEC~2( zsrTVfYaAc|%!>p3eE|gc`FZ&P)_|WhVIe+**^n2&`4iq_&+86lq_i&uhV8?f@j?&&a6gYz+fkIqOw8b#sTn-LE_XF`giz+>%*VT@L5} E0IK=vy8r+H literal 0 HcmV?d00001 From 7db7455c12fb9b1c06e9ffc3bc47e27ed489eff1 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 12 Jul 2020 23:05:24 -0400 Subject: [PATCH 175/199] deprecate error in noisemodel, use loss instead; revise virtual with override --- gtsam/linear/NoiseModel.cpp | 36 +++--- gtsam/linear/NoiseModel.h | 172 +++++++++++++++------------- gtsam/nonlinear/NonlinearFactor.cpp | 2 +- 3 files changed, 113 insertions(+), 97 deletions(-) diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index ec4fd08fd..f5ec95696 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -74,6 +74,13 @@ Vector Base::sigmas() const { throw("Base::sigmas: sigmas() not implemented for this noise model"); } +/* ************************************************************************* */ +double Base::squaredMahalanobisDistance(const Vector& v) const { + // Note: for Diagonal, which does ediv_, will be correct for constraints + Vector w = whiten(v); + return w.dot(w); +} + /* ************************************************************************* */ Gaussian::shared_ptr Gaussian::SqrtInformation(const Matrix& R, bool smart) { size_t m = R.rows(), n = R.cols(); @@ -164,13 +171,6 @@ Vector Gaussian::unwhiten(const Vector& v) const { return backSubstituteUpper(thisR(), v); } -/* ************************************************************************* */ -double Gaussian::squaredMahalanobisDistance(const Vector& v) const { - // Note: for Diagonal, which does ediv_, will be correct for constraints - Vector w = whiten(v); - return w.dot(w); -} - /* ************************************************************************* */ Matrix Gaussian::Whiten(const Matrix& H) const { return thisR() * H; @@ -376,6 +376,7 @@ Vector Constrained::whiten(const Vector& v) const { return c; } +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /* ************************************************************************* */ double Constrained::error(const Vector& v) const { Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements @@ -384,6 +385,16 @@ double Constrained::error(const Vector& v) const { w[i] = v[i] * sqrt(mu_[i]); // TODO: may want to store sqrt rather than rebuild return 0.5 * w.dot(w); } +#endif + +/* ************************************************************************* */ +double Constrained::squaredMahalanobisDistance(const Vector& v) const { + Vector w = Diagonal::whiten(v); // get noisemodel for constrained elements + for (size_t i=0; ireweight(A1,A2,A3,b); } -Robust::shared_ptr Robust::Create(const RobustModel::shared_ptr& robust, - const noiseModel::Base::shared_ptr noise) { - SharedGaussian gaussian; - if (!(gaussian = boost::dynamic_pointer_cast(noise))) - { - throw std::invalid_argument("The noise model inside robust must be Gaussian"); - }; - return shared_ptr(new Robust(robust, gaussian)); +Robust::shared_ptr Robust::Create( +const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise){ + return shared_ptr(new Robust(robust,noise)); } /* ************************************************************************* */ diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 449a70cf3..7494e0501 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -90,13 +90,26 @@ namespace gtsam { /// Unwhiten an error vector. virtual Vector unwhiten(const Vector& v) const = 0; + /// Squared Mahalanobis distance v'*R'*R*v = + virtual double squaredMahalanobisDistance(const Vector& v) const; + + /// Mahalanobis distance + virtual double mahalanobisDistance(const Vector& v) const { + return std::sqrt(squaredMahalanobisDistance(v)); + } + + /// loss function, input is Mahalanobis distance + virtual double loss(const double squared_distance) const { + return 0.5 * squared_distance; + } + +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// calculate the error value given measurement error vector virtual double error(const Vector& v) const = 0; -#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 virtual double distance(const Vector& v) { return error(v) * 2; - } + } #endif virtual void WhitenSystem(std::vector& A, Vector& b) const = 0; @@ -207,42 +220,30 @@ namespace gtsam { */ static shared_ptr Covariance(const Matrix& covariance, bool smart = true); - virtual void print(const std::string& name) const; - virtual bool equals(const Base& expected, double tol=1e-9) const; - virtual Vector sigmas() const; - virtual Vector whiten(const Vector& v) const; - virtual Vector unwhiten(const Vector& v) const; - - /** - * Squared Mahalanobis distance v'*R'*R*v = - */ - virtual double squaredMahalanobisDistance(const Vector& v) const; - - /** - * Mahalanobis distance - */ - virtual double mahalanobisDistance(const Vector& v) const { - return std::sqrt(squaredMahalanobisDistance(v)); - } + void print(const std::string& name) const override; + bool equals(const Base& expected, double tol=1e-9) const override; + Vector sigmas() const override; + Vector whiten(const Vector& v) const override; + Vector unwhiten(const Vector& v) const override; #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 virtual double Mahalanobis(const Vector& v) const { return squaredMahalanobisDistance(v); } -#endif /** * error value 0.5 * v'*R'*R*v */ - inline virtual double error(const Vector& v) const { + inline double error(const Vector& v) const override { return 0.5 * squaredMahalanobisDistance(v); } +#endif /** * Multiply a derivative with R (derivative of whiten) * Equivalent to whitening each column of the input matrix. */ - virtual Matrix Whiten(const Matrix& H) const; + Matrix Whiten(const Matrix& H) const override; /** * In-place version @@ -257,10 +258,10 @@ namespace gtsam { /** * Whiten a system, in place as well */ - virtual void WhitenSystem(std::vector& A, Vector& b) const; - virtual void WhitenSystem(Matrix& A, Vector& b) const; - virtual void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const; - virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const; + void WhitenSystem(std::vector& A, Vector& b) const override; + void WhitenSystem(Matrix& A, Vector& b) const override; + void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const override; + void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const override; /** * Apply appropriately weighted QR factorization to the system [A b] @@ -345,13 +346,13 @@ namespace gtsam { return Variances(precisions.array().inverse(), smart); } - virtual void print(const std::string& name) const; - virtual Vector sigmas() const { return sigmas_; } - virtual Vector whiten(const Vector& v) const; - virtual Vector unwhiten(const Vector& v) const; - virtual Matrix Whiten(const Matrix& H) const; - virtual void WhitenInPlace(Matrix& H) const; - virtual void WhitenInPlace(Eigen::Block H) const; + void print(const std::string& name) const override; + Vector sigmas() const override { return sigmas_; } + Vector whiten(const Vector& v) const override; + Vector unwhiten(const Vector& v) const override; + Matrix Whiten(const Matrix& H) const override; + void WhitenInPlace(Matrix& H) const override; + void WhitenInPlace(Eigen::Block H) const override; /** * Return standard deviations (sqrt of diagonal) @@ -373,7 +374,7 @@ namespace gtsam { /** * Return R itself, but note that Whiten(H) is cheaper than R*H */ - virtual Matrix R() const { + Matrix R() const override { return invsigmas().asDiagonal(); } @@ -427,10 +428,10 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; - virtual ~Constrained() {} + ~Constrained() {} /// true if a constrained noise mode, saves slow/clumsy dynamic casting - virtual bool isConstrained() const { return true; } + bool isConstrained() const override { return true; } /// Return true if a particular dimension is free or constrained bool constrained(size_t i) const; @@ -482,12 +483,16 @@ namespace gtsam { return MixedVariances(precisions.array().inverse()); } +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /** * The error function for a constrained noisemodel, * for non-constrained versions, uses sigmas, otherwise * uses the penalty function with mu */ - virtual double error(const Vector& v) const; + double error(const Vector& v) const override; +#endif + + double squaredMahalanobisDistance(const Vector& v) const override; /** Fully constrained variations */ static shared_ptr All(size_t dim) { @@ -504,16 +509,16 @@ namespace gtsam { return shared_ptr(new Constrained(Vector::Constant(dim, mu), Vector::Constant(dim,0))); } - virtual void print(const std::string& name) const; + void print(const std::string& name) const override; /// Calculates error vector with weights applied - virtual Vector whiten(const Vector& v) const; + Vector whiten(const Vector& v) const override; /// Whitening functions will perform partial whitening on rows /// with a non-zero sigma. Other rows remain untouched. - virtual Matrix Whiten(const Matrix& H) const; - virtual void WhitenInPlace(Matrix& H) const; - virtual void WhitenInPlace(Eigen::Block H) const; + Matrix Whiten(const Matrix& H) const override; + void WhitenInPlace(Matrix& H) const override; + void WhitenInPlace(Eigen::Block H) const override; /** * Apply QR factorization to the system [A b], taking into account constraints @@ -524,7 +529,7 @@ namespace gtsam { * @param Ab is the m*(n+1) augmented system matrix [A b] * @return diagonal noise model can be all zeros, mixed, or not-constrained */ - virtual Diagonal::shared_ptr QR(Matrix& Ab) const; + Diagonal::shared_ptr QR(Matrix& Ab) const override; /** * Returns a Unit version of a constrained noisemodel in which @@ -586,14 +591,14 @@ namespace gtsam { return Variance(dim, 1.0/precision, smart); } - virtual void print(const std::string& name) const; - virtual double squaredMahalanobisDistance(const Vector& v) const; - virtual Vector whiten(const Vector& v) const; - virtual Vector unwhiten(const Vector& v) const; - virtual Matrix Whiten(const Matrix& H) const; - virtual void WhitenInPlace(Matrix& H) const; - virtual void whitenInPlace(Vector& v) const; - virtual void WhitenInPlace(Eigen::Block H) const; + void print(const std::string& name) const override; + double squaredMahalanobisDistance(const Vector& v) const override; + Vector whiten(const Vector& v) const override; + Vector unwhiten(const Vector& v) const override; + Matrix Whiten(const Matrix& H) const override; + void WhitenInPlace(Matrix& H) const override; + void whitenInPlace(Vector& v) const override; + void WhitenInPlace(Eigen::Block H) const override; /** * Return standard deviation @@ -626,7 +631,7 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; - virtual ~Unit() {} + ~Unit() {} /** * Create a unit covariance noise model @@ -636,19 +641,19 @@ namespace gtsam { } /// true if a unit noise model, saves slow/clumsy dynamic casting - virtual bool isUnit() const { return true; } + bool isUnit() const override { return true; } - virtual void print(const std::string& name) const; - virtual double squaredMahalanobisDistance(const Vector& v) const {return v.dot(v); } - virtual Vector whiten(const Vector& v) const { return v; } - virtual Vector unwhiten(const Vector& v) const { return v; } - virtual Matrix Whiten(const Matrix& H) const { return H; } - virtual void WhitenInPlace(Matrix& /*H*/) const {} - virtual void WhitenInPlace(Eigen::Block /*H*/) const {} - virtual void whitenInPlace(Vector& /*v*/) const {} - virtual void unwhitenInPlace(Vector& /*v*/) const {} - virtual void whitenInPlace(Eigen::Block& /*v*/) const {} - virtual void unwhitenInPlace(Eigen::Block& /*v*/) const {} + void print(const std::string& name) const override; + double squaredMahalanobisDistance(const Vector& v) const override {return v.dot(v); } + Vector whiten(const Vector& v) const override { return v; } + Vector unwhiten(const Vector& v) const override { return v; } + Matrix Whiten(const Matrix& H) const override { return H; } + void WhitenInPlace(Matrix& /*H*/) const override {} + void WhitenInPlace(Eigen::Block /*H*/) const override {} + void whitenInPlace(Vector& /*v*/) const override {} + void unwhitenInPlace(Vector& /*v*/) const override {} + void whitenInPlace(Eigen::Block& /*v*/) const override {} + void unwhitenInPlace(Eigen::Block& /*v*/) const override {} private: /** Serialization function */ @@ -682,7 +687,7 @@ namespace gtsam { protected: typedef mEstimator::Base RobustModel; - typedef noiseModel::Gaussian NoiseModel; + typedef noiseModel::Base NoiseModel; const RobustModel::shared_ptr robust_; ///< robust error function used const NoiseModel::shared_ptr noise_; ///< noise model used @@ -697,10 +702,10 @@ namespace gtsam { : Base(noise->dim()), robust_(robust), noise_(noise) {} /// Destructor - virtual ~Robust() {} + ~Robust() {} - virtual void print(const std::string& name) const; - virtual bool equals(const Base& expected, double tol=1e-9) const; + void print(const std::string& name) const override; + bool equals(const Base& expected, double tol=1e-9) const override; /// Return the contained robust error function const RobustModel::shared_ptr& robust() const { return robust_; } @@ -709,37 +714,42 @@ namespace gtsam { const NoiseModel::shared_ptr& noise() const { return noise_; } // TODO: functions below are dummy but necessary for the noiseModel::Base - inline virtual Vector whiten(const Vector& v) const + inline Vector whiten(const Vector& v) const override { Vector r = v; this->WhitenSystem(r); return r; } - inline virtual Matrix Whiten(const Matrix& A) const + inline Matrix Whiten(const Matrix& A) const override { Vector b; Matrix B=A; this->WhitenSystem(B,b); return B; } - inline virtual Vector unwhiten(const Vector& /*v*/) const + inline Vector unwhiten(const Vector& /*v*/) const override { throw std::invalid_argument("unwhiten is not currently supported for robust noise models."); } #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 - inline virtual double distance(const Vector& v) { + inline double distance(const Vector& v) override { return robust_->loss(this->unweightedWhiten(v).norm()); } -#endif // Fold the use of the m-estimator loss(...) function into error(...) - inline virtual double error(const Vector& v) const + inline double error(const Vector& v) const override { return robust_->loss(noise_->mahalanobisDistance(v)); } +#endif + + double loss(const double squared_distance) const override { + return robust_->loss(std::sqrt(squared_distance)); + } + // TODO: these are really robust iterated re-weighting support functions virtual void WhitenSystem(Vector& b) const; - virtual void WhitenSystem(std::vector& A, Vector& b) const; - virtual void WhitenSystem(Matrix& A, Vector& b) const; - virtual void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const; - virtual void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const; + void WhitenSystem(std::vector& A, Vector& b) const override; + void WhitenSystem(Matrix& A, Vector& b) const override; + void WhitenSystem(Matrix& A1, Matrix& A2, Vector& b) const override; + void WhitenSystem(Matrix& A1, Matrix& A2, Matrix& A3, Vector& b) const override; - virtual Vector unweightedWhiten(const Vector& v) const { + Vector unweightedWhiten(const Vector& v) const override { return noise_->unweightedWhiten(v); } - virtual double weight(const Vector& v) const { + double weight(const Vector& v) const override { // Todo(mikebosse): make the robust weight function input a vector. return robust_->weight(v.norm()); } static shared_ptr Create( - const RobustModel::shared_ptr &robust, const noiseModel::Base::shared_ptr noise); + const RobustModel::shared_ptr &robust, const NoiseModel::shared_ptr noise); private: /** Serialization function */ diff --git a/gtsam/nonlinear/NonlinearFactor.cpp b/gtsam/nonlinear/NonlinearFactor.cpp index 40fc1c427..1cfcba274 100644 --- a/gtsam/nonlinear/NonlinearFactor.cpp +++ b/gtsam/nonlinear/NonlinearFactor.cpp @@ -121,7 +121,7 @@ double NoiseModelFactor::error(const Values& c) const { const Vector b = unwhitenedError(c); check(noiseModel_, b.size()); if (noiseModel_) - return noiseModel_->error(b); + return noiseModel_->loss(noiseModel_->squaredMahalanobisDistance(b)); else return 0.5 * b.squaredNorm(); } else { From ec993497f322df8b8c3dbbbfeef80d59c397405c Mon Sep 17 00:00:00 2001 From: yetongumich Date: Sun, 12 Jul 2020 23:09:13 -0400 Subject: [PATCH 176/199] deprecate error in noisemodel, use loss instead; revise virtual with override --- gtsam/linear/JacobianFactor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/linear/JacobianFactor.cpp b/gtsam/linear/JacobianFactor.cpp index be9b17052..b8a08be9e 100644 --- a/gtsam/linear/JacobianFactor.cpp +++ b/gtsam/linear/JacobianFactor.cpp @@ -515,7 +515,7 @@ Vector JacobianFactor::error_vector(const VectorValues& c) const { double JacobianFactor::error(const VectorValues& c) const { Vector e = unweighted_error(c); // Use the noise model distance function to get the correct error if available. - if (model_) return model_->error(e); + if (model_) return 0.5 * model_->squaredMahalanobisDistance(e); return 0.5 * e.dot(e); } From ec69c7a2a9db299f9ba692a4879d656c243db35f Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 16:03:48 -0400 Subject: [PATCH 177/199] Extra tests on frontal keys --- gtsam/discrete/tests/testDiscreteBayesTree.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 9950c014e..6823d3c04 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -80,6 +80,12 @@ TEST_UNSAFE(DiscreteBayesTree, ThinTree) { bayesTree->saveGraph("/tmp/discreteBayesTree.dot"); } + // Check frontals and parents + for (size_t i : {13, 14, 9, 3, 2, 8, 1, 0, 10, 5, 4}) { + auto clique_i = (*bayesTree)[i]; + EXPECT_LONGS_EQUAL(i, *(clique_i->conditional_->beginFrontals())); + } + auto R = bayesTree->roots().front(); // Check whether BN and BT give the same answer on all configurations From 8666a15f2e388651e9ab50de59423989a5fec189 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 16:04:01 -0400 Subject: [PATCH 178/199] Some more refactoring of marginals --- .../discrete/tests/testDiscreteBayesTree.cpp | 58 ++++++++++--------- 1 file changed, 32 insertions(+), 26 deletions(-) diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 6823d3c04..11a88af59 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -110,16 +110,22 @@ TEST_UNSAFE(DiscreteBayesTree, ThinTree) { double px = bayesTree->evaluate(x); for (size_t i = 0; i < 15; i++) if (x[i]) marginals[i] += px; - if (x[12] && x[14]) joint_12_14 += px; - if (x[9] && x[12] && x[14]) joint_9_12_14 += px; - if (x[8] && x[12] && x[14]) joint_8_12_14 += px; + if (x[12] && x[14]) { + joint_12_14 += px; + if (x[9]) joint_9_12_14 += px; + if (x[8]) joint_8_12_14 += px; + } if (x[8] && x[12]) joint_8_12 += px; - if (x[8] && x[2]) joint82 += px; - if (x[1] && x[2]) joint12 += px; - if (x[2] && x[4]) joint24 += px; - if (x[4] && x[5]) joint45 += px; - if (x[4] && x[6]) joint46 += px; - if (x[4] && x[11]) joint_4_11 += px; + if (x[2]) { + if (x[8]) joint82 += px; + if (x[1]) joint12 += px; + } + if (x[4]) { + if (x[2]) joint24 += px; + if (x[5]) joint45 += px; + if (x[6]) joint46 += px; + if (x[11]) joint_4_11 += px; + } if (x[11] && x[13]) { joint_11_13 += px; if (x[8] && x[12]) joint_8_11_12_13 += px; @@ -135,50 +141,50 @@ TEST_UNSAFE(DiscreteBayesTree, ThinTree) { DiscreteFactor::Values all1 = allPosbValues.back(); // check separator marginal P(S0) - auto c = (*bayesTree)[0]; + auto clique = (*bayesTree)[0]; DiscreteFactorGraph separatorMarginal0 = - c->separatorMarginal(EliminateDiscrete); + clique->separatorMarginal(EliminateDiscrete); DOUBLES_EQUAL(joint_8_12, separatorMarginal0(all1), 1e-9); // check separator marginal P(S9), should be P(14) - c = (*bayesTree)[9]; + clique = (*bayesTree)[9]; DiscreteFactorGraph separatorMarginal9 = - c->separatorMarginal(EliminateDiscrete); + clique->separatorMarginal(EliminateDiscrete); DOUBLES_EQUAL(marginals[14], separatorMarginal9(all1), 1e-9); // check separator marginal of root, should be empty - c = (*bayesTree)[11]; + clique = (*bayesTree)[11]; DiscreteFactorGraph separatorMarginal11 = - c->separatorMarginal(EliminateDiscrete); + clique->separatorMarginal(EliminateDiscrete); LONGS_EQUAL(0, separatorMarginal11.size()); // check shortcut P(S9||R) to root - c = (*bayesTree)[9]; - DiscreteBayesNet shortcut = c->shortcut(R, EliminateDiscrete); + clique = (*bayesTree)[9]; + DiscreteBayesNet shortcut = clique->shortcut(R, EliminateDiscrete); LONGS_EQUAL(1, shortcut.size()); DOUBLES_EQUAL(joint_11_13_14 / joint_11_13, shortcut.evaluate(all1), 1e-9); // check shortcut P(S8||R) to root - c = (*bayesTree)[8]; - shortcut = c->shortcut(R, EliminateDiscrete); + clique = (*bayesTree)[8]; + shortcut = clique->shortcut(R, EliminateDiscrete); DOUBLES_EQUAL(joint_11_12_13_14 / joint_11_13, shortcut.evaluate(all1), 1e-9); // check shortcut P(S2||R) to root - c = (*bayesTree)[2]; - shortcut = c->shortcut(R, EliminateDiscrete); + clique = (*bayesTree)[2]; + shortcut = clique->shortcut(R, EliminateDiscrete); DOUBLES_EQUAL(joint_9_11_12_13 / joint_11_13, shortcut.evaluate(all1), 1e-9); // check shortcut P(S0||R) to root - c = (*bayesTree)[0]; - shortcut = c->shortcut(R, EliminateDiscrete); + clique = (*bayesTree)[0]; + shortcut = clique->shortcut(R, EliminateDiscrete); DOUBLES_EQUAL(joint_8_11_12_13 / joint_11_13, shortcut.evaluate(all1), 1e-9); // calculate all shortcuts to root DiscreteBayesTree::Nodes cliques = bayesTree->nodes(); - for (auto c : cliques) { - DiscreteBayesNet shortcut = c.second->shortcut(R, EliminateDiscrete); + for (auto clique : cliques) { + DiscreteBayesNet shortcut = clique.second->shortcut(R, EliminateDiscrete); if (debug) { - c.second->conditional_->printSignature(); + clique.second->conditional_->printSignature(); shortcut.print("shortcut:"); } } From 9c5bba753cc8d9a1c21b8d14cd24f08bb1688239 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 12:28:43 -0400 Subject: [PATCH 179/199] Fix confusion between parents and frontals --- gtsam/discrete/DiscreteConditional.h | 16 +++++++++ gtsam/discrete/tests/testDiscreteBayesNet.cpp | 36 ++++++++++++++++++- .../tests/testDiscreteConditional.cpp | 5 +++ 3 files changed, 56 insertions(+), 1 deletion(-) diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index 225e6e1d3..b1e9da754 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -90,6 +90,22 @@ public: /// GTSAM-style equals bool equals(const DiscreteFactor& other, double tol = 1e-9) const; + /// @} + /// @name Parent keys are stored *first* in a DiscreteConditional, so re-jigger: + /// @{ + + /** Iterator pointing to first frontal key. */ + typename DecisionTreeFactor::const_iterator beginFrontals() const { return endParents(); } + + /** Iterator pointing past the last frontal key. */ + typename DecisionTreeFactor::const_iterator endFrontals() const { return end(); } + + /** Iterator pointing to the first parent key. */ + typename DecisionTreeFactor::const_iterator beginParents() const { return begin(); } + + /** Iterator pointing past the last parent key. */ + typename DecisionTreeFactor::const_iterator endParents() const { return end() - nrFrontals_; } + /// @} /// @name Standard Interface /// @{ diff --git a/gtsam/discrete/tests/testDiscreteBayesNet.cpp b/gtsam/discrete/tests/testDiscreteBayesNet.cpp index 5ed662332..c3f8aacf1 100644 --- a/gtsam/discrete/tests/testDiscreteBayesNet.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesNet.cpp @@ -18,8 +18,10 @@ #include #include -#include +#include #include +#include +#include #include @@ -29,10 +31,42 @@ using namespace boost::assign; #include +#include +#include using namespace std; using namespace gtsam; +/* ************************************************************************* */ +TEST(DiscreteBayesNet, bayesNet) { + DiscreteBayesNet bayesNet; + DiscreteKey Parent(0, 2), Child(1, 2); + + auto prior = boost::make_shared(Parent % "6/4"); + CHECK(assert_equal(Potentials::ADT({Parent}, "0.6 0.4"), + (Potentials::ADT)*prior)); + bayesNet.push_back(prior); + + auto conditional = + boost::make_shared(Child | Parent = "7/3 8/2"); + EXPECT_LONGS_EQUAL(1, *(conditional->beginFrontals())); + Potentials::ADT expected(Child & Parent, "0.7 0.8 0.3 0.2"); + CHECK(assert_equal(expected, (Potentials::ADT)*conditional)); + bayesNet.push_back(conditional); + + DiscreteFactorGraph fg(bayesNet); + LONGS_EQUAL(2, fg.back()->size()); + + // Check the marginals + const double expectedMarginal[2]{0.4, 0.6 * 0.3 + 0.4 * 0.2}; + DiscreteMarginals marginals(fg); + for (size_t j = 0; j < 2; j++) { + Vector FT = marginals.marginalProbabilities(DiscreteKey(j, 2)); + EXPECT_DOUBLES_EQUAL(expectedMarginal[j], FT[1], 1e-3); + EXPECT_DOUBLES_EQUAL(FT[0], 1.0 - FT[1], 1e-9); + } +} + /* ************************************************************************* */ TEST(DiscreteBayesNet, Asia) { diff --git a/gtsam/discrete/tests/testDiscreteConditional.cpp b/gtsam/discrete/tests/testDiscreteConditional.cpp index 888bf76df..577edecb3 100644 --- a/gtsam/discrete/tests/testDiscreteConditional.cpp +++ b/gtsam/discrete/tests/testDiscreteConditional.cpp @@ -36,6 +36,11 @@ TEST( DiscreteConditional, constructors) DiscreteConditional::shared_ptr expected1 = // boost::make_shared(X | Y = "1/1 2/3 1/4"); EXPECT(expected1); + EXPECT_LONGS_EQUAL(0, *(expected1->beginFrontals())); + EXPECT_LONGS_EQUAL(2, *(expected1->beginParents())); + EXPECT(expected1->endParents() == expected1->beginFrontals()); + EXPECT(expected1->endFrontals() == expected1->end()); + DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8"); DiscreteConditional actual1(1, f1); EXPECT(assert_equal(*expected1, actual1, 1e-9)); From 1ffddf72e1e3ef3a6b60ba35f35f09817bf26f1c Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 16:50:55 -0400 Subject: [PATCH 180/199] Added code to re-jigger Signature cpt so that frontal keys are always first, consistent with how the DiscreteElimination function works. --- gtsam/discrete/DiscreteConditional.cpp | 7 ++-- gtsam/discrete/DiscreteConditional.h | 16 -------- gtsam/discrete/Signature.cpp | 18 +++++---- gtsam/discrete/Signature.h | 4 +- .../tests/testAlgebraicDecisionTree.cpp | 7 ++-- .../tests/testDiscreteConditional.cpp | 4 +- gtsam/discrete/tests/testSignature.cpp | 38 ++++++++++--------- 7 files changed, 42 insertions(+), 52 deletions(-) diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index 2ab3054a8..b5b5c0dbc 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -61,10 +61,9 @@ DiscreteConditional::DiscreteConditional(const DecisionTreeFactor& joint, } /* ******************************************************************************** */ -DiscreteConditional::DiscreteConditional(const Signature& signature) : - BaseFactor(signature.discreteKeysParentsFirst(), signature.cpt()), BaseConditional( - 1) { -} +DiscreteConditional::DiscreteConditional(const Signature& signature) + : BaseFactor(signature.discreteKeys(), signature.cpt()), + BaseConditional(1) {} /* ******************************************************************************** */ void DiscreteConditional::print(const std::string& s, diff --git a/gtsam/discrete/DiscreteConditional.h b/gtsam/discrete/DiscreteConditional.h index b1e9da754..225e6e1d3 100644 --- a/gtsam/discrete/DiscreteConditional.h +++ b/gtsam/discrete/DiscreteConditional.h @@ -90,22 +90,6 @@ public: /// GTSAM-style equals bool equals(const DiscreteFactor& other, double tol = 1e-9) const; - /// @} - /// @name Parent keys are stored *first* in a DiscreteConditional, so re-jigger: - /// @{ - - /** Iterator pointing to first frontal key. */ - typename DecisionTreeFactor::const_iterator beginFrontals() const { return endParents(); } - - /** Iterator pointing past the last frontal key. */ - typename DecisionTreeFactor::const_iterator endFrontals() const { return end(); } - - /** Iterator pointing to the first parent key. */ - typename DecisionTreeFactor::const_iterator beginParents() const { return begin(); } - - /** Iterator pointing past the last parent key. */ - typename DecisionTreeFactor::const_iterator endParents() const { return end() - nrFrontals_; } - /// @} /// @name Standard Interface /// @{ diff --git a/gtsam/discrete/Signature.cpp b/gtsam/discrete/Signature.cpp index 89e763703..94b160a29 100644 --- a/gtsam/discrete/Signature.cpp +++ b/gtsam/discrete/Signature.cpp @@ -122,28 +122,30 @@ namespace gtsam { key_(key) { } - DiscreteKeys Signature::discreteKeysParentsFirst() const { + DiscreteKeys Signature::discreteKeys() const { DiscreteKeys keys; - for(const DiscreteKey& key: parents_) - keys.push_back(key); keys.push_back(key_); + for (const DiscreteKey& key : parents_) keys.push_back(key); return keys; } KeyVector Signature::indices() const { KeyVector js; js.push_back(key_.first); - for(const DiscreteKey& key: parents_) - js.push_back(key.first); + for (const DiscreteKey& key : parents_) js.push_back(key.first); return js; } vector Signature::cpt() const { vector cpt; if (table_) { - for(const Row& row: *table_) - for(const double& x: row) - cpt.push_back(x); + const size_t nrStates = table_->at(0).size(); + for (size_t j = 0; j < nrStates; j++) { + for (const Row& row : *table_) { + assert(row.size() == nrStates); + cpt.push_back(row[j]); + } + } } return cpt; } diff --git a/gtsam/discrete/Signature.h b/gtsam/discrete/Signature.h index 587cd6b30..6c59b5bff 100644 --- a/gtsam/discrete/Signature.h +++ b/gtsam/discrete/Signature.h @@ -86,8 +86,8 @@ namespace gtsam { return parents_; } - /** All keys, with variable key last */ - DiscreteKeys discreteKeysParentsFirst() const; + /** All keys, with variable key first */ + DiscreteKeys discreteKeys() const; /** All key indices, with variable key first */ KeyVector indices() const; diff --git a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp index 753af16d8..0261ef833 100644 --- a/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp +++ b/gtsam/discrete/tests/testAlgebraicDecisionTree.cpp @@ -132,7 +132,7 @@ TEST(ADT, example3) /** Convert Signature into CPT */ ADT create(const Signature& signature) { - ADT p(signature.discreteKeysParentsFirst(), signature.cpt()); + ADT p(signature.discreteKeys(), signature.cpt()); static size_t count = 0; const DiscreteKey& key = signature.key(); string dotfile = (boost::format("CPT-%03d-%d") % ++count % key.first).str(); @@ -181,19 +181,20 @@ TEST(ADT, joint) dot(joint, "Asia-ASTLBEX"); joint = apply(joint, pD, &mul); dot(joint, "Asia-ASTLBEXD"); - EXPECT_LONGS_EQUAL(346, (long)muls); + EXPECT_LONGS_EQUAL(346, muls); gttoc_(asiaJoint); tictoc_getNode(asiaJointNode, asiaJoint); elapsed = asiaJointNode->secs() + asiaJointNode->wall(); tictoc_reset_(); printCounts("Asia joint"); + // Form P(A,S,T,L) = P(A) P(S) P(T|A) P(L|S) ADT pASTL = pA; pASTL = apply(pASTL, pS, &mul); pASTL = apply(pASTL, pT, &mul); pASTL = apply(pASTL, pL, &mul); - // test combine + // test combine to check that P(A) = \sum_{S,T,L} P(A,S,T,L) ADT fAa = pASTL.combine(L, &add_).combine(T, &add_).combine(S, &add_); EXPECT(assert_equal(pA, fAa)); ADT fAb = pASTL.combine(S, &add_).combine(T, &add_).combine(L, &add_); diff --git a/gtsam/discrete/tests/testDiscreteConditional.cpp b/gtsam/discrete/tests/testDiscreteConditional.cpp index 577edecb3..749186d14 100644 --- a/gtsam/discrete/tests/testDiscreteConditional.cpp +++ b/gtsam/discrete/tests/testDiscreteConditional.cpp @@ -38,8 +38,8 @@ TEST( DiscreteConditional, constructors) EXPECT(expected1); EXPECT_LONGS_EQUAL(0, *(expected1->beginFrontals())); EXPECT_LONGS_EQUAL(2, *(expected1->beginParents())); - EXPECT(expected1->endParents() == expected1->beginFrontals()); - EXPECT(expected1->endFrontals() == expected1->end()); + EXPECT(expected1->endParents() == expected1->end()); + EXPECT(expected1->endFrontals() == expected1->beginParents()); DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8"); DiscreteConditional actual1(1, f1); diff --git a/gtsam/discrete/tests/testSignature.cpp b/gtsam/discrete/tests/testSignature.cpp index de47a00f3..830fc32fc 100644 --- a/gtsam/discrete/tests/testSignature.cpp +++ b/gtsam/discrete/tests/testSignature.cpp @@ -11,36 +11,37 @@ /** * @file testSignature - * @brief Tests focusing on the details of Signatures to evaluate boost compliance + * @brief Tests focusing on the details of Signatures to evaluate boost + * compliance * @author Alex Cunningham * @date Sept 19th 2011 */ -#include #include - #include #include +#include + using namespace std; using namespace gtsam; using namespace boost::assign; -DiscreteKey X(0,2), Y(1,3), Z(2,2); +DiscreteKey X(0, 2), Y(1, 3), Z(2, 2); /* ************************************************************************* */ TEST(testSignature, simple_conditional) { Signature sig(X | Y = "1/1 2/3 1/4"); DiscreteKey actKey = sig.key(); - LONGS_EQUAL((long)X.first, (long)actKey.first); + LONGS_EQUAL(X.first, actKey.first); - DiscreteKeys actKeys = sig.discreteKeysParentsFirst(); - LONGS_EQUAL(2, (long)actKeys.size()); - LONGS_EQUAL((long)Y.first, (long)actKeys.front().first); - LONGS_EQUAL((long)X.first, (long)actKeys.back().first); + DiscreteKeys actKeys = sig.discreteKeys(); + LONGS_EQUAL(2, actKeys.size()); + LONGS_EQUAL(X.first, actKeys.front().first); + LONGS_EQUAL(Y.first, actKeys.back().first); vector actCpt = sig.cpt(); - EXPECT_LONGS_EQUAL(6, (long)actCpt.size()); + EXPECT_LONGS_EQUAL(6, actCpt.size()); } /* ************************************************************************* */ @@ -54,17 +55,20 @@ TEST(testSignature, simple_conditional_nonparser) { Signature sig(X | Y = table); DiscreteKey actKey = sig.key(); - EXPECT_LONGS_EQUAL((long)X.first, (long)actKey.first); + EXPECT_LONGS_EQUAL(X.first, actKey.first); - DiscreteKeys actKeys = sig.discreteKeysParentsFirst(); - LONGS_EQUAL(2, (long)actKeys.size()); - LONGS_EQUAL((long)Y.first, (long)actKeys.front().first); - LONGS_EQUAL((long)X.first, (long)actKeys.back().first); + DiscreteKeys actKeys = sig.discreteKeys(); + LONGS_EQUAL(2, actKeys.size()); + LONGS_EQUAL(X.first, actKeys.front().first); + LONGS_EQUAL(Y.first, actKeys.back().first); vector actCpt = sig.cpt(); - EXPECT_LONGS_EQUAL(6, (long)actCpt.size()); + EXPECT_LONGS_EQUAL(6, actCpt.size()); } /* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} /* ************************************************************************* */ From 7dba3023d6f6057762ff80ec05d3e716c976e59b Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sat, 11 Jul 2020 13:16:08 -0400 Subject: [PATCH 181/199] New discrete example --- examples/DiscreteBayesNetExample.cpp | 82 ++++++++++++++++++++++++++++ examples/DiscreteBayesNet_FG.cpp | 2 +- 2 files changed, 83 insertions(+), 1 deletion(-) create mode 100644 examples/DiscreteBayesNetExample.cpp diff --git a/examples/DiscreteBayesNetExample.cpp b/examples/DiscreteBayesNetExample.cpp new file mode 100644 index 000000000..3531fd723 --- /dev/null +++ b/examples/DiscreteBayesNetExample.cpp @@ -0,0 +1,82 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file DiscreteBayesNetExample.cpp + * @brief Discrete Bayes Net example with famous Asia Bayes Network + * @author Frank Dellaert + * @date JULY 10, 2020 + */ + +#include +#include + +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char **argv) { + DiscreteBayesNet asia; + DiscreteKey Asia(0, 2), Smoking(4, 2), Tuberculosis(3, 2), LungCancer(6, 2), + Bronchitis(7, 2), Either(5, 2), XRay(2, 2), Dyspnea(1, 2); + asia.add(Asia % "99/1"); + asia.add(Smoking % "50/50"); + + asia.add(Tuberculosis | Asia = "99/1 95/5"); + asia.add(LungCancer | Smoking = "99/1 90/10"); + asia.add(Bronchitis | Smoking = "70/30 40/60"); + + asia.add((Either | Tuberculosis, LungCancer) = "F T T T"); + + asia.add(XRay | Either = "95/5 2/98"); + asia.add((Dyspnea | Either, Bronchitis) = "9/1 2/8 3/7 1/9"); + + // print + vector pretty = {"Asia", "Dyspnea", "XRay", "Tuberculosis", + "Smoking", "Either", "LungCancer", "Bronchitis"}; + auto formatter = [pretty](Key key) { return pretty[key]; }; + asia.print("Asia", formatter); + + // Convert to factor graph + DiscreteFactorGraph fg(asia); + + // Create solver and eliminate + Ordering ordering; + ordering += Key(0), Key(1), Key(2), Key(3), Key(4), Key(5), Key(6), Key(7); + DiscreteBayesNet::shared_ptr chordal = fg.eliminateSequential(ordering); + + // solve + DiscreteFactor::sharedValues mpe = chordal->optimize(); + GTSAM_PRINT(*mpe); + + // We can also build a Bayes tree (directed junction tree). + // The elimination order above will do fine: + auto bayesTree = fg.eliminateMultifrontal(ordering); + bayesTree->print("bayesTree", formatter); + + // add evidence, we were in Asia and we have dyspnea + fg.add(Asia, "0 1"); + fg.add(Dyspnea, "0 1"); + + // solve again, now with evidence + DiscreteBayesNet::shared_ptr chordal2 = fg.eliminateSequential(ordering); + DiscreteFactor::sharedValues mpe2 = chordal2->optimize(); + GTSAM_PRINT(*mpe2); + + // We can also sample from it + cout << "\n10 samples:" << endl; + for (size_t i = 0; i < 10; i++) { + DiscreteFactor::sharedValues sample = chordal2->sample(); + GTSAM_PRINT(*sample); + } + return 0; +} diff --git a/examples/DiscreteBayesNet_FG.cpp b/examples/DiscreteBayesNet_FG.cpp index 9802b5984..121df4bef 100644 --- a/examples/DiscreteBayesNet_FG.cpp +++ b/examples/DiscreteBayesNet_FG.cpp @@ -10,7 +10,7 @@ * -------------------------------------------------------------------------- */ /** - * @file DiscreteBayesNet_graph.cpp + * @file DiscreteBayesNet_FG.cpp * @brief Discrete Bayes Net example using Factor Graphs * @author Abhijit * @date Jun 4, 2012 From 550dc377e3703fd13e2ec5f7a121a3067b5ac2e1 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sat, 11 Jul 2020 13:16:35 -0400 Subject: [PATCH 182/199] Better print --- gtsam/discrete/DiscreteConditional.cpp | 20 ++++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index b5b5c0dbc..acd0cefee 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -27,6 +27,7 @@ #include #include #include +#include #include using namespace std; @@ -66,10 +67,21 @@ DiscreteConditional::DiscreteConditional(const Signature& signature) BaseConditional(1) {} /* ******************************************************************************** */ -void DiscreteConditional::print(const std::string& s, - const KeyFormatter& formatter) const { - std::cout << s << std::endl; - Potentials::print(s); +void DiscreteConditional::print(const string& s, + const KeyFormatter& formatter) const { + cout << s << " P( "; + for (const_iterator it = beginFrontals(); it != endFrontals(); ++it) { + cout << formatter(*it) << " "; + } + if (nrParents()) { + cout << "| "; + for (const_iterator it = beginParents(); it != endParents(); ++it) { + cout << formatter(*it) << " "; + } + } + cout << ")"; + Potentials::print(""); + cout << endl; } /* ******************************************************************************** */ From 4c7ba2a98f7012199b9c3bbf16f03b2fe946cd93 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sat, 11 Jul 2020 13:18:48 -0400 Subject: [PATCH 183/199] Cleaned up tests --- gtsam/discrete/tests/testDiscreteBayesNet.cpp | 90 +++++++++---------- .../tests/testDiscreteConditional.cpp | 71 +++++++-------- .../discrete/tests/testDiscreteMarginals.cpp | 42 +++++---- gtsam/discrete/tests/testSignature.cpp | 6 ++ 4 files changed, 100 insertions(+), 109 deletions(-) diff --git a/gtsam/discrete/tests/testDiscreteBayesNet.cpp b/gtsam/discrete/tests/testDiscreteBayesNet.cpp index c3f8aacf1..2b440e5a0 100644 --- a/gtsam/discrete/tests/testDiscreteBayesNet.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesNet.cpp @@ -25,8 +25,9 @@ #include -#include + #include +#include using namespace boost::assign; @@ -68,94 +69,84 @@ TEST(DiscreteBayesNet, bayesNet) { } /* ************************************************************************* */ -TEST(DiscreteBayesNet, Asia) -{ +TEST(DiscreteBayesNet, Asia) { DiscreteBayesNet asia; -// DiscreteKey A("Asia"), S("Smoking"), T("Tuberculosis"), L("LungCancer"), B( -// "Bronchitis"), E("Either"), X("XRay"), D("Dyspnoea"); - DiscreteKey A(0,2), S(4,2), T(3,2), L(6,2), B(7,2), E(5,2), X(2,2), D(1,2); + DiscreteKey Asia(0, 2), Smoking(4, 2), Tuberculosis(3, 2), LungCancer(6, 2), + Bronchitis(7, 2), Either(5, 2), XRay(2, 2), Dyspnea(1, 2); - // TODO: make a version that doesn't use the parser - asia.add(A % "99/1"); - asia.add(S % "50/50"); + asia.add(Asia % "99/1"); + asia.add(Smoking % "50/50"); - asia.add(T | A = "99/1 95/5"); - asia.add(L | S = "99/1 90/10"); - asia.add(B | S = "70/30 40/60"); + asia.add(Tuberculosis | Asia = "99/1 95/5"); + asia.add(LungCancer | Smoking = "99/1 90/10"); + asia.add(Bronchitis | Smoking = "70/30 40/60"); - asia.add((E | T, L) = "F T T T"); + asia.add((Either | Tuberculosis, LungCancer) = "F T T T"); - asia.add(X | E = "95/5 2/98"); - // next lines are same as asia.add((D | E, B) = "9/1 2/8 3/7 1/9"); - DiscreteConditional::shared_ptr actual = - boost::make_shared((D | E, B) = "9/1 2/8 3/7 1/9"); - asia.push_back(actual); - // GTSAM_PRINT(asia); + asia.add(XRay | Either = "95/5 2/98"); + asia.add((Dyspnea | Either, Bronchitis) = "9/1 2/8 3/7 1/9"); // Convert to factor graph DiscreteFactorGraph fg(asia); -// GTSAM_PRINT(fg); - LONGS_EQUAL(3,fg.back()->size()); - Potentials::ADT expected(B & D & E, "0.9 0.3 0.1 0.7 0.2 0.1 0.8 0.9"); - CHECK(assert_equal(expected,(Potentials::ADT)*actual)); + LONGS_EQUAL(3, fg.back()->size()); + + // Check the marginals we know (of the parent-less nodes) + DiscreteMarginals marginals(fg); + Vector2 va(0.99, 0.01), vs(0.5, 0.5); + EXPECT(assert_equal(va, marginals.marginalProbabilities(Asia))); + EXPECT(assert_equal(vs, marginals.marginalProbabilities(Smoking))); // Create solver and eliminate Ordering ordering; - ordering += Key(0),Key(1),Key(2),Key(3),Key(4),Key(5),Key(6),Key(7); + ordering += Key(0), Key(1), Key(2), Key(3), Key(4), Key(5), Key(6), Key(7); DiscreteBayesNet::shared_ptr chordal = fg.eliminateSequential(ordering); -// GTSAM_PRINT(*chordal); - DiscreteConditional expected2(B % "11/9"); - CHECK(assert_equal(expected2,*chordal->back())); + DiscreteConditional expected2(Bronchitis % "11/9"); + EXPECT(assert_equal(expected2, *chordal->back())); // solve DiscreteFactor::sharedValues actualMPE = chordal->optimize(); DiscreteFactor::Values expectedMPE; - insert(expectedMPE)(A.first, 0)(D.first, 0)(X.first, 0)(T.first, 0)(S.first, - 0)(E.first, 0)(L.first, 0)(B.first, 0); + insert(expectedMPE)(Asia.first, 0)(Dyspnea.first, 0)(XRay.first, 0)( + Tuberculosis.first, 0)(Smoking.first, 0)(Either.first, 0)( + LungCancer.first, 0)(Bronchitis.first, 0); EXPECT(assert_equal(expectedMPE, *actualMPE)); - // add evidence, we were in Asia and we have Dispnoea - fg.add(A, "0 1"); - fg.add(D, "0 1"); -// fg.product().dot("fg"); + // add evidence, we were in Asia and we have dyspnea + fg.add(Asia, "0 1"); + fg.add(Dyspnea, "0 1"); // solve again, now with evidence DiscreteBayesNet::shared_ptr chordal2 = fg.eliminateSequential(ordering); -// GTSAM_PRINT(*chordal2); DiscreteFactor::sharedValues actualMPE2 = chordal2->optimize(); DiscreteFactor::Values expectedMPE2; - insert(expectedMPE2)(A.first, 1)(D.first, 1)(X.first, 0)(T.first, 0)(S.first, - 1)(E.first, 0)(L.first, 0)(B.first, 1); + insert(expectedMPE2)(Asia.first, 1)(Dyspnea.first, 1)(XRay.first, 0)( + Tuberculosis.first, 0)(Smoking.first, 1)(Either.first, 0)( + LungCancer.first, 0)(Bronchitis.first, 1); EXPECT(assert_equal(expectedMPE2, *actualMPE2)); // now sample from it DiscreteFactor::Values expectedSample; SETDEBUG("DiscreteConditional::sample", false); - insert(expectedSample)(A.first, 1)(D.first, 1)(X.first, 1)(T.first, 0)( - S.first, 1)(E.first, 1)(L.first, 1)(B.first, 0); + insert(expectedSample)(Asia.first, 1)(Dyspnea.first, 1)(XRay.first, 1)( + Tuberculosis.first, 0)(Smoking.first, 1)(Either.first, 1)( + LungCancer.first, 1)(Bronchitis.first, 0); DiscreteFactor::sharedValues actualSample = chordal2->sample(); EXPECT(assert_equal(expectedSample, *actualSample)); } /* ************************************************************************* */ -TEST_UNSAFE(DiscreteBayesNet, Sugar) -{ - DiscreteKey T(0,2), L(1,2), E(2,2), D(3,2), C(8,3), S(7,2); +TEST_UNSAFE(DiscreteBayesNet, Sugar) { + DiscreteKey T(0, 2), L(1, 2), E(2, 2), C(8, 3), S(7, 2); DiscreteBayesNet bn; - // test some mistakes - // add(bn, D); - // add(bn, D | E); - // add(bn, D | E = "blah"); - // try logic bn.add((E | T, L) = "OR"); bn.add((E | T, L) = "AND"); - // // try multivalued - bn.add(C % "1/1/2"); - bn.add(C | S = "1/1/2 5/2/3"); + // try multivalued + bn.add(C % "1/1/2"); + bn.add(C | S = "1/1/2 5/2/3"); } /* ************************************************************************* */ @@ -164,4 +155,3 @@ int main() { return TestRegistry::runAllTests(tr); } /* ************************************************************************* */ - diff --git a/gtsam/discrete/tests/testDiscreteConditional.cpp b/gtsam/discrete/tests/testDiscreteConditional.cpp index 749186d14..3ac3ffc9e 100644 --- a/gtsam/discrete/tests/testDiscreteConditional.cpp +++ b/gtsam/discrete/tests/testDiscreteConditional.cpp @@ -16,9 +16,9 @@ * @date Feb 14, 2011 */ -#include #include #include +#include using namespace boost::assign; #include @@ -48,71 +48,68 @@ TEST( DiscreteConditional, constructors) DecisionTreeFactor f2(X & Y & Z, "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75"); DiscreteConditional actual2(1, f2); - DecisionTreeFactor::shared_ptr actual2factor = actual2.toFactor(); -// EXPECT(assert_equal(f2, *actual2factor, 1e-9)); + EXPECT(assert_equal(f2 / *f2.sum(1), *actual2.toFactor(), 1e-9)); } /* ************************************************************************* */ -TEST( DiscreteConditional, constructors_alt_interface) -{ - DiscreteKey X(0, 2), Y(2, 3), Z(1, 2); // watch ordering ! +TEST(DiscreteConditional, constructors_alt_interface) { + DiscreteKey X(0, 2), Y(2, 3), Z(1, 2); // watch ordering ! Signature::Table table; Signature::Row r1, r2, r3; - r1 += 1.0, 1.0; r2 += 2.0, 3.0; r3 += 1.0, 4.0; + r1 += 1.0, 1.0; + r2 += 2.0, 3.0; + r3 += 1.0, 4.0; table += r1, r2, r3; - DiscreteConditional::shared_ptr expected1 = // - boost::make_shared(X | Y = table); - EXPECT(expected1); + auto actual1 = boost::make_shared(X | Y = table); + EXPECT(actual1); DecisionTreeFactor f1(X & Y, "0.5 0.4 0.2 0.5 0.6 0.8"); - DiscreteConditional actual1(1, f1); - EXPECT(assert_equal(*expected1, actual1, 1e-9)); + DiscreteConditional expected1(1, f1); + EXPECT(assert_equal(expected1, *actual1, 1e-9)); - DecisionTreeFactor f2(X & Y & Z, - "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75"); + DecisionTreeFactor f2( + X & Y & Z, "0.2 0.5 0.3 0.6 0.4 0.7 0.25 0.55 0.35 0.65 0.45 0.75"); DiscreteConditional actual2(1, f2); - DecisionTreeFactor::shared_ptr actual2factor = actual2.toFactor(); -// EXPECT(assert_equal(f2, *actual2factor, 1e-9)); + EXPECT(assert_equal(f2 / *f2.sum(1), *actual2.toFactor(), 1e-9)); } /* ************************************************************************* */ -TEST( DiscreteConditional, constructors2) -{ +TEST(DiscreteConditional, constructors2) { // Declare keys and ordering - DiscreteKey C(0,2), B(1,2); - DecisionTreeFactor expected(C & B, "0.8 0.75 0.2 0.25"); + DiscreteKey C(0, 2), B(1, 2); + DecisionTreeFactor actual(C & B, "0.8 0.75 0.2 0.25"); Signature signature((C | B) = "4/1 3/1"); - DiscreteConditional actual(signature); - DecisionTreeFactor::shared_ptr actualFactor = actual.toFactor(); - EXPECT(assert_equal(expected, *actualFactor)); + DiscreteConditional expected(signature); + DecisionTreeFactor::shared_ptr expectedFactor = expected.toFactor(); + EXPECT(assert_equal(*expectedFactor, actual)); } /* ************************************************************************* */ -TEST( DiscreteConditional, constructors3) -{ +TEST(DiscreteConditional, constructors3) { // Declare keys and ordering - DiscreteKey C(0,2), B(1,2), A(2,2); - DecisionTreeFactor expected(C & B & A, "0.8 0.5 0.5 0.2 0.2 0.5 0.5 0.8"); + DiscreteKey C(0, 2), B(1, 2), A(2, 2); + DecisionTreeFactor actual(C & B & A, "0.8 0.5 0.5 0.2 0.2 0.5 0.5 0.8"); Signature signature((C | B, A) = "4/1 1/1 1/1 1/4"); - DiscreteConditional actual(signature); - DecisionTreeFactor::shared_ptr actualFactor = actual.toFactor(); - EXPECT(assert_equal(expected, *actualFactor)); + DiscreteConditional expected(signature); + DecisionTreeFactor::shared_ptr expectedFactor = expected.toFactor(); + EXPECT(assert_equal(*expectedFactor, actual)); } /* ************************************************************************* */ -TEST( DiscreteConditional, Combine) { +TEST(DiscreteConditional, Combine) { DiscreteKey A(0, 2), B(1, 2); vector c; c.push_back(boost::make_shared(A | B = "1/2 2/1")); c.push_back(boost::make_shared(B % "1/2")); DecisionTreeFactor factor(A & B, "0.111111 0.444444 0.222222 0.222222"); - DiscreteConditional expected(2, factor); - DiscreteConditional::shared_ptr actual = DiscreteConditional::Combine( - c.begin(), c.end()); - EXPECT(assert_equal(expected, *actual,1e-5)); + DiscreteConditional actual(2, factor); + auto expected = DiscreteConditional::Combine(c.begin(), c.end()); + EXPECT(assert_equal(*expected, actual, 1e-5)); } /* ************************************************************************* */ -int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +int main() { + TestResult tr; + return TestRegistry::runAllTests(tr); +} /* ************************************************************************* */ - diff --git a/gtsam/discrete/tests/testDiscreteMarginals.cpp b/gtsam/discrete/tests/testDiscreteMarginals.cpp index 4e9f956b6..e1eb92af3 100644 --- a/gtsam/discrete/tests/testDiscreteMarginals.cpp +++ b/gtsam/discrete/tests/testDiscreteMarginals.cpp @@ -146,8 +146,7 @@ TEST_UNSAFE( DiscreteMarginals, truss ) { /* ************************************************************************* */ // Second truss example with non-trivial factors -TEST_UNSAFE( DiscreteMarginals, truss2 ) { - +TEST_UNSAFE(DiscreteMarginals, truss2) { const int nrNodes = 5; const size_t nrStates = 2; @@ -160,40 +159,39 @@ TEST_UNSAFE( DiscreteMarginals, truss2 ) { // create graph and add three truss potentials DiscreteFactorGraph graph; - graph.add(key[0] & key[2] & key[4],"1 2 3 4 5 6 7 8"); - graph.add(key[1] & key[3] & key[4],"1 2 3 4 5 6 7 8"); - graph.add(key[2] & key[3] & key[4],"1 2 3 4 5 6 7 8"); + graph.add(key[0] & key[2] & key[4], "1 2 3 4 5 6 7 8"); + graph.add(key[1] & key[3] & key[4], "1 2 3 4 5 6 7 8"); + graph.add(key[2] & key[3] & key[4], "1 2 3 4 5 6 7 8"); // Calculate the marginals by brute force - vector allPosbValues = cartesianProduct( - key[0] & key[1] & key[2] & key[3] & key[4]); + vector allPosbValues = + cartesianProduct(key[0] & key[1] & key[2] & key[3] & key[4]); Vector T = Z_5x1, F = Z_5x1; for (size_t i = 0; i < allPosbValues.size(); ++i) { DiscreteFactor::Values x = allPosbValues[i]; double px = graph(x); - for (size_t j=0;j<5;j++) - if (x[j]) T[j]+=px; else F[j]+=px; - // cout << x[0] << " " << x[1] << " "<< x[2] << " " << x[3] << " " << x[4] << " :\t" << px << endl; + for (size_t j = 0; j < 5; j++) + if (x[j]) + T[j] += px; + else + F[j] += px; } // Check all marginals given by a sequential solver and Marginals -// DiscreteSequentialSolver solver(graph); + // DiscreteSequentialSolver solver(graph); DiscreteMarginals marginals(graph); - for (size_t j=0;j<5;j++) { - double sum = T[j]+F[j]; - T[j]/=sum; - F[j]/=sum; - -// // solver -// Vector actualV = solver.marginalProbabilities(key[j]); -// EXPECT(assert_equal((Vector(2) << F[j], T[j]), actualV)); + for (size_t j = 0; j < 5; j++) { + double sum = T[j] + F[j]; + T[j] /= sum; + F[j] /= sum; // Marginals vector table; - table += F[j],T[j]; - DecisionTreeFactor expectedM(key[j],table); + table += F[j], T[j]; + DecisionTreeFactor expectedM(key[j], table); DiscreteFactor::shared_ptr actualM = marginals(j); - EXPECT(assert_equal(expectedM, *boost::dynamic_pointer_cast(actualM))); + EXPECT(assert_equal( + expectedM, *boost::dynamic_pointer_cast(actualM))); } } diff --git a/gtsam/discrete/tests/testSignature.cpp b/gtsam/discrete/tests/testSignature.cpp index 830fc32fc..049c455f7 100644 --- a/gtsam/discrete/tests/testSignature.cpp +++ b/gtsam/discrete/tests/testSignature.cpp @@ -22,6 +22,7 @@ #include #include +#include using namespace std; using namespace gtsam; @@ -32,6 +33,11 @@ DiscreteKey X(0, 2), Y(1, 3), Z(2, 2); /* ************************************************************************* */ TEST(testSignature, simple_conditional) { Signature sig(X | Y = "1/1 2/3 1/4"); + Signature::Table table = *sig.table(); + vector row[3]{{0.5, 0.5}, {0.4, 0.6}, {0.2, 0.8}}; + CHECK(row[0] == table[0]); + CHECK(row[1] == table[1]); + CHECK(row[2] == table[2]); DiscreteKey actKey = sig.key(); LONGS_EQUAL(X.first, actKey.first); From 33f045729893b4d77ba27a3abbcb9e73a98fc520 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sat, 11 Jul 2020 13:19:48 -0400 Subject: [PATCH 184/199] Use dict notation in print --- gtsam/discrete/Potentials.cpp | 68 ++++++++++++++++++----------------- 1 file changed, 35 insertions(+), 33 deletions(-) diff --git a/gtsam/discrete/Potentials.cpp b/gtsam/discrete/Potentials.cpp index c4cdbe0ef..fe99ea975 100644 --- a/gtsam/discrete/Potentials.cpp +++ b/gtsam/discrete/Potentials.cpp @@ -15,50 +15,52 @@ * @author Frank Dellaert */ -#include #include +#include + #include +#include + using namespace std; namespace gtsam { - // explicit instantiation - template class DecisionTree ; - template class AlgebraicDecisionTree ; +// explicit instantiation +template class DecisionTree; +template class AlgebraicDecisionTree; - /* ************************************************************************* */ - double Potentials::safe_div(const double& a, const double& b) { - // cout << boost::format("%g / %g = %g\n") % a % b % ((a == 0) ? 0 : (a / b)); - // The use for safe_div is when we divide the product factor by the sum factor. - // If the product or sum is zero, we accord zero probability to the event. - return (a == 0 || b == 0) ? 0 : (a / b); - } +/* ************************************************************************* */ +double Potentials::safe_div(const double& a, const double& b) { + // cout << boost::format("%g / %g = %g\n") % a % b % ((a == 0) ? 0 : (a / b)); + // The use for safe_div is when we divide the product factor by the sum + // factor. If the product or sum is zero, we accord zero probability to the + // event. + return (a == 0 || b == 0) ? 0 : (a / b); +} - /* ******************************************************************************** */ - Potentials::Potentials() : - ADT(1.0) { - } +/* ******************************************************************************** + */ +Potentials::Potentials() : ADT(1.0) {} - /* ******************************************************************************** */ - Potentials::Potentials(const DiscreteKeys& keys, const ADT& decisionTree) : - ADT(decisionTree), cardinalities_(keys.cardinalities()) { - } +/* ******************************************************************************** + */ +Potentials::Potentials(const DiscreteKeys& keys, const ADT& decisionTree) + : ADT(decisionTree), cardinalities_(keys.cardinalities()) {} - /* ************************************************************************* */ - bool Potentials::equals(const Potentials& other, double tol) const { - return ADT::equals(other, tol); - } +/* ************************************************************************* */ +bool Potentials::equals(const Potentials& other, double tol) const { + return ADT::equals(other, tol); +} - /* ************************************************************************* */ - void Potentials::print(const string& s, - const KeyFormatter& formatter) const { - cout << s << "\n Cardinalities: "; - for(const DiscreteKey& key: cardinalities_) - cout << formatter(key.first) << "=" << formatter(key.second) << " "; - cout << endl; - ADT::print(" "); - } +/* ************************************************************************* */ +void Potentials::print(const string& s, const KeyFormatter& formatter) const { + cout << s << "\n Cardinalities: {"; + for (const DiscreteKey& key : cardinalities_) + cout << formatter(key.first) << ":" << key.second << ", "; + cout << "}" << endl; + ADT::print(" "); +} // // /* ************************************************************************* */ // template @@ -95,4 +97,4 @@ namespace gtsam { /* ************************************************************************* */ -} // namespace gtsam +} // namespace gtsam From 621e79f06c27c66bd9804e1c462e494cfc2522ac Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 17:34:16 -0400 Subject: [PATCH 185/199] Add explicit HMM example --- examples/DiscreteBayesNetExample.cpp | 1 + examples/HMMExample.cpp | 94 ++++++++++++++++++++++++++++ 2 files changed, 95 insertions(+) create mode 100644 examples/HMMExample.cpp diff --git a/examples/DiscreteBayesNetExample.cpp b/examples/DiscreteBayesNetExample.cpp index 3531fd723..629043431 100644 --- a/examples/DiscreteBayesNetExample.cpp +++ b/examples/DiscreteBayesNetExample.cpp @@ -18,6 +18,7 @@ #include #include +#include #include diff --git a/examples/HMMExample.cpp b/examples/HMMExample.cpp new file mode 100644 index 000000000..a56058633 --- /dev/null +++ b/examples/HMMExample.cpp @@ -0,0 +1,94 @@ +/* ---------------------------------------------------------------------------- + + * GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, + * Atlanta, Georgia 30332-0415 + * All Rights Reserved + * Authors: Frank Dellaert, et al. (see THANKS for the full author list) + + * See LICENSE for the license information + + * -------------------------------------------------------------------------- */ + +/** + * @file DiscreteBayesNetExample.cpp + * @brief Hidden Markov Model example, discrete. + * @author Frank Dellaert + * @date July 12, 2020 + */ + +#include +#include +#include + +#include +#include + +using namespace std; +using namespace gtsam; + +int main(int argc, char **argv) { + const int nrNodes = 4; + const size_t nrStates = 3; + + // Define variables as well as ordering + Ordering ordering; + vector keys; + for (int k = 0; k < nrNodes; k++) { + DiscreteKey key_i(k, nrStates); + keys.push_back(key_i); + ordering.emplace_back(k); + } + + // Create HMM as a DiscreteBayesNet + DiscreteBayesNet hmm; + + // Define backbone + const string transition = "8/1/1 1/8/1 1/1/8"; + for (int k = 1; k < nrNodes; k++) { + hmm.add(keys[k] | keys[k - 1] = transition); + } + + // Add some measurements, not needed for all time steps! + hmm.add(keys[0] % "7/2/1"); + hmm.add(keys[1] % "1/9/0"); + hmm.add(keys.back() % "5/4/1"); + + // print + hmm.print("HMM"); + + // Convert to factor graph + DiscreteFactorGraph factorGraph(hmm); + + // Create solver and eliminate + // This will create a DAG ordered with arrow of time reversed + DiscreteBayesNet::shared_ptr chordal = + factorGraph.eliminateSequential(ordering); + chordal->print("Eliminated"); + + // solve + DiscreteFactor::sharedValues mpe = chordal->optimize(); + GTSAM_PRINT(*mpe); + + // We can also sample from it + cout << "\n10 samples:" << endl; + for (size_t k = 0; k < 10; k++) { + DiscreteFactor::sharedValues sample = chordal->sample(); + GTSAM_PRINT(*sample); + } + + // Or compute the marginals. This re-eliminates the FG into a Bayes tree + cout << "\nComputing Node Marginals .." << endl; + DiscreteMarginals marginals(factorGraph); + for (int k = 0; k < nrNodes; k++) { + Vector margProbs = marginals.marginalProbabilities(keys[k]); + stringstream ss; + ss << "marginal " << k; + print(margProbs, ss.str()); + } + + // TODO(frank): put in the glue to have DiscreteMarginals produce *arbitrary* + // joints efficiently, by the Bayes tree shortcut magic. All the code is there + // but it's not yet connected. + + return 0; +} From 947d7377b49b5863891995c410652eb0fc212277 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Sun, 12 Jul 2020 23:25:07 -0400 Subject: [PATCH 186/199] Modernized sample function --- gtsam/discrete/DiscreteConditional.cpp | 51 ++++++-------------------- 1 file changed, 12 insertions(+), 39 deletions(-) diff --git a/gtsam/discrete/DiscreteConditional.cpp b/gtsam/discrete/DiscreteConditional.cpp index acd0cefee..ac7c58405 100644 --- a/gtsam/discrete/DiscreteConditional.cpp +++ b/gtsam/discrete/DiscreteConditional.cpp @@ -184,55 +184,28 @@ size_t DiscreteConditional::solve(const Values& parentsValues) const { /* ******************************************************************************** */ size_t DiscreteConditional::sample(const Values& parentsValues) const { - - static mt19937 rng(2); // random number generator - - bool debug = ISDEBUG("DiscreteConditional::sample"); + static mt19937 rng(2); // random number generator // Get the correct conditional density - ADT pFS = choose(parentsValues); // P(F|S=parentsValues) - if (debug) - GTSAM_PRINT(pFS); + ADT pFS = choose(parentsValues); // P(F|S=parentsValues) - // get cumulative distribution function (cdf) - // TODO, only works for one key now, seems horribly slow this way + // TODO(Duy): only works for one key now, seems horribly slow this way assert(nrFrontals() == 1); - Key j = (firstFrontalKey()); - size_t nj = cardinality(j); - vector cdf(nj); + Key key = firstFrontalKey(); + size_t nj = cardinality(key); + vector p(nj); Values frontals; - double sum = 0; for (size_t value = 0; value < nj; value++) { - frontals[j] = value; - double pValueS = pFS(frontals); // P(F=value|S=parentsValues) - sum += pValueS; // accumulate - if (debug) - cout << sum << " "; - if (pValueS == 1) { - if (debug) - cout << "--> " << value << endl; - return value; // shortcut exit + frontals[key] = value; + p[value] = pFS(frontals); // P(F=value|S=parentsValues) + if (p[value] == 1.0) { + return value; // shortcut exit } - cdf[value] = sum; } - - // inspired by http://www.boost.org/doc/libs/1_46_1/doc/html/boost_random/tutorial.html - uniform_real_distribution dist(0, cdf.back()); - size_t sampled = lower_bound(cdf.begin(), cdf.end(), dist(rng)) - cdf.begin(); - if (debug) - cout << "-> " << sampled << endl; - - return sampled; - - return 0; + std::discrete_distribution distribution(p.begin(), p.end()); + return distribution(rng); } -/* ******************************************************************************** */ -//void DiscreteConditional::permuteWithInverse( -// const Permutation& inversePermutation) { -// IndexConditionalOrdered::permuteWithInverse(inversePermutation); -// Potentials::permuteWithInverse(inversePermutation); -//} /* ******************************************************************************** */ }// namespace From 52927c1c5b8a5b3e71ce8184fb6fcb4ca4c7b83b Mon Sep 17 00:00:00 2001 From: yetongumich Date: Mon, 13 Jul 2020 01:45:22 -0400 Subject: [PATCH 187/199] modify testNoiseModel to use loss instead of error --- gtsam/linear/tests/testNoiseModel.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/gtsam/linear/tests/testNoiseModel.cpp b/gtsam/linear/tests/testNoiseModel.cpp index dd1d46b42..42d68a603 100644 --- a/gtsam/linear/tests/testNoiseModel.cpp +++ b/gtsam/linear/tests/testNoiseModel.cpp @@ -182,8 +182,9 @@ TEST(NoiseModel, ConstrainedMixed ) EXPECT(assert_equal(Vector3(0.5, 1.0, 0.5),d->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.5, 0.0, 0.5),d->whiten(feasible))); - DOUBLES_EQUAL(0.5 * (1000.0 + 0.25 + 0.25),d->error(infeasible),1e-9); - DOUBLES_EQUAL(0.5 * 0.5,d->error(feasible),1e-9); + DOUBLES_EQUAL(0.5 * (1000.0 + 0.25 + 0.25),d->loss(d->squaredMahalanobisDistance(infeasible)),1e-9); + DOUBLES_EQUAL(0.5, d->squaredMahalanobisDistance(feasible),1e-9); + DOUBLES_EQUAL(0.5 * 0.5, d->loss(0.5),1e-9); } /* ************************************************************************* */ @@ -197,8 +198,9 @@ TEST(NoiseModel, ConstrainedAll ) EXPECT(assert_equal(Vector3(1.0, 1.0, 1.0),i->whiten(infeasible))); EXPECT(assert_equal(Vector3(0.0, 0.0, 0.0),i->whiten(feasible))); - DOUBLES_EQUAL(0.5 * 1000.0 * 3.0,i->error(infeasible),1e-9); - DOUBLES_EQUAL(0.0,i->error(feasible),1e-9); + DOUBLES_EQUAL(0.5 * 1000.0 * 3.0,i->loss(i->squaredMahalanobisDistance(infeasible)),1e-9); + DOUBLES_EQUAL(0.0, i->squaredMahalanobisDistance(feasible), 1e-9); + DOUBLES_EQUAL(0.0, i->loss(0.0),1e-9); } /* ************************************************************************* */ @@ -717,7 +719,8 @@ TEST(NoiseModel, lossFunctionAtZero) EQUALITY(cov, gaussian->covariance());\ EXPECT(assert_equal(white, gaussian->whiten(e)));\ EXPECT(assert_equal(e, gaussian->unwhiten(white)));\ - EXPECT_DOUBLES_EQUAL(0.5 * 251, gaussian->error(e), 1e-9);\ + EXPECT_DOUBLES_EQUAL(251.0, gaussian->squaredMahalanobisDistance(e), 1e-9);\ + EXPECT_DOUBLES_EQUAL(0.5 * 251.0, gaussian->loss(251.0), 1e-9);\ Matrix A = R.inverse(); Vector b = e;\ gaussian->WhitenSystem(A, b);\ EXPECT(assert_equal(I, A));\ From 529f6091d30eddc76119a28f674e41a104df45d5 Mon Sep 17 00:00:00 2001 From: yetongumich Date: Mon, 13 Jul 2020 02:01:40 -0400 Subject: [PATCH 188/199] change doc --- doc/robust.pdf | Bin 205572 -> 205563 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/doc/robust.pdf b/doc/robust.pdf index 45c023384c723a506f5bb48b2bfcab5aa5b338c3..67b853f44eefdf176e8b73bad1a6fd3da83f93d8 100644 GIT binary patch delta 3753 zcmbt%X*3iL*u61!BKz1fmMoFk%=V)p`_5nz5=M*^Wov{CWgR6&K_U(WE@7MSFbniXqxgVZ$?sLwK?%_M6@ufjwCncFf0Q6zXoDz0Cv{)gkdqB7!;J~ zPJ}_>*RWWm2N4BFp)u~rYp{P3P8*GOC&G#UoIEu>J-tvc7!dqE7Fs(OY)no;rGsD=_y-k5Y z{Zb(CN33W|jm*R53~?VrwdvfDPupGgjQl0V3JJ)A8X2vRl5>%zrz^AaqMqI5Nm~LE z-1^1hY>f@T+eJ#ckygmb>py+Vaa4wW2xt7 zf8q(?c~I@sSnUH?jH3KI6b{D|7!=^??#mOBzv0Ztn13U9uc*eRP@doj_2+yu$En2( zrg=8!uV2bI#}Js72rV_pftBs7Z%!P3)1!*peH*ojey+m{s zMV)Nu9Uk|cQbpY8X${>kNBgRBm%PyO^&9%upvHc%(x@!dB$B};SkbQb>tfQP*E`px zDll^d@vMA*wGA`aTNShBbt_vKfHZ1t;kBGPDC|WA_9uv-8p1EDI~d*^%6o}bnEpg% z-YoF`Xi-DTuxiXJO8hu8E%q!*METO%Dm~BFwIDm4VnIzPj4w>7o7E*@6CuK8iu){ka14!Df2CO=@^TnQ?=b(^x`=P|#LI@{zb z^3)%n?QIKCm8V)K9))r|IX^dl6k7D=6k@dOWpX{gFQ~wKS(SH5!B*-r2ZHdF4rh8GZX0H;`fb&e;ihkd|haVe#Xk{YGb~tzntn`0BvQ^q%L<^V!q~@FOX! zlKaaK&rPJcZ+1V=4Lqfd`2>|mq`yDzPFlHMOKEYzJlS+k0_{`*BlZQ4Y(GG)PUXZ! z7ixAMjogP=b~MsOy-LQ+gsKh8l+Ne_GEX77yX2I+`?MPdgv>~zD3zMA)yUD$ukxV- z%^Fh;)L(KCPtoz!9z4DTA2Wgi{AZRnCI48Jn6(K9cbN=D@>P!~l$`H;RI4j%>=0s2 z$(t9(00|=QT@r37arX&9PGZRN-43zw{z0IBU!I18h|m$xVY1QUtLtki)Fbe@eN=~sip}Y zb^a*rW@PXqc7q0DPP1*1|K*~YDR5ThvZlJ#?B4tHZd%;4Esm(ub<5M^jL1pc z;P-nWckM*b&6D$}D^l5HogbsG%(A9S2DBmENMh0C=Y>xg(eQK+j#*`0{&N`z3 z!DqdGzx9ICzQA3wKbMqXK>2kYJFy+9@2_M!uFM(klaB}b_bAN`;vWR2%VnOP2eoXj zOPo4+|H&hy<9ouu{k{|rvZ=99LQ@FSd-*4=3j0k*Lnqe%$|~pyj~>a%!lO^UzqxKQ z?3}>JaTnKk-PJgbjp}Y;v9HsuEbMlUnQdVq?P_`ovI8@j5!crXQ51!i8)v>SkE@7b z5Zduls4Hzlv0ZivYkUDaMBZsin9x!@@>?Je1m_oot#_ZUW*owq4+j{FJ?9aJuD3{m z&&vO*LPKQAw_C(|{|4yWp*0^3AuGn)2?Y@156c}t+08q&V9~RluTSrNr=LqtQAanY zrF~0IGgfao5*Uh!rO=<-(HArjy9j#nql3jCGS|-v(M6vM5ct_e1E_2oK0k&Ax38xx zOI|G>?kaZY(3#wOqs|K{GfHb$MNJrnCaq4nh8w$V<@^QV9S1dB+g(TACVme*nyK!p zj`U-9dHWYrrl%#colB;t_cY& zGnMDAw3z!#g&5IkIVW~?Z5M0tnPK?QzMN;GHVL7VIpR*e(fwyX`K(^`KWR0A$$J_=O}wxDvXpKZ#{f>lx3Oy*?1gpV#&_(2JV*!gp|AF9@ii@RP4pFr+16g7 zg08f_^w)$rUw>+y1thgwDcnHr(hmb}d!x`P3=3=!fD#rIgt5_mo9Vd z1P6Y6fZ}hY_-HN8sFy?Yg@V+8@-6t0tfzRf#s1xZMm4`8v9m-6jaHAT6rOrvynIw* z&_lPLKU{|mDziAfZ&oBBVHglUCp#@~}J)d=8H% zR1%5=GTO(55i%?)G4`VrBpU>JvPP(;7_{nKAiIgV>C`?SmKf`Ew5m^4>#q`s(r_z+ zT|2!q>1iHYw=8Tkj{zEREWg!?Sc&XQ*8w$hY0UJHUs%%k!aEjzG6KRl|0^CZo`&#} zGjs>G2`<5AJu^o)yzYWh>i+<^3nS>-oQYp+u2l7;=YqLo;H8utHiG*7(iCY$u4MSP z3u72`WZ}t5;U582;k1Am@Uwbk4&kf$JB22Mlgz}+;cZQ;yyy}&Mo6W~3eE!6UiAFV zbY5KHK{MXb%#0jRzgQz1%uiFqiTTPRaMA}m?Lu)8M`6j`kWFn%pG!P=8i2)TAjBn3 zo5T@vG8+pZP}b`0XC_;)(i$H5#cc8Q;=xm`s}W)TAHgn-Rk+gCLQd;P?`6HIu2Cw( zu{X5Iu@08Ha*uzf7+txui~1Q2Rg~}*4UxGWG(3~y>{gVHI}v!2Sn-BKYbIvr{p{iJ zPxOw7(p?OXMBY82Z?m|v_mur@N&iZz-bkbM6{5Fho7Uz{jewAT??IJkMuP%LGx>iI zugrgsnvI;yrT>!cs=jWN`W1FZfb;zKo-B6MsE4N{(+4PW!ph;nUmd5r4`|fgXAM>6 zM#B(L6cnln&FKaM75*P>-1&f{|C(u{#O71 delta 3790 zcmbu?_dgYmqsMW_LH0;y;e>=v&N|$mFbQA?s*?XeZxyDGg1FR=!O()?+SsI={O`Bk2cE57YkqpNc} zayh5Rhm}G#Tm!t z`^%c|y&o$rb8THYlbRXLl8CmheS$@8z_M*?@N7;)dX(AMx5!3k?{BXePk+zyvtii{ zqGG8F0wqWjX!}_^oa-wY&2>{k zkYd4Sv+wLS!iuUdLfKr;Mo`zYN~oKwVP@oK4(yKViJbmtS#CXNTKKBk{p7Z`uNDaaOa$w4)tiBPdffW=?wF#>McXu;tj*;E4J&oqrAtz!sp{7(LO$kU%+@AIe|%K~ z!$fT2OKAn1=P}gxAl1@AC8swhALUmc0(rQV68ep#ea@k{;0IuWmk{^+6G186zrVum zo-ws!6cg@stz0dofiAbo=ge@BRU(BF|=B)VK(V zYtW6P3L+_iuMh22$0MtX!uk!Zdq`v-%)}$i67g<$(#4X7Sm&2krOlkNP;)paa{USI zk)gLUc&zV>z&w?(ddxJUC7|=ho8`@Np}oM{44uSs^_}mLkr=KjnheW5z4V;duj-Zt zro4h{1sI4o!yWY5uJUnlasZ!YLisqiP8m%;h#~>1&QPR)ck!6K0|R%elW9vG$gt;? z2*aPBMIPY|1C`ZA_8gkhm+i660KTf}mFfwXD;f5=8pH8~dx#p{vZsf0h?>zt`cP8$ zzFgH&kZnQv>xKyC1dXZwfPb4N2u8R3Sf=-e>d|eFi!?9P*qoU^8P6Qt@1%N+1D7zK z=EWiQ&KIz}TAB+p_(cuygo(t%dO%BUrep}y* zD@e8c1bmf{O5750P`zrdn+6}+5W!rF8*qBp44?ary+~kBP0UK-YLdHr?Kbd3oZE$9 z2cPus0SEJXBa1m-4CozCaoxGr9%@M^Up2V_^?$ zUuYuOY6Lf{o;5!7*Q%WZPf_eLa%QC`{j?E0WXs7L=SDHEfW~Y%w_c&1X;PF}ZywYX zX$l`Y6!ZcSgk)tF)%B*^XtmlLU&DM@j{A`dfmGnyMZ2!qmd7X77eQh(G=;0Jj_)sV zl{B)7>y^Hs7-H}@ch%Mb7A|jM6j!Y!QwU)XMwHYSO>+&#e-8liMO`Mea%yumKNc4#N*!&ISm^ZHIy4=NC%-GTX9vMoNp{c^0o&-bXrPPF;mFoAVD zTdyJTykdIZ(5Jm=-qJ^HVEe_>5i=9xeQb*-?SPxD{W87FSIp(7_z5&>{jeCk(j(=VE_K3E+C>zn9P zpZYr`Qj}o@Y3U%TAAB5;^V@!f4utw&7^Nmk!e1kQT-h^vsNRD(w7<^3w_o4Zj?R^g zi2oL<1`o}aBFAKw6F)wB)4>zadXv&=SkCvu>*cV2ig+>kP-wwy>SRSz7b8fdpd_Z? zTQvF=LSyB}^(B54sWLnF)8%zEG&TFtr%0_ysmbz{eTLi)tZ)pNbtc?zPgh zI>Ct>LnV$aVpn(j!K+Np@Y{-Eq$G79@f$Dh03H5?&x!>W!c>VP#G2vi<$AZTR026Z zx_p(z;?9vAUmiR8#D}IIH1LbR0JrEkStvY=`e4?*D2SJrKhF?8(g=KJ1wQI2`}9;P z0bUx5BqtIjqe06JkBxip+U`%Owu-OZnbU(lY`$#b;}U(#b0WP-SnP)O2mAYOTh8%ZKr@ zCjL+`IB5p^_&I5@oSXX_)1{^|G-uZ7eyHUY7+u&GQ(G+8CsGJhsePY8v@3K)Q1ior z$p&SmSqrGqiU;BX=~-oo= zw5YfC|5B!}IaZ4)Sl6m!p6@-3c;vOq=;isdS|iQ03R5WWu{G_6Rx^I1UKhWL6oMix zFa27-&L31?9T=P1g54y=R5qs$N?dZQZX;okJkOU>{SP&R^NdboP%S_CDx<~zs_-}s zZEMt3tc(#HC%l|Zeaf_l`64@$N7$dIoDC#XHbg>b+4=(`#COW0d70~ka1)Ush{=!7 zS9fUv z3sVjBAF1}I-SwNc^BRk-)xM0i3Eh2LpX65u`1%M|jyf9`&#TD3v8hr`HBI432QXD+ zfrHqLmBv%I#dFzaUi{!_T63%W2}zc(*->`?O+#_#20C4TQBv&M8<<9?#?3pQOfGz) zW_6>7w9=1ljuq{px(SkZ#H6x|NRDXKK@yCyyiv_yzT4yHM&qpQd+KXH_77ca-#pDq zM!pf^HvX8kLp6yd&fmmn>>9rvsSZh|EK*uSyH@xJZgxwH0+C7Vyb+~b?+eM5WDD=xc49`#f5(_n%? zyIu4B#7MCAMRvSCgssAg$v{j+pH~$BIi#p|_Ep~5R^IWb1b?#ccThP|DbvDEr75x= z{y?m*%6J|z5*r1)J{xpNc1^Rtfl8shZc!-js=|p7q82paz}`5=p;~ z?c$16&suv^1OnM*lx{@7r!g?p<68*TxAWjY^>h8s@QMTL3XR-|_ozrLLzygqwxRPj zpoVN`l#9@x+N>DOC%^l2PiD6-nbvsuC2>h~^lgg;ziI4hE08PmZ6?>PtDFY9Hq5pc zuDqqzEelS&l)O4;{+EV*a*fQf9M@%;wFa3NqQrRH#po2 z`UVj#lPt1-dH5>Ni(jDVfJPLZG59(g0tSaEBTxurCK&{j`k!oE{Z9f2|9|IcVE>nx zaE=TB8QtC&bWS6!`>@y_7Xc{=_Q-9+Ps&o57C!XX*ys8(a!@)8I$J+dKPxj<63ETe MglGHq-v)H}FAO9e_5c6? From 84bb4185298a080670be7235465b9730932e4352 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 14 Jul 2020 02:23:19 -0400 Subject: [PATCH 189/199] fix serialization warning for boost::optional --- gtsam/navigation/PreintegratedRotation.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index 9346f749a..0e0559a32 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -62,8 +62,14 @@ struct GTSAM_EXPORT PreintegratedRotationParams { void serialize(ARCHIVE & ar, const unsigned int /*version*/) { namespace bs = ::boost::serialization; ar & BOOST_SERIALIZATION_NVP(gyroscopeCovariance); - ar & BOOST_SERIALIZATION_NVP(omegaCoriolis); ar & BOOST_SERIALIZATION_NVP(body_P_sensor); + + // Provide support for Eigen::Matrix in boost::optional + bool omegaCoriolisFlag = omegaCoriolis.is_initialized(); + ar & boost::serialization::make_nvp("omegaCoriolisFlag", omegaCoriolisFlag); + if (omegaCoriolisFlag) { + ar & BOOST_SERIALIZATION_NVP(*omegaCoriolis); + } } #ifdef GTSAM_USE_QUATERNIONS From c76ebcf9e7a19ff3908e398d452f369000a1a049 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 14 Jul 2020 08:49:45 -0400 Subject: [PATCH 190/199] Partial Specialization --- gtsam/base/Matrix.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/gtsam/base/Matrix.h b/gtsam/base/Matrix.h index 37ae1dd9a..1c1138438 100644 --- a/gtsam/base/Matrix.h +++ b/gtsam/base/Matrix.h @@ -610,5 +610,11 @@ namespace boost { split_free(ar, m, version); } + // specialized to Matrix for MATLAB wrapper + template + void serialize(Archive& ar, gtsam::Matrix& m, const unsigned int version) { + split_free(ar, m, version); + } + } // namespace serialization } // namespace boost From 4b4a0e532f7089d9cf8ba569ded01dcd19f944b0 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 14 Jul 2020 08:50:20 -0400 Subject: [PATCH 191/199] Add BayesNet-inst.h at end of BayesNet.h --- examples/DiscreteBayesNetExample.cpp | 2 +- examples/HMMExample.cpp | 2 +- gtsam/discrete/tests/testDiscreteBayesTree.cpp | 2 +- gtsam/discrete/tests/testDiscreteFactorGraph.cpp | 2 +- gtsam/inference/BayesNet.h | 4 +++- 5 files changed, 7 insertions(+), 5 deletions(-) diff --git a/examples/DiscreteBayesNetExample.cpp b/examples/DiscreteBayesNetExample.cpp index 629043431..5dca116c3 100644 --- a/examples/DiscreteBayesNetExample.cpp +++ b/examples/DiscreteBayesNetExample.cpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include diff --git a/examples/HMMExample.cpp b/examples/HMMExample.cpp index a56058633..ee861e381 100644 --- a/examples/HMMExample.cpp +++ b/examples/HMMExample.cpp @@ -18,7 +18,7 @@ #include #include -#include +#include #include #include diff --git a/gtsam/discrete/tests/testDiscreteBayesTree.cpp b/gtsam/discrete/tests/testDiscreteBayesTree.cpp index 11a88af59..ecf485036 100644 --- a/gtsam/discrete/tests/testDiscreteBayesTree.cpp +++ b/gtsam/discrete/tests/testDiscreteBayesTree.cpp @@ -19,7 +19,7 @@ #include #include #include -#include +#include #include using namespace boost::assign; diff --git a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp index 7a0e1eaf7..1defd5acf 100644 --- a/gtsam/discrete/tests/testDiscreteFactorGraph.cpp +++ b/gtsam/discrete/tests/testDiscreteFactorGraph.cpp @@ -19,7 +19,7 @@ #include #include #include -#include +#include #include diff --git a/gtsam/inference/BayesNet.h b/gtsam/inference/BayesNet.h index a69fb9b8c..0597ece98 100644 --- a/gtsam/inference/BayesNet.h +++ b/gtsam/inference/BayesNet.h @@ -69,4 +69,6 @@ namespace gtsam { void saveGraph(const std::string &s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const; }; -} \ No newline at end of file +} + +#include From aca002fc126c521d750b4c0f091669e6f34e1fe7 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Tue, 14 Jul 2020 13:25:08 -0400 Subject: [PATCH 192/199] correct indentation for Python version --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index f6f012118..a520d4d74 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -607,7 +607,7 @@ endif() message(STATUS "Cython toolbox flags ") print_config_flag(${GTSAM_INSTALL_CYTHON_TOOLBOX} "Install Cython toolbox ") if(GTSAM_INSTALL_CYTHON_TOOLBOX) - message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") + message(STATUS " Python version : ${GTSAM_PYTHON_VERSION}") endif() message(STATUS "===============================================================") From 94bb08ed34ab87e55f88f88f71dafb3c975daab8 Mon Sep 17 00:00:00 2001 From: Mike Sheffler Date: Tue, 14 Jul 2020 13:03:21 -0700 Subject: [PATCH 193/199] Missing BOOST_SERIALIZATION_NVP wrapper macro for an argument to be serialized --- gtsam/geometry/SOn.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/geometry/SOn.h b/gtsam/geometry/SOn.h index f44c578cc..a6392c2f9 100644 --- a/gtsam/geometry/SOn.h +++ b/gtsam/geometry/SOn.h @@ -340,7 +340,7 @@ void serialize( const unsigned int file_version ) { Matrix& M = Q.matrix_; - ar& M; + ar& BOOST_SERIALIZATION_NVP(M); } /* From 23db3bb721fc5603e7fb9363029b88e92ac480e6 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 14 Jul 2020 23:24:47 +0200 Subject: [PATCH 194/199] docker tag and pip3 fixes; add a readme --- docker/README.md | 16 ++++++++++++++++ docker/ubuntu-boost-tbb/build.sh | 3 +++ docker/ubuntu-gtsam-python-vnc/Dockerfile | 6 +++--- docker/ubuntu-gtsam-python/Dockerfile | 4 ++-- docker/ubuntu-gtsam/Dockerfile | 6 +++--- 5 files changed, 27 insertions(+), 8 deletions(-) create mode 100644 docker/README.md create mode 100755 docker/ubuntu-boost-tbb/build.sh diff --git a/docker/README.md b/docker/README.md new file mode 100644 index 000000000..4dec63b94 --- /dev/null +++ b/docker/README.md @@ -0,0 +1,16 @@ +# Instructions + +Build all docker images, in order: + +```bash +(cd ubuntu-boost-tbb && exec build.sh) +(cd ubuntu-gtsam && exec build.sh) +(cd ubuntu-gtsam-python && exec build.sh) +(cd ubuntu-gtsam-python-vnc && exec build.sh) +``` + +Then launch with: + + docker run dellaert/ubuntu-gtsam-python-vnc:bionic + + diff --git a/docker/ubuntu-boost-tbb/build.sh b/docker/ubuntu-boost-tbb/build.sh new file mode 100755 index 000000000..2dac4c3db --- /dev/null +++ b/docker/ubuntu-boost-tbb/build.sh @@ -0,0 +1,3 @@ +# Build command for Docker image +# TODO(dellaert): use docker compose and/or cmake +docker build --no-cache -t dellaert/ubuntu-boost-tbb:bionic . diff --git a/docker/ubuntu-gtsam-python-vnc/Dockerfile b/docker/ubuntu-gtsam-python-vnc/Dockerfile index 26f995c56..61ecd9b9a 100644 --- a/docker/ubuntu-gtsam-python-vnc/Dockerfile +++ b/docker/ubuntu-gtsam-python-vnc/Dockerfile @@ -1,18 +1,18 @@ # This GTSAM image connects to the host X-server via VNC to provide a Graphical User Interface for interaction. # Get the base Ubuntu/GTSAM image from Docker Hub -FROM dellaert/ubuntu-gtsam-python:latest +FROM dellaert/ubuntu-gtsam-python:bionic # Things needed to get a python GUI ENV DEBIAN_FRONTEND noninteractive RUN apt install -y python-tk -RUN pip install matplotlib +RUN python3 -m pip install matplotlib # Install a VNC X-server, Frame buffer, and windows manager RUN apt install -y x11vnc xvfb fluxbox # Finally, install wmctrl needed for bootstrap script -RUN apt install -y wmctrl +RUN apt install -y wmctrl # Copy bootstrap script and make sure it runs COPY bootstrap.sh / diff --git a/docker/ubuntu-gtsam-python/Dockerfile b/docker/ubuntu-gtsam-python/Dockerfile index 71787d480..c733ceb19 100644 --- a/docker/ubuntu-gtsam-python/Dockerfile +++ b/docker/ubuntu-gtsam-python/Dockerfile @@ -1,7 +1,7 @@ # GTSAM Ubuntu image with Python wrapper support. # Get the base Ubuntu/GTSAM image from Docker Hub -FROM dellaert/ubuntu-gtsam:latest +FROM dellaert/ubuntu-gtsam:bionic # Install pip RUN apt-get install -y python3-pip python3-dev @@ -25,7 +25,7 @@ RUN cmake \ RUN make -j4 install && make clean # Needed to run python wrapper: -RUN echo 'export PYTHONPATH=/usr/local/cython/:$PYTHONPATH' >> /root/.bashrc +RUN echo 'export PYTHONPATH=/usr/local/cython/:$PYTHONPATH' >> /root/.bashrc # Run bash CMD ["bash"] diff --git a/docker/ubuntu-gtsam/Dockerfile b/docker/ubuntu-gtsam/Dockerfile index 393443361..187c76314 100644 --- a/docker/ubuntu-gtsam/Dockerfile +++ b/docker/ubuntu-gtsam/Dockerfile @@ -1,10 +1,10 @@ # Ubuntu image with GTSAM installed. Configured with Boost and TBB support. # Get the base Ubuntu image from Docker Hub -FROM dellaert/ubuntu-boost-tbb:latest +FROM dellaert/ubuntu-boost-tbb:bionic # Install git -RUN apt-get update && \ +RUN apt-get update && \ apt-get install -y git # Install compiler @@ -30,7 +30,7 @@ RUN cmake \ RUN make -j4 install && make clean # Needed to link with GTSAM -RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib:LD_LIBRARY_PATH' >> /root/.bashrc +RUN echo 'export LD_LIBRARY_PATH=/usr/local/lib:LD_LIBRARY_PATH' >> /root/.bashrc # Run bash CMD ["bash"] From 17873485db36531a2a360b4bd609139e2c0e7128 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Tue, 14 Jul 2020 23:33:25 +0200 Subject: [PATCH 195/199] complete README --- docker/README.md | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/docker/README.md b/docker/README.md index 4dec63b94..0c136f94c 100644 --- a/docker/README.md +++ b/docker/README.md @@ -3,14 +3,19 @@ Build all docker images, in order: ```bash -(cd ubuntu-boost-tbb && exec build.sh) -(cd ubuntu-gtsam && exec build.sh) -(cd ubuntu-gtsam-python && exec build.sh) -(cd ubuntu-gtsam-python-vnc && exec build.sh) +(cd ubuntu-boost-tbb && ./build.sh) +(cd ubuntu-gtsam && ./build.sh) +(cd ubuntu-gtsam-python && ./build.sh) +(cd ubuntu-gtsam-python-vnc && ./build.sh) ``` Then launch with: - docker run dellaert/ubuntu-gtsam-python-vnc:bionic + docker run -p 5900:5900 dellaert/ubuntu-gtsam-python-vnc:bionic + +Then open a remote VNC X client, for example: + + sudo apt-get install tigervnc-viewer + xtigervncviewer :5900 From 02e8966d4f33a615a338fc17fa024c7387167bb9 Mon Sep 17 00:00:00 2001 From: acxz <17132214+acxz@users.noreply.github.com> Date: Wed, 15 Jul 2020 23:19:44 -0400 Subject: [PATCH 196/199] set default initialization --- gtsam/nonlinear/AdaptAutoDiff.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam/nonlinear/AdaptAutoDiff.h b/gtsam/nonlinear/AdaptAutoDiff.h index ff059ef78..682cca29a 100644 --- a/gtsam/nonlinear/AdaptAutoDiff.h +++ b/gtsam/nonlinear/AdaptAutoDiff.h @@ -57,7 +57,7 @@ class AdaptAutoDiff { if (H1 || H2) { // Get derivatives with AutoDiff const double* parameters[] = {v1.data(), v2.data()}; - double rowMajor1[M * N1], rowMajor2[M * N2]; // on the stack + double rowMajor1[M * N1] = {}, rowMajor2[M * N2] = {}; // on the stack double* jacobians[] = {rowMajor1, rowMajor2}; success = AutoDiff::Differentiate( f, parameters, M, result.data(), jacobians); From 2605e10c27cdeacf5a65ff4dbc1f332e6eea44d0 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 21 Jul 2020 11:04:36 -0400 Subject: [PATCH 197/199] Fixed conventions for Jacobians --- GTSAM-Concepts.md | 4 +- gtsam/geometry/Pose3.cpp | 158 ++++++++++++++++++++------------------- gtsam/geometry/Pose3.h | 80 ++++++++++---------- 3 files changed, 122 insertions(+), 120 deletions(-) diff --git a/GTSAM-Concepts.md b/GTSAM-Concepts.md index a6cfee984..953357ede 100644 --- a/GTSAM-Concepts.md +++ b/GTSAM-Concepts.md @@ -72,9 +72,9 @@ A Lie group is both a manifold *and* a group. Hence, a LIE_GROUP type should imp However, we now also need to be able to evaluate the derivatives of compose and inverse. Hence, we have the following extra valid static functions defined in the struct `gtsam::traits`: -* `r = traits::Compose(p,q,Hq,Hp)` +* `r = traits::Compose(p,q,Hp,Hq)` * `q = traits::Inverse(p,Hp)` -* `r = traits::Between(p,q,Hq,H2p)` +* `r = traits::Between(p,q,Hp,Hq)` where above the *H* arguments stand for optional Jacobian arguments. That makes it possible to create factors implementing priors (PriorFactor) or relations between two instances of a Lie group type (BetweenFactor). diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 31033a027..0ee19ef76 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -19,8 +19,10 @@ #include #include -#include #include +#include +#include +#include using namespace std; @@ -36,10 +38,10 @@ Pose3::Pose3(const Pose2& pose2) : } /* ************************************************************************* */ -Pose3 Pose3::Create(const Rot3& R, const Point3& t, OptionalJacobian<6, 3> H1, - OptionalJacobian<6, 3> H2) { - if (H1) *H1 << I_3x3, Z_3x3; - if (H2) *H2 << Z_3x3, R.transpose(); +Pose3 Pose3::Create(const Rot3& R, const Point3& t, OptionalJacobian<6, 3> HR, + OptionalJacobian<6, 3> Ht) { + if (HR) *HR << I_3x3, Z_3x3; + if (Ht) *Ht << Z_3x3, R.transpose(); return Pose3(R, t); } @@ -72,15 +74,15 @@ Matrix6 Pose3::adjointMap(const Vector6& xi) { /* ************************************************************************* */ Vector6 Pose3::adjoint(const Vector6& xi, const Vector6& y, - OptionalJacobian<6,6> H) { - if (H) { - H->setZero(); + OptionalJacobian<6, 6> Hxi) { + if (Hxi) { + Hxi->setZero(); for (int i = 0; i < 6; ++i) { Vector6 dxi; dxi.setZero(); dxi(i) = 1.0; Matrix6 Gi = adjointMap(dxi); - H->col(i) = Gi * y; + Hxi->col(i) = Gi * y; } } return adjointMap(xi) * y; @@ -88,15 +90,15 @@ Vector6 Pose3::adjoint(const Vector6& xi, const Vector6& y, /* ************************************************************************* */ Vector6 Pose3::adjointTranspose(const Vector6& xi, const Vector6& y, - OptionalJacobian<6,6> H) { - if (H) { - H->setZero(); + OptionalJacobian<6, 6> Hxi) { + if (Hxi) { + Hxi->setZero(); for (int i = 0; i < 6; ++i) { Vector6 dxi; dxi.setZero(); dxi(i) = 1.0; Matrix6 GTi = adjointMap(dxi).transpose(); - H->col(i) = GTi * y; + Hxi->col(i) = GTi * y; } } return adjointMap(xi).transpose() * y; @@ -116,8 +118,8 @@ bool Pose3::equals(const Pose3& pose, double tol) const { /* ************************************************************************* */ /** Modified from Murray94book version (which assumes w and v normalized?) */ -Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> H) { - if (H) *H = ExpmapDerivative(xi); +Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> Hxi) { + if (Hxi) *Hxi = ExpmapDerivative(xi); // get angular velocity omega and translational velocity v from twist xi Vector3 omega(xi(0), xi(1), xi(2)), v(xi(3), xi(4), xi(5)); @@ -125,8 +127,8 @@ Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> H) { Rot3 R = Rot3::Expmap(omega); double theta2 = omega.dot(omega); if (theta2 > std::numeric_limits::epsilon()) { - Vector3 t_parallel = omega * omega.dot(v); // translation parallel to axis - Vector3 omega_cross_v = omega.cross(v); // points towards axis + Vector3 t_parallel = omega * omega.dot(v); // translation parallel to axis + Vector3 omega_cross_v = omega.cross(v); // points towards axis Vector3 t = (omega_cross_v - R * omega_cross_v + t_parallel) / theta2; return Pose3(R, t); } else { @@ -135,10 +137,10 @@ Pose3 Pose3::Expmap(const Vector6& xi, OptionalJacobian<6, 6> H) { } /* ************************************************************************* */ -Vector6 Pose3::Logmap(const Pose3& p, OptionalJacobian<6, 6> H) { - if (H) *H = LogmapDerivative(p); - const Vector3 w = Rot3::Logmap(p.rotation()); - const Vector3 T = p.translation(); +Vector6 Pose3::Logmap(const Pose3& pose, OptionalJacobian<6, 6> Hpose) { + if (Hpose) *Hpose = LogmapDerivative(pose); + const Vector3 w = Rot3::Logmap(pose.rotation()); + const Vector3 T = pose.translation(); const double t = w.norm(); if (t < 1e-10) { Vector6 log; @@ -158,33 +160,33 @@ Vector6 Pose3::Logmap(const Pose3& p, OptionalJacobian<6, 6> H) { } /* ************************************************************************* */ -Pose3 Pose3::ChartAtOrigin::Retract(const Vector6& xi, ChartJacobian H) { +Pose3 Pose3::ChartAtOrigin::Retract(const Vector6& xi, ChartJacobian Hxi) { #ifdef GTSAM_POSE3_EXPMAP - return Expmap(xi, H); + return Expmap(xi, Hxi); #else Matrix3 DR; - Rot3 R = Rot3::Retract(xi.head<3>(), H ? &DR : 0); - if (H) { - *H = I_6x6; - H->topLeftCorner<3,3>() = DR; + Rot3 R = Rot3::Retract(xi.head<3>(), Hxi ? &DR : 0); + if (Hxi) { + *Hxi = I_6x6; + Hxi->topLeftCorner<3, 3>() = DR; } return Pose3(R, Point3(xi.tail<3>())); #endif } /* ************************************************************************* */ -Vector6 Pose3::ChartAtOrigin::Local(const Pose3& T, ChartJacobian H) { +Vector6 Pose3::ChartAtOrigin::Local(const Pose3& pose, ChartJacobian Hpose) { #ifdef GTSAM_POSE3_EXPMAP - return Logmap(T, H); + return Logmap(pose, Hpose); #else Matrix3 DR; - Vector3 omega = Rot3::LocalCoordinates(T.rotation(), H ? &DR : 0); - if (H) { - *H = I_6x6; - H->topLeftCorner<3,3>() = DR; + Vector3 omega = Rot3::LocalCoordinates(pose.rotation(), Hpose ? &DR : 0); + if (Hpose) { + *Hpose = I_6x6; + Hpose->topLeftCorner<3, 3>() = DR; } Vector6 xi; - xi << omega, T.translation(); + xi << omega, pose.translation(); return xi; #endif } @@ -261,16 +263,16 @@ Matrix6 Pose3::LogmapDerivative(const Pose3& pose) { } /* ************************************************************************* */ -const Point3& Pose3::translation(OptionalJacobian<3, 6> H) const { - if (H) *H << Z_3x3, rotation().matrix(); +const Point3& Pose3::translation(OptionalJacobian<3, 6> Hself) const { + if (Hself) *Hself << Z_3x3, rotation().matrix(); return t_; } /* ************************************************************************* */ -const Rot3& Pose3::rotation(OptionalJacobian<3, 6> H) const { - if (H) { - *H << I_3x3, Z_3x3; +const Rot3& Pose3::rotation(OptionalJacobian<3, 6> Hself) const { + if (Hself) { + *Hself << I_3x3, Z_3x3; } return R_; } @@ -299,101 +301,101 @@ Pose3 Pose3::transform_to(const Pose3& pose) const { #endif /* ************************************************************************* */ -Pose3 Pose3::transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> H1, - OptionalJacobian<6, 6> H2) const { - if (H1) *H1 = -wTb.inverse().AdjointMap() * AdjointMap(); - if (H2) *H2 = I_6x6; +Pose3 Pose3::transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself, + OptionalJacobian<6, 6> HwTb) const { + if (Hself) *Hself = -wTb.inverse().AdjointMap() * AdjointMap(); + if (HwTb) *HwTb = I_6x6; const Pose3& wTa = *this; return wTa.inverse() * wTb; } /* ************************************************************************* */ -Point3 Pose3::transformFrom(const Point3& p, OptionalJacobian<3,6> Dpose, - OptionalJacobian<3,3> Dpoint) const { +Point3 Pose3::transformFrom(const Point3& p, OptionalJacobian<3, 6> Hself, + OptionalJacobian<3, 3> Hpoint) const { // Only get matrix once, to avoid multiple allocations, // as well as multiple conversions in the Quaternion case const Matrix3 R = R_.matrix(); - if (Dpose) { - Dpose->leftCols<3>() = R * skewSymmetric(-p.x(), -p.y(), -p.z()); - Dpose->rightCols<3>() = R; + if (Hself) { + Hself->leftCols<3>() = R * skewSymmetric(-p.x(), -p.y(), -p.z()); + Hself->rightCols<3>() = R; } - if (Dpoint) { - *Dpoint = R; + if (Hpoint) { + *Hpoint = R; } return R_ * p + t_; } /* ************************************************************************* */ -Point3 Pose3::transformTo(const Point3& p, OptionalJacobian<3,6> Dpose, - OptionalJacobian<3,3> Dpoint) const { +Point3 Pose3::transformTo(const Point3& p, OptionalJacobian<3, 6> Hself, + OptionalJacobian<3, 3> Hpoint) const { // Only get transpose once, to avoid multiple allocations, // as well as multiple conversions in the Quaternion case const Matrix3 Rt = R_.transpose(); const Point3 q(Rt*(p - t_)); - if (Dpose) { + if (Hself) { const double wx = q.x(), wy = q.y(), wz = q.z(); - (*Dpose) << + (*Hself) << 0.0, -wz, +wy,-1.0, 0.0, 0.0, +wz, 0.0, -wx, 0.0,-1.0, 0.0, -wy, +wx, 0.0, 0.0, 0.0,-1.0; } - if (Dpoint) { - *Dpoint = Rt; + if (Hpoint) { + *Hpoint = Rt; } return q; } /* ************************************************************************* */ -double Pose3::range(const Point3& point, OptionalJacobian<1, 6> H1, - OptionalJacobian<1, 3> H2) const { +double Pose3::range(const Point3& point, OptionalJacobian<1, 6> Hself, + OptionalJacobian<1, 3> Hpoint) const { Matrix36 D_local_pose; Matrix3 D_local_point; - Point3 local = transformTo(point, H1 ? &D_local_pose : 0, H2 ? &D_local_point : 0); - if (!H1 && !H2) { + Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0); + if (!Hself && !Hpoint) { return local.norm(); } else { Matrix13 D_r_local; const double r = norm3(local, D_r_local); - if (H1) *H1 = D_r_local * D_local_pose; - if (H2) *H2 = D_r_local * D_local_point; + if (Hself) *Hself = D_r_local * D_local_pose; + if (Hpoint) *Hpoint = D_r_local * D_local_point; return r; } } /* ************************************************************************* */ -double Pose3::range(const Pose3& pose, OptionalJacobian<1, 6> H1, - OptionalJacobian<1, 6> H2) const { +double Pose3::range(const Pose3& pose, OptionalJacobian<1, 6> Hself, + OptionalJacobian<1, 6> Hpose) const { Matrix13 D_local_point; - double r = range(pose.translation(), H1, H2 ? &D_local_point : 0); - if (H2) *H2 << Matrix13::Zero(), D_local_point * pose.rotation().matrix(); + double r = range(pose.translation(), Hself, Hpose ? &D_local_point : 0); + if (Hpose) *Hpose << Matrix13::Zero(), D_local_point * pose.rotation().matrix(); return r; } /* ************************************************************************* */ -Unit3 Pose3::bearing(const Point3& point, OptionalJacobian<2, 6> H1, - OptionalJacobian<2, 3> H2) const { +Unit3 Pose3::bearing(const Point3& point, OptionalJacobian<2, 6> Hself, + OptionalJacobian<2, 3> Hpoint) const { Matrix36 D_local_pose; Matrix3 D_local_point; - Point3 local = transformTo(point, H1 ? &D_local_pose : 0, H2 ? &D_local_point : 0); - if (!H1 && !H2) { + Point3 local = transformTo(point, Hself ? &D_local_pose : 0, Hpoint ? &D_local_point : 0); + if (!Hself && !Hpoint) { return Unit3(local); } else { Matrix23 D_b_local; Unit3 b = Unit3::FromPoint3(local, D_b_local); - if (H1) *H1 = D_b_local * D_local_pose; - if (H2) *H2 = D_b_local * D_local_point; + if (Hself) *Hself = D_b_local * D_local_pose; + if (Hpoint) *Hpoint = D_b_local * D_local_point; return b; } } /* ************************************************************************* */ -Unit3 Pose3::bearing(const Pose3& pose, OptionalJacobian<2, 6> H1, - OptionalJacobian<2, 6> H2) const { - if (H2) { - H2->setZero(); - return bearing(pose.translation(), H1, H2.cols<3>(3)); +Unit3 Pose3::bearing(const Pose3& pose, OptionalJacobian<2, 6> Hself, + OptionalJacobian<2, 6> Hpose) const { + if (Hpose) { + Hpose->setZero(); + return bearing(pose.translation(), Hself, Hpose.cols<3>(3)); } - return bearing(pose.translation(), H1, boost::none); + return bearing(pose.translation(), Hself, boost::none); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index ced3b904b..f56e6903a 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -75,8 +75,8 @@ public: /// Named constructor with derivatives static Pose3 Create(const Rot3& R, const Point3& t, - OptionalJacobian<6, 3> H1 = boost::none, - OptionalJacobian<6, 3> H2 = boost::none); + OptionalJacobian<6, 3> HR = boost::none, + OptionalJacobian<6, 3> Ht = boost::none); /** * Create Pose3 by aligning two point pairs @@ -117,10 +117,10 @@ public: /// @{ /// Exponential map at identity - create a rotation from canonical coordinates \f$ [R_x,R_y,R_z,T_x,T_y,T_z] \f$ - static Pose3 Expmap(const Vector6& xi, OptionalJacobian<6, 6> H = boost::none); + static Pose3 Expmap(const Vector6& xi, OptionalJacobian<6, 6> Hxi = boost::none); /// Log map at identity - return the canonical coordinates \f$ [R_x,R_y,R_z,T_x,T_y,T_z] \f$ of this rotation - static Vector6 Logmap(const Pose3& p, OptionalJacobian<6, 6> H = boost::none); + static Vector6 Logmap(const Pose3& pose, OptionalJacobian<6, 6> Hpose = boost::none); /** * Calculate Adjoint map, transforming a twist in the this pose's (i.e, body) frame to the world spatial frame @@ -157,7 +157,7 @@ public: * Action of the adjointMap on a Lie-algebra vector y, with optional derivatives */ static Vector6 adjoint(const Vector6 &xi, const Vector6 &y, - OptionalJacobian<6, 6> = boost::none); + OptionalJacobian<6, 6> Hxi = boost::none); // temporary fix for wrappers until case issue is resolved static Matrix6 adjointMap_(const Vector6 &xi) { return adjointMap(xi);} @@ -167,7 +167,7 @@ public: * The dual version of adjoint action, acting on the dual space of the Lie-algebra vector space. */ static Vector6 adjointTranspose(const Vector6& xi, const Vector6& y, - OptionalJacobian<6, 6> H = boost::none); + OptionalJacobian<6, 6> Hxi = boost::none); /// Derivative of Expmap static Matrix6 ExpmapDerivative(const Vector6& xi); @@ -177,8 +177,8 @@ public: // Chart at origin, depends on compile-time flag GTSAM_POSE3_EXPMAP struct ChartAtOrigin { - static Pose3 Retract(const Vector6& v, ChartJacobian H = boost::none); - static Vector6 Local(const Pose3& r, ChartJacobian H = boost::none); + static Pose3 Retract(const Vector6& xi, ChartJacobian Hxi = boost::none); + static Vector6 Local(const Pose3& pose, ChartJacobian Hpose = boost::none); }; using LieGroup::inverse; // version with derivative @@ -202,12 +202,12 @@ public: /** * @brief takes point in Pose coordinates and transforms it to world coordinates * @param p point in Pose coordinates - * @param Dpose optional 3*6 Jacobian wrpt this pose - * @param Dpoint optional 3*3 Jacobian wrpt point + * @param Hself optional 3*6 Jacobian wrpt this pose + * @param Hpoint optional 3*3 Jacobian wrpt point * @return point in world coordinates */ - Point3 transformFrom(const Point3& p, OptionalJacobian<3, 6> Dpose = - boost::none, OptionalJacobian<3, 3> Dpoint = boost::none) const; + Point3 transformFrom(const Point3& p, OptionalJacobian<3, 6> Hself = + boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; /** syntactic sugar for transformFrom */ inline Point3 operator*(const Point3& p) const { @@ -217,22 +217,22 @@ public: /** * @brief takes point in world coordinates and transforms it to Pose coordinates * @param p point in world coordinates - * @param Dpose optional 3*6 Jacobian wrpt this pose - * @param Dpoint optional 3*3 Jacobian wrpt point + * @param Hself optional 3*6 Jacobian wrpt this pose + * @param Hpoint optional 3*3 Jacobian wrpt point * @return point in Pose coordinates */ - Point3 transformTo(const Point3& p, OptionalJacobian<3, 6> Dpose = - boost::none, OptionalJacobian<3, 3> Dpoint = boost::none) const; + Point3 transformTo(const Point3& p, OptionalJacobian<3, 6> Hself = + boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; /// @} /// @name Standard Interface /// @{ /// get rotation - const Rot3& rotation(OptionalJacobian<3, 6> H = boost::none) const; + const Rot3& rotation(OptionalJacobian<3, 6> Hself = boost::none) const; /// get translation - const Point3& translation(OptionalJacobian<3, 6> H = boost::none) const; + const Point3& translation(OptionalJacobian<3, 6> Hself = boost::none) const; /// get x double x() const { @@ -256,32 +256,32 @@ public: Pose3 transformPoseFrom(const Pose3& pose) const; /** receives a pose in world coordinates and transforms it to local coordinates */ - Pose3 transformPoseTo(const Pose3& pose, OptionalJacobian<6, 6> H1 = boost::none, - OptionalJacobian<6, 6> H2 = boost::none) const; + Pose3 transformPoseTo(const Pose3& pose, OptionalJacobian<6, 6> Hself = boost::none, + OptionalJacobian<6, 6> Hpose = boost::none) const; /** * Calculate range to a landmark * @param point 3D location of landmark * @return range (double) */ - double range(const Point3& point, OptionalJacobian<1, 6> H1 = boost::none, - OptionalJacobian<1, 3> H2 = boost::none) const; + double range(const Point3& point, OptionalJacobian<1, 6> Hself = boost::none, + OptionalJacobian<1, 3> Hpoint = boost::none) const; /** * Calculate range to another pose * @param pose Other SO(3) pose * @return range (double) */ - double range(const Pose3& pose, OptionalJacobian<1, 6> H1 = boost::none, - OptionalJacobian<1, 6> H2 = boost::none) const; + double range(const Pose3& pose, OptionalJacobian<1, 6> Hself = boost::none, + OptionalJacobian<1, 6> Hpose = boost::none) const; /** * Calculate bearing to a landmark * @param point 3D location of landmark * @return bearing (Unit3) */ - Unit3 bearing(const Point3& point, OptionalJacobian<2, 6> H1 = boost::none, - OptionalJacobian<2, 3> H2 = boost::none) const; + Unit3 bearing(const Point3& point, OptionalJacobian<2, 6> Hself = boost::none, + OptionalJacobian<2, 3> Hpoint = boost::none) const; /** * Calculate bearing to another pose @@ -289,8 +289,8 @@ public: * information is ignored. * @return bearing (Unit3) */ - Unit3 bearing(const Pose3& pose, OptionalJacobian<2, 6> H1 = boost::none, - OptionalJacobian<2, 6> H2 = boost::none) const; + Unit3 bearing(const Pose3& pose, OptionalJacobian<2, 6> Hself = boost::none, + OptionalJacobian<2, 6> Hpose = boost::none) const; /// @} /// @name Advanced Interface @@ -321,20 +321,20 @@ public: #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4 /// @name Deprecated /// @{ - Point3 transform_from(const Point3& p, - OptionalJacobian<3, 6> Dpose = boost::none, - OptionalJacobian<3, 3> Dpoint = boost::none) const { - return transformFrom(p, Dpose, Dpoint); + Point3 transform_from(const Point3& point, + OptionalJacobian<3, 6> Hself = boost::none, + OptionalJacobian<3, 3> Hpoint = boost::none) const { + return transformFrom(point, Hself, Hpoint); } - Point3 transform_to(const Point3& p, - OptionalJacobian<3, 6> Dpose = boost::none, - OptionalJacobian<3, 3> Dpoint = boost::none) const { - return transformTo(p, Dpose, Dpoint); + Point3 transform_to(const Point3& point, + OptionalJacobian<3, 6> Hself = boost::none, + OptionalJacobian<3, 3> Hpoint = boost::none) const { + return transformTo(point, Hself, Hpoint); } - Pose3 transform_pose_to(const Pose3& pose, - OptionalJacobian<6, 6> H1 = boost::none, - OptionalJacobian<6, 6> H2 = boost::none) const { - return transformPoseTo(pose, H1, H2); + Pose3 transform_pose_to(const Pose3& pose, + OptionalJacobian<6, 6> Hself = boost::none, + OptionalJacobian<6, 6> Hpose = boost::none) const { + return transformPoseTo(pose, Hself, Hpose); } /** * @deprecated: this function is neither here not there. */ From d672e7eb871308524184a4033e4d7728c6c6f76b Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 21 Jul 2020 11:37:08 -0400 Subject: [PATCH 198/199] Unit test for transformPoseFrom --- gtsam/geometry/tests/testPose3.cpp | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp index 5808f36f8..a169c833c 100644 --- a/gtsam/geometry/tests/testPose3.cpp +++ b/gtsam/geometry/tests/testPose3.cpp @@ -418,6 +418,29 @@ TEST(Pose3, transform_to_rotate) { EXPECT(assert_equal(expected, actual, 0.001)); } +/* ************************************************************************* */ +// Check transformPoseFrom and its pushforward +Pose3 transformPoseFrom_(const Pose3& wTa, const Pose3& aTb) { + return wTa.transformPoseFrom(aTb); +} + +TEST(Pose3, transformPoseFrom) +{ + Matrix actual = (T2*T2).matrix(); + Matrix expected = T2.matrix()*T2.matrix(); + EXPECT(assert_equal(actual, expected, 1e-8)); + + Matrix H1, H2; + T2.transformPoseFrom(T2, H1, H2); + + Matrix numericalH1 = numericalDerivative21(transformPoseFrom_, T2, T2); + EXPECT(assert_equal(numericalH1, H1, 5e-3)); + EXPECT(assert_equal(T2.inverse().AdjointMap(), H1, 5e-3)); + + Matrix numericalH2 = numericalDerivative22(transformPoseFrom_, T2, T2); + EXPECT(assert_equal(numericalH2, H2, 1e-4)); +} + /* ************************************************************************* */ TEST(Pose3, transformTo) { Pose3 transform(Rot3::Rodrigues(0, 0, -1.570796), Point3(2, 4, 0)); From 6192f90de5cdf3b8e963678d3293b27b330cdbb5 Mon Sep 17 00:00:00 2001 From: Frank dellaert Date: Tue, 21 Jul 2020 11:37:23 -0400 Subject: [PATCH 199/199] Some more name changes and documentation --- gtsam/geometry/Pose3.cpp | 15 ++++++++------- gtsam/geometry/Pose3.h | 30 +++++++++++++++++++----------- 2 files changed, 27 insertions(+), 18 deletions(-) diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp index 0ee19ef76..1b9285100 100644 --- a/gtsam/geometry/Pose3.cpp +++ b/gtsam/geometry/Pose3.cpp @@ -286,9 +286,10 @@ Matrix4 Pose3::matrix() const { } /* ************************************************************************* */ -Pose3 Pose3::transformPoseFrom(const Pose3& aTb) const { +Pose3 Pose3::transformPoseFrom(const Pose3& aTb, OptionalJacobian<6, 6> Hself, + OptionalJacobian<6, 6> HaTb) const { const Pose3& wTa = *this; - return wTa * aTb; + return wTa.compose(aTb, Hself, HaTb); } /* ************************************************************************* */ @@ -310,28 +311,28 @@ Pose3 Pose3::transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself, } /* ************************************************************************* */ -Point3 Pose3::transformFrom(const Point3& p, OptionalJacobian<3, 6> Hself, +Point3 Pose3::transformFrom(const Point3& point, OptionalJacobian<3, 6> Hself, OptionalJacobian<3, 3> Hpoint) const { // Only get matrix once, to avoid multiple allocations, // as well as multiple conversions in the Quaternion case const Matrix3 R = R_.matrix(); if (Hself) { - Hself->leftCols<3>() = R * skewSymmetric(-p.x(), -p.y(), -p.z()); + Hself->leftCols<3>() = R * skewSymmetric(-point.x(), -point.y(), -point.z()); Hself->rightCols<3>() = R; } if (Hpoint) { *Hpoint = R; } - return R_ * p + t_; + return R_ * point + t_; } /* ************************************************************************* */ -Point3 Pose3::transformTo(const Point3& p, OptionalJacobian<3, 6> Hself, +Point3 Pose3::transformTo(const Point3& point, OptionalJacobian<3, 6> Hself, OptionalJacobian<3, 3> Hpoint) const { // Only get transpose once, to avoid multiple allocations, // as well as multiple conversions in the Quaternion case const Matrix3 Rt = R_.transpose(); - const Point3 q(Rt*(p - t_)); + const Point3 q(Rt*(point - t_)); if (Hself) { const double wx = q.x(), wy = q.y(), wz = q.z(); (*Hself) << diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index f56e6903a..3825b6241 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -201,27 +201,27 @@ public: /** * @brief takes point in Pose coordinates and transforms it to world coordinates - * @param p point in Pose coordinates + * @param point point in Pose coordinates * @param Hself optional 3*6 Jacobian wrpt this pose * @param Hpoint optional 3*3 Jacobian wrpt point * @return point in world coordinates */ - Point3 transformFrom(const Point3& p, OptionalJacobian<3, 6> Hself = + Point3 transformFrom(const Point3& point, OptionalJacobian<3, 6> Hself = boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; /** syntactic sugar for transformFrom */ - inline Point3 operator*(const Point3& p) const { - return transformFrom(p); + inline Point3 operator*(const Point3& point) const { + return transformFrom(point); } /** * @brief takes point in world coordinates and transforms it to Pose coordinates - * @param p point in world coordinates + * @param point point in world coordinates * @param Hself optional 3*6 Jacobian wrpt this pose * @param Hpoint optional 3*3 Jacobian wrpt point * @return point in Pose coordinates */ - Point3 transformTo(const Point3& p, OptionalJacobian<3, 6> Hself = + Point3 transformTo(const Point3& point, OptionalJacobian<3, 6> Hself = boost::none, OptionalJacobian<3, 3> Hpoint = boost::none) const; /// @} @@ -252,12 +252,20 @@ public: /** convert to 4*4 matrix */ Matrix4 matrix() const; - /** receives a pose in local coordinates and transforms it to world coordinates */ - Pose3 transformPoseFrom(const Pose3& pose) const; + /** + * Assuming self == wTa, takes a pose aTb in local coordinates + * and transforms it to world coordinates wTb = wTa * aTb. + * This is identical to compose. + */ + Pose3 transformPoseFrom(const Pose3& aTb, OptionalJacobian<6, 6> Hself = boost::none, + OptionalJacobian<6, 6> HaTb = boost::none) const; - /** receives a pose in world coordinates and transforms it to local coordinates */ - Pose3 transformPoseTo(const Pose3& pose, OptionalJacobian<6, 6> Hself = boost::none, - OptionalJacobian<6, 6> Hpose = boost::none) const; + /** + * Assuming self == wTa, takes a pose wTb in world coordinates + * and transforms it to local coordinates aTb = inv(wTa) * wTb + */ + Pose3 transformPoseTo(const Pose3& wTb, OptionalJacobian<6, 6> Hself = boost::none, + OptionalJacobian<6, 6> HwTb = boost::none) const; /** * Calculate range to a landmark