diff --git a/AUTHORS b/AUTHORS index 1b923b209f..76dd357f29 100644 --- a/AUTHORS +++ b/AUTHORS @@ -104,6 +104,8 @@ the University of Malaga. - Several improvements and bug fixes in the mrpt-reactivenav library. - Developemnt in octomap classes. - Some improvements and bug fixes in the mrpt-opengl library. + - Visual Odometry based on depth images (mrpt::vision::CDifodo) and 2 applications to use it: DifOdometry-Camera and DifOdometry-Datasets + - Examples to manage an RGB-D camera with openNI2 * Robert Schattschneider, University of Canterbury (2012) - Patches for bug fixes, serialization of templates. diff --git a/CMakeLists.txt b/CMakeLists.txt index 9a5a414531..18219afb44 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -180,6 +180,7 @@ include(cmakemodules/script_ftdi.cmake REQUIRED) # Check for the FTDI hea include(cmakemodules/script_inotify.cmake REQUIRED) # Check for the sys/inotify headers (Linux only, in win32 we use the equivalent API for file system monitoring): include(cmakemodules/script_gl_glut.cmake REQUIRED) # Check for the GL,GLUT libraries include(cmakemodules/script_opencv.cmake REQUIRED) # Check for the OpenCV libraries (via pkg-config, CMake, with different options) +include(cmakemodules/script_openni2.cmake REQUIRED) # Check for the OpenNI2 library include(cmakemodules/script_ffmpeg.cmake REQUIRED) # Check for ffmpeg C libraries: libavcodec, libavutil, libavformat, libswscale include(cmakemodules/script_wxwidgets.cmake REQUIRED) # Check for wxWidgets + GL include(cmakemodules/script_libdc1394.cmake REQUIRED) # Check for libdc1394-2 diff --git a/apps/DifOdometry-Camera/CMakeLists.txt b/apps/DifOdometry-Camera/CMakeLists.txt new file mode 100644 index 0000000000..791560a614 --- /dev/null +++ b/apps/DifOdometry-Camera/CMakeLists.txt @@ -0,0 +1,40 @@ +INCLUDE(../../cmakemodules/AssureCMakeRootFile.cmake) # Avoid user mistake in CMake source directory + +if (CMAKE_MRPT_HAS_OPENNI2) # This project can't be built without OpenNI2 + +#----------------------------------------------------------------- +# CMake file for the MRPT application: ReactiveNav3D-Demo +# +# Run with "cmake ." at the root directory +# +# January 2014, Mariano Jaimez Tarifa +#----------------------------------------------------------------- +PROJECT(DifOdometry-Camera) + +#MESSAGE(STATUS "Makefile for application: /apps/ReactiveNav3D-Demo ") + +# --------------------------------------------- +# TARGET: +# --------------------------------------------- +# Define the executable target: +ADD_EXECUTABLE(DifOdometry-Camera + DifOdometry_Camera_main.cpp + DifOdometry_Camera.cpp + DifOdometry_Camera.h) + +SET(TMP_TARGET_NAME "DifOdometry-Camera") + + + +# Add the required libraries for linking: +TARGET_LINK_LIBRARIES(${TMP_TARGET_NAME} ${MRPT_LINKER_LIBS} ${OPENNI2_LIBRARIES}) + +# Dependencies on MRPT libraries: +# Just mention the top-level dependency, the rest will be detected automatically, +# and all the needed #include<> dirs added (see the script DeclareAppDependencies.cmake for further details) +DeclareAppDependencies(${TMP_TARGET_NAME} mrpt-gui mrpt-opengl mrpt-vision) + +DeclareAppForInstall(${TMP_TARGET_NAME}) + +endif (CMAKE_MRPT_HAS_OPENNI2) # This project can't be built without OpenNI2 + diff --git a/apps/DifOdometry-Camera/DifOdometry_Camera.cpp b/apps/DifOdometry-Camera/DifOdometry_Camera.cpp new file mode 100644 index 0000000000..9507b59d75 --- /dev/null +++ b/apps/DifOdometry-Camera/DifOdometry_Camera.cpp @@ -0,0 +1,489 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + +#include "DifOdometry_Camera.h" +#include +#include + +using namespace mrpt; +using namespace mrpt::opengl; +using namespace mrpt::gui; +using namespace mrpt::slam; + + +void CDifodoCamera::loadConfiguration(const utils::CConfigFileBase &ini ) +{ + cam_mode = ini.read_int("DIFODO_CONFIG", "cam_mode", 2, true); + downsample = ini.read_int("DIFODO_CONFIG", "downsample", 2, true); + rows = ini.read_int("DIFODO_CONFIG", "rows", 50, true); + cols = ini.read_int("DIFODO_CONFIG", "cols", 60, true); + fps = ini.read_int("DIFODO_CONFIG", "fps", 30, false); + + + // Resize Matrices and adjust parameters + //========================================================= + const unsigned int resh = 640/(cam_mode*downsample); + const unsigned int resv = 480/(cam_mode*downsample); + + depth.setSize(rows,cols); + depth_old.setSize(rows,cols); + depth_inter.setSize(rows,cols); + depth_ft.setSize(resv,resh); + depth_wf.setSize(resv,resh); + + du.setSize(rows,cols); + dv.setSize(rows,cols); + dt.setSize(rows,cols); + xx.setSize(rows,cols); + xx_inter.setSize(rows,cols); + xx_old.setSize(rows,cols); + yy.setSize(rows,cols); + yy_inter.setSize(rows,cols); + yy_old.setSize(rows,cols); + + border.setSize(rows,cols); + border.assign(0); + null.setSize(rows,cols); + null.assign(0); + est_cov.assign(0); + + x_incr = 2.0*f_dist*(floor(float(resh)/float(cols))*cols/float(resh))*tan(0.5*fovh)/(cols-1); //In meters + y_incr = 2.0*f_dist*(floor(float(resv)/float(rows))*rows/float(resv))*tan(0.5*fovv)/(rows-1); //In meters //In Hz + + //Depth thresholds + const int dz = floor(float(resv)/float(rows)); + const int dy = floor(float(resh)/float(cols)); + + duv_threshold = 0.001*(dz + dy)*(cam_mode*downsample); + dt_threshold = 0.2*fps; + dif_threshold = 0.001*(dz + dy)*(cam_mode*downsample); + difuv_surroundings = 0.0022*(dz + dy)*(cam_mode*downsample); + dift_surroundings = 0.01*fps*(dz + dy)*(cam_mode*downsample); +} + + +bool CDifodoCamera::openCamera() +{ + const char* deviceURI = openni::ANY_DEVICE; + + rc = openni::OpenNI::initialize(); + + printf("Initialization:\n %s\n", openni::OpenNI::getExtendedError()); + rc = device.open(deviceURI); + if (rc != openni::STATUS_OK) + { + printf("SimpleViewer: Device open failed:\n%s\n", openni::OpenNI::getExtendedError()); + openni::OpenNI::shutdown(); + return 1; + } + + // Create Depth channel + //======================================================================================== + + rc = depth_ch.create(device, openni::SENSOR_DEPTH); + if (rc == openni::STATUS_OK) + { + rc = depth_ch.start(); + if (rc != openni::STATUS_OK) + { + printf("SimpleViewer: Couldn't start depth stream:\n%s\n", openni::OpenNI::getExtendedError()); + depth_ch.destroy(); + } + } + else + printf("SimpleViewer: Couldn't find depth stream:\n%s\n", openni::OpenNI::getExtendedError()); + + if (!depth_ch.isValid()) + { + printf("Camera: No valid streams. Exiting\n"); + openni::OpenNI::shutdown(); + return 1; + } + + // Configure some properties (resolution) + //======================================================================================== + + //Display video modes + openni::VideoMode vm; + printf("Camera depth modes are listed:\n"); + for(int i=0; i= 0; --yc) + { + const openni::DepthPixel* pDepth = pDepthRow; + for (int xc = width-1; xc >= 0; --xc, ++pDepth) + if ((yc%downsample == 0)&&(xc%downsample == 0)) + depth_wf(yc/downsample,xc/downsample) = 0.001*(*pDepth); + + pDepthRow += rowSize; + } +} + +void CDifodoCamera::CreateResultsFile() +{ + try + { + // Open file, find the first free file-name. + char aux[100]; + int nFile = 0; + bool free_name = false; + + system::createDirectory("./difodo.results"); + + while (!free_name) + { + nFile++; + sprintf(aux, "./difodo.results/experiment_%03u.txt", nFile ); + free_name = !system::fileExists(aux); + } + + // Open log file: + f_res.open(aux); + + clock.Tic(); + + printf(" Saving results to file: %s \n", aux); + } + catch (...) + { + printf("Exception found trying to create the 'results file' !!\n"); + } +} + + +void CDifodoCamera::initializeScene() +{ + global_settings::OCTREE_RENDER_MAX_POINTS_PER_NODE = 1000000; + window.resize(1000,900); + window.setPos(900,0); + window.setCameraZoom(16); + window.setCameraAzimuthDeg(0); + window.setCameraElevationDeg(90); + window.setCameraPointingToPoint(0,0,0); + window.setCameraPointingToPoint(0,0,1); + + scene = window.get3DSceneAndLock(); + + // Lights: + scene->getViewport()->setNumberOfLights(1); + CLight & light0 = scene->getViewport()->getLight(0); + light0.light_ID = 0; + light0.setPosition(0,0,1,1); + + //Grid (ground) + CGridPlaneXYPtr ground = CGridPlaneXY::Create(); + scene->insert( ground ); + + //Reference + CSetOfObjectsPtr reference = stock_objects::CornerXYZ(); + scene->insert( reference ); + + // Cameras and points + //------------------------------------------------------ + + //DifOdo camera + CBoxPtr camera_odo = CBox::Create(math::TPoint3D(-0.02,-0.1,-0.01),math::TPoint3D(0.02,0.1,0.01)); + camera_odo->setPose(cam_pose); + camera_odo->setColor(0,1,0); + scene->insert( camera_odo ); + + //Frustum + opengl::CFrustumPtr FOV = opengl::CFrustum::Create(0.3, 5, 57.3*fovh, 57.3*fovv, 1.5f, true, false); + FOV->setPose(cam_pose); + scene->insert( FOV ); + + //Reference cam + CSetOfObjectsPtr reference_gt = stock_objects::CornerXYZ(); + reference_gt->setScale(0.2); + reference_gt->setPose(cam_pose); + scene->insert( reference_gt ); + + //Camera points + CPointCloudPtr cam_points = CPointCloud::Create(); + cam_points->setColor(1,0,0); + cam_points->setPointSize(2); + cam_points->enablePointSmooth(1); + cam_points->setPose(cam_pose); + scene->insert( cam_points ); + + //Border points + CPointCloudPtr border_points = CPointCloud::Create(); + border_points->setColor(0,0,1); + border_points->setPointSize(3); + border_points->enablePointSmooth(1); + border_points->setPose(cam_pose); + scene->insert( border_points ); + + // Trajectories and covarianze + //------------------------------------------------------------- + + //Dif Odometry + CSetOfLinesPtr traj_lines_odo = CSetOfLines::Create(); + traj_lines_odo->setLocation(0,0,0); + traj_lines_odo->setColor(0,0,0); + traj_lines_odo->setLineWidth(3); + scene->insert( traj_lines_odo ); + CPointCloudPtr traj_points_odo = CPointCloud::Create(); + traj_points_odo->setColor(0,0.5,0); + traj_points_odo->setPointSize(4); + traj_points_odo->enablePointSmooth(1); + scene->insert( traj_points_odo ); + + //Ellipsoid showing covariance + math::CMatrixFloat33 cov3d(est_cov.topLeftCorner(3,3)); + CEllipsoidPtr ellip = CEllipsoid::Create(); + ellip->setCovMatrix(cov3d); + ellip->setQuantiles(2.0); + ellip->setColor(1.0, 1.0, 1.0, 0.5); + ellip->enableDrawSolid3D(true); + ellip->setPose(cam_pose); + scene->insert( ellip ); + + //User-interface information + utils::CImage img_legend; + img_legend.loadFromXPM(legend_xpm); + COpenGLViewportPtr legend = scene->createViewport("legend"); + legend->setViewportPosition(20, 20, 348, 200); + legend->setImageView(img_legend); + + window.unlockAccess3DScene(); + window.repaint(); +} + + +void CDifodoCamera::updateScene() +{ + scene = window.get3DSceneAndLock(); + + //Reference gt + CSetOfObjectsPtr reference_gt = scene->getByClass(1); + reference_gt->setPose(cam_pose); + + //Camera points + CPointCloudPtr cam_points = scene->getByClass(0); + cam_points->clear(); + cam_points->setPose(cam_pose); + for (unsigned int y=0; yinsertPoint(depth_inter(z,y), xx_inter(z,y), yy_inter(z,y)); + } + + //Border points + CPointCloudPtr border_points = scene->getByClass(1); + border_points->clear(); + border_points->setPose(cam_pose); + for (unsigned int y=0; yinsertPoint(depth_inter(z,y), xx_inter(z,y), yy_inter(z,y)); + + //DifOdo camera + CBoxPtr camera_odo = scene->getByClass(0); + camera_odo->setPose(cam_pose); + + //Frustum + CFrustumPtr FOV = scene->getByClass(0); + FOV->setPose(cam_pose); + + //Difodo traj lines + CSetOfLinesPtr traj_lines_odo = scene->getByClass(0); + traj_lines_odo->appendLine(cam_oldpose.x(), cam_oldpose.y(), cam_oldpose.z(), cam_pose.x(), cam_pose.y(), cam_pose.z()); + + //Difodo traj points + CPointCloudPtr traj_points_odo = scene->getByClass(2); + traj_points_odo->insertPoint(cam_pose.x(), cam_pose.y(), cam_pose.z()); + + //Ellipsoid showing covariance + math::CMatrixFloat33 cov3d(est_cov.topLeftCorner(3,3)); + CEllipsoidPtr ellip = scene->getByClass(0); + ellip->setCovMatrix(cov3d); + ellip->setPose(cam_pose); + + window.unlockAccess3DScene(); + window.repaint(); +} + + +void CDifodoCamera::closeCamera() +{ + depth_ch.destroy(); + openni::OpenNI::shutdown(); +} + + +void CDifodoCamera::reset() +{ + //Reset Difodo + loadFrame(); + filterAndDownsample(); + calculateCoord(); + calculateDepthDerivatives(); + findNullPoints(); + findBorders(); + findValidPoints(); + + cam_pose.setFromValues(0,0,1.5,0,0,0); + cam_oldpose = cam_pose; + + //Reset scene + scene = window.get3DSceneAndLock(); + CSetOfLinesPtr traj_lines_odo = scene->getByClass(0); + traj_lines_odo->clear(); + CPointCloudPtr traj_points_odo = scene->getByClass(2); + traj_points_odo->clear(); + window.unlockAccess3DScene(); + + updateScene(); +} + + +void CDifodoCamera::filterSpeedAndPoseUpdate() +{ + //------------------------------------------------------------------------- + // Filter speed + //------------------------------------------------------------------------- + + utils::CTicTac clock; + clock.Tic(); + + // Calculate Eigenvalues and Eigenvectors + //---------------------------------------------------------- + Eigen::SelfAdjointEigenSolver eigensolver(est_cov); + if (eigensolver.info() != Eigen::Success) + { + printf("Eigensolver couldn't find a solution. Pose is not updated"); + return; + } + + //First, we have to describe both the new linear and angular speeds in the "eigenvector" basis + //------------------------------------------------------------------------------------------------- + MatrixXf Bii, kai_b; + Bii.setSize(6,6); kai_b.setSize(6,1); + Bii = eigensolver.eigenvectors(); + + kai_b = Bii.colPivHouseholderQr().solve(kai_solver); + + //Second, we have to describe both the old linear and angular speeds in the "eigenvector" basis too + //------------------------------------------------------------------------------------------------- + math::CMatrixDouble33 inv_trans; + math::CMatrixFloat31 v_loc_old, w_loc_old; + + //Express them in the local reference frame first + cam_pose.getRotationMatrix(inv_trans); + v_loc_old = inv_trans.inverse().cast()*kai_abs.topRows(3); + w_loc_old = inv_trans.inverse().cast()*kai_abs.bottomRows(3); + + //Then transform that local representation to the "eigenvector" basis + MatrixXf kai_b_old; + kai_b_old.setSize(6,1); + math::CMatrixFloat61 kai_loc_old; + kai_loc_old.topRows<3>() = v_loc_old; + kai_loc_old.bottomRows<3>() = w_loc_old; + + kai_b_old = Bii.colPivHouseholderQr().solve(kai_loc_old); + + //Filter speed + const float c = 400.0; + MatrixXf kai_b_fil; + kai_b_fil.setSize(6,1); + for (unsigned int i=0; i<6; i++) + { + kai_b_fil(i,0) = (kai_b(i,0) + (c*eigensolver.eigenvalues()(i,0) + 0.2)*kai_b_old(i,0))/(1.0 + c*eigensolver.eigenvalues()(i,0) + 0.2); + //kai_b_fil_d(i,0) = (kai_b_d(i,0) + 0.2*kai_b_old_d(i,0))/(1.0 + 0.2); + } + + //Transform filtered speed to local and then absolute reference systems + MatrixXf kai_loc_fil; + math::CMatrixFloat31 v_abs_fil, w_abs_fil; + kai_loc_fil.setSize(6,1); + kai_loc_fil = Bii.inverse().colPivHouseholderQr().solve(kai_b_fil); + + cam_pose.getRotationMatrix(inv_trans); + v_abs_fil = inv_trans.cast()*kai_loc_fil.topRows(3); + w_abs_fil = inv_trans.cast()*kai_loc_fil.bottomRows(3); + + kai_abs.topRows<3>() = v_abs_fil; + kai_abs.bottomRows<3>() = w_abs_fil; + + + //------------------------------------------------------------------------- + // Update pose (DIFODO) + //------------------------------------------------------------------------- + + cam_oldpose = cam_pose; + + //Rotations and translations (could be better, and I tried it but there isn't any significant difference...) + double yaw,pitch,roll; + math::CMatrixDouble31 w_euler_d; + + cam_pose.getYawPitchRoll(yaw,pitch,roll); + w_euler_d(0,0) = kai_loc_fil(4,0)*sin(roll)/cos(pitch) + kai_loc_fil(5,0)*cos(roll)/cos(pitch); + w_euler_d(1,0) = kai_loc_fil(4,0)*cos(roll) - kai_loc_fil(5,0)*sin(roll); + w_euler_d(2,0) = kai_loc_fil(3,0) + kai_loc_fil(4,0)*sin(roll)*tan(pitch) + kai_loc_fil(5,0)*cos(roll)*tan(pitch); + + //Update pose + cam_pose.x_incr(v_abs_fil(0,0)/fps); + cam_pose.y_incr(v_abs_fil(1,0)/fps); + cam_pose.z_incr(v_abs_fil(2,0)/fps); + cam_pose.setYawPitchRoll(yaw + w_euler_d(0,0)/fps, pitch + w_euler_d(1,0)/fps, roll + w_euler_d(2,0)/fps); + + execution_time += 1000*clock.Tac(); + + if (save_results == 1) + writeToLogFile(); + +} + + +void CDifodoCamera::writeToLogFile() +{ + f_res << clock.Tac() << " "; + f_res << cam_pose[0] << " "; + f_res << cam_pose[1] << " "; + f_res << cam_pose[2] << " "; + f_res << cam_pose[3] << " "; + f_res << cam_pose[4] << " "; + f_res << cam_pose[5] << " "; + f_res << "\n"; +} + diff --git a/apps/DifOdometry-Camera/DifOdometry_Camera.h b/apps/DifOdometry-Camera/DifOdometry_Camera.h new file mode 100644 index 0000000000..a7eac05902 --- /dev/null +++ b/apps/DifOdometry-Camera/DifOdometry_Camera.h @@ -0,0 +1,86 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + + +#include +#include +#include +#include +#include +#include + +#if defined(MRPT_OS_LINUX) && !defined(linux) +# define linux 1 // Seems to be required by OpenNI.h +#endif +#include + +#include "legend.xpm" + + + +class CDifodoCamera : public mrpt::vision::CDifodo { +public: + + mrpt::gui::CDisplayWindow3D window; + std::ofstream f_res; + + bool save_results; + + /** Constructor. */ + CDifodoCamera() : mrpt::vision::CDifodo() + { + save_results = 0; + } + + /** Initializes the visual odometry method and loads the rawlog file */ + void loadConfiguration( const mrpt::utils::CConfigFileBase &ini ); + + /** Open camera */ + bool openCamera(); + + /** Close camera */ + void closeCamera(); + + /** Capture a new depth frame */ + void loadFrame(); + + /** Creates a file to save some results */ + void CreateResultsFile(); + + /** Initializes opengl scene */ + void initializeScene(); + + /** Updates the opengl scene */ + void updateScene(); + + /** Obtains the filtered speed, updates the pose and saves some statistics */ + void filterSpeedAndPoseUpdate(); + + /** A pre-step that should be performed before starting to estimate the camera speed, + * and can also be called to reset the estimated trajectory and pose */ + void reset(); + +private: + + mrpt::opengl::COpenGLScenePtr scene; //!< Opengl scene + + // OpenNI variables to manage the camera + openni::Status rc; + openni::Device device; + openni::VideoMode video_options; + openni::VideoStream depth_ch; + + /** Clock used to save the timestamp */ + mrpt::utils::CTicTac clock; + + /** Saves the following data for each observation (distance in meters and angles in radians): + * timestamp(s) - x - y - z - yaw - pitch - roll */ + void writeToLogFile(); + +}; diff --git a/apps/DifOdometry-Camera/DifOdometry_Camera_main.cpp b/apps/DifOdometry-Camera/DifOdometry_Camera_main.cpp new file mode 100644 index 0000000000..a9dc98e593 --- /dev/null +++ b/apps/DifOdometry-Camera/DifOdometry_Camera_main.cpp @@ -0,0 +1,193 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + +#include "DifOdometry_Camera.h" + +using namespace std; +using namespace mrpt; + +const char *default_cfg_txt = + "; ---------------------------------------------------------------\n" + "; FILE: Difodo Parameters.txt\n" + ";\n" + "; MJT @ JANUARY-2014\n" + "; ---------------------------------------------------------------\n\n" + + "[DIFODO_CONFIG]\n\n" + + ";cam_mode: 1 - 640x480, 2 - 320x240, 4 - 160x120 \n" + "cam_mode = 2 \n\n" + + ";downsample: 1 - same resolution, 2 - rx/2, ry/2, 4 - rx/4, ry/4 \n" + "downsample = 2 \n\n" + + "Set the frame rate (fps) to 30 or 60 Hz \n" + "fps = 60 \n\n" + + ";Indicate the number of rows and columns. They must be equal or inferior to what is indicated with the 'downsample' variable). \n" + "rows = 60 \n" + "cols = 80 \n\n"; + + +// ------------------------------------------------------ +// MAIN +// ------------------------------------------------------ + + +int main(int num_arg, char *argv[]) +{ + try + { + // Read function arguments + //---------------------------------------------------------------------- + bool use_config_file = 0; + string filename; + CDifodoCamera odo; + + if (num_arg < 2); + else if ( string(argv[1]) == "--help") + { + printf("\n\t Arguments of the function 'main' \n"); + printf("==============================================================\n\n"); + printf(" --help: Shows this menu... \n\n"); + printf(" --config FICH.txt: Load FICH.txt as config file \n\n"); + printf(" --create-config FICH.txt: Save the default config parameters \n\n"); + printf(" \t\t\t in FICH.txt and close the program \n\n"); + printf(" --save-logfile: Enable saving a file with results of the pose estimate \n\n"); + system::os::getch(); + return 1; + } + else if ( string(argv[1]) == "--create-config") + { + filename = argv[2]; + cout << endl << "Config_file name: " << filename; + ofstream new_file(filename.c_str()); + new_file << string(default_cfg_txt); + new_file.close(); + cout << endl << "File saved" << endl; + system::os::getch(); + return 1; + } + else + { + for (int i=1; i 1.1/odo.fps) + cout << endl << "Not enough time to compute everything!!!"; + + main_clock.Tic(); + + odo.loadFrame(); + odo.OdometryCalculation(); + odo.filterSpeedAndPoseUpdate(); + cout << endl << "Difodo execution time(ms): " << odo.execution_time; + odo.updateScene(); + } + } + + odo.closeCamera(); + + return 0; + + } + catch (std::exception &e) + { + std::cout << "MRPT exception caught: " << e.what() << std::endl; + return -1; + } + catch (...) + { + printf("Untyped exception!!"); + return -1; + } +} + diff --git a/apps/DifOdometry-Camera/legend.xpm b/apps/DifOdometry-Camera/legend.xpm new file mode 100644 index 0000000000..c43d4db317 --- /dev/null +++ b/apps/DifOdometry-Camera/legend.xpm @@ -0,0 +1,1840 @@ +/* XPM */ +static const char * legend_xpm[] = { +"348 200 1637 2", +" c #010101", +". c #030303", +"+ c #000000", +"@ c #060606", +"# c #121212", +"$ c #0A0A0A", +"% c #080808", +"& c #101010", +"* c #0D0D0D", +"= c #0E0E0E", +"- c #0C0C0C", +"; c #0B0B0B", +"> c #050505", +", c #040404", +"' c #0F0F0F", +") c #020202", +"! c #191919", +"~ c #3F3F3F", +"{ c #494949", +"] c #4D4D4D", +"^ c #4C4C4C", +"/ c #434343", +"( c #444444", +"_ c #414141", +": c #464646", +"< c #252525", +"[ c #171717", +"} c #B0B0B0", +"| c #BCBCBC", +"1 c #B8B8B8", +"2 c #AEAEAE", +"3 c #B9B9B9", +"4 c #B7B7B7", +"5 c #B6B6B6", +"6 c #B5B5B5", +"7 c #ACACAC", +"8 c #4A4A4A", +"9 c #161616", +"0 c #454545", +"a c #C0C0C0", +"b c #C2C2C2", +"c c #C3C3C3", +"d c #C4C4C4", +"e c #CCCCCC", +"f c #CBCBCB", +"g c #CACACA", +"h c #C9C9C9", +"i c #D2D2D2", +"j c #DEDEDE", +"k c #EEEEEE", +"l c #F6F6F6", +"m c #E7E7E7", +"n c #E8E8E8", +"o c #E6E6E6", +"p c #E5E5E5", +"q c #E4E4E4", +"r c #CDCDCD", +"s c #505050", +"t c #181818", +"u c #1E1E1E", +"v c #F5F5F5", +"w c #FAFAFA", +"x c #EFEFEF", +"y c #F8F8F8", +"z c #F9F9F9", +"A c #DBDBDB", +"B c #5E5E5E", +"C c #5A5A5A", +"D c #F7F7F7", +"E c #FDFDFD", +"F c #FFFFFF", +"G c #FEFEFE", +"H c #F3F3F3", +"I c #FCFCFC", +"J c #FBFBFB", +"K c #EAEAEA", +"L c #535353", +"M c #5B5B5B", +"N c #F4F4F4", +"O c #111111", +"P c #595959", +"Q c #F1F1F1", +"R c #F2F2F2", +"S c #F0F0F0", +"T c #585858", +"U c #E9E9E9", +"V c #A1A1A1", +"W c #545454", +"X c #424242", +"Y c #A5A5A5", +"Z c #ECECEC", +"` c #868686", +" . c #484848", +".. c #686868", +"+. c #D5D5D5", +"@. c #7B7B7B", +"#. c #3B3B3B", +"$. c #3A3A3A", +"%. c #393939", +"&. c #383838", +"*. c #A3A3A3", +"=. c #D6D6D6", +"-. c #555555", +";. c #8D8D8D", +">. c #949494", +",. c #515151", +"'. c #A7A7A7", +"). c #747474", +"!. c #1D1D1D", +"~. c #848484", +"{. c #BEBEBE", +"]. c #3E3E3E", +"^. c #E1E1E1", +"/. c #A6A6A6", +"(. c #797979", +"_. c #818181", +":. c #EBEBEB", +"<. c #EDEDED", +"[. c #9E9E9E", +"}. c #DDDDDD", +"|. c #A8A8A8", +"1. c #262626", +"2. c #6C6C6C", +"3. c #323232", +"4. c #C5C5C5", +"5. c #525252", +"6. c #292929", +"7. c #959595", +"8. c #888888", +"9. c #E0E0E0", +"0. c #767676", +"a. c #D7D7D7", +"b. c #676767", +"c. c #E3E3E3", +"d. c #3D3D3D", +"e. c #D3D3D3", +"f. c #242424", +"g. c #212121", +"h. c #C1C1C1", +"i. c #343434", +"j. c #373737", +"k. c #BABABA", +"l. c #A9A9A9", +"m. c #838383", +"n. c #636363", +"o. c #2B2B2B", +"p. c #BDBDBD", +"q. c #C6C6C6", +"r. c #D9D9D9", +"s. c #AFAFAF", +"t. c #DFDFDF", +"u. c #BFBFBF", +"v. c #B2B2B2", +"w. c #B1B1B1", +"x. c #D1D1D1", +"y. c #9A9A9A", +"z. c #BBBBBB", +"A. c #B3B3B3", +"B. c #ADADAD", +"C. c #DCDCDC", +"D. c #AAAAAA", +"E. c #E2E2E2", +"F. c #CECECE", +"G. c #D0D0D0", +"H. c #070707", +"I. c #909090", +"J. c #1C1C1C", +"K. c #2C2C2C", +"L. c #ABABAB", +"M. c #9F9F9F", +"N. c #C7C7C7", +"O. c #D4D4D4", +"P. c #8E8E8E", +"Q. c #565656", +"R. c #222222", +"S. c #979797", +"T. c #626262", +"U. c #6D6D6D", +"V. c #4E4E4E", +"W. c #272727", +"X. c #A0A0A0", +"Y. c #737373", +"Z. c #131313", +"`. c #646464", +" + c #CFCFCF", +".+ c #727272", +"++ c #232323", +"@+ c #6B6B6B", +"#+ c #696969", +"$+ c #7A7A7A", +"%+ c #989898", +"&+ c #777777", +"*+ c #6E6E6E", +"=+ c #4F4F4F", +"-+ c #656565", +";+ c #575757", +">+ c #D8D8D8", +",+ c #9B9B9B", +"'+ c #919191", +")+ c #282828", +"!+ c #313131", +"~+ c #141414", +"{+ c #3C3C3C", +"]+ c #090909", +"^+ c #333333", +"/+ c #2A2A2A", +"(+ c #7E7E7E", +"_+ c #969696", +":+ c #999999", +"<+ c #5F5F5F", +"[+ c #787878", +"}+ c #5D5D5D", +"|+ c #202020", +"1+ c #2F2F2F", +"2+ c #303030", +"3+ c #2E2E2E", +"4+ c #1A1A1A", +"5+ c #757575", +"6+ c #2D2D2D", +"7+ c #828282", +"8+ c #606060", +"9+ c #717171", +"0+ c #939393", +"a+ c #6F6F6F", +"b+ c #616161", +"c+ c #666666", +"d+ c #4B4B4B", +"e+ c #878787", +"f+ c #C8C8C8", +"g+ c #707070", +"h+ c #808080", +"i+ c #B4B4B4", +"j+ c #DADADA", +"k+ c #5C5C5C", +"l+ c #151515", +"m+ c #9D9D9D", +"n+ c #363636", +"o+ c #A2A2A2", +"p+ c #1F1F1F", +"q+ c #8A8A8A", +"r+ c #8C8C8C", +"s+ c #9C9C9C", +"t+ c #898989", +"u+ c #8B8B8B", +"v+ c #474747", +"w+ c #7C7C7C", +"x+ c #1B1B1B", +"y+ c #353535", +"z+ c #929292", +"A+ c #858585", +"B+ c #8F8F8F", +"C+ c #7F7F7F", +"D+ c #404040", +"E+ c #A4A4A4", +"F+ c #6A6A6A", +"G+ c #7D7D7D", +"H+ c #FFFFFD", +"I+ c #FFFFFB", +"J+ c #FEFEFC", +"K+ c #FEFFF9", +"L+ c #FDFEF9", +"M+ c #FDFEF8", +"N+ c #FEFFFF", +"O+ c #FDFFFE", +"P+ c #FDFFFC", +"Q+ c #FCFEFB", +"R+ c #FBFDF8", +"S+ c #FDFFFA", +"T+ c #FAFCF7", +"U+ c #FCFEF9", +"V+ c #F7F9F4", +"W+ c #F5FFFF", +"X+ c #F6FFFF", +"Y+ c #EEFAFA", +"Z+ c #E2EEEE", +"`+ c #F3FFFF", +" @ c #F2FEFE", +".@ c #F1FDFD", +"+@ c #F4FFFF", +"@@ c #F0FEFE", +"#@ c #EDFBFB", +"$@ c #F2FFFF", +"%@ c #F3FFFD", +"&@ c #E8F4F2", +"*@ c #F1FDFB", +"=@ c #F2FEFC", +"-@ c #F4FFFE", +";@ c #F7FFFF", +">@ c #F0FCFA", +",@ c #EAF6F4", +"'@ c #F9FFFF", +")@ c #E9F2F1", +"!@ c #F8FFFF", +"~@ c #ECF5F4", +"{@ c #F1FAF9", +"]@ c #EDF6F5", +"^@ c #EFF8F7", +"/@ c #F5FEFD", +"(@ c #EFFEFB", +"_@ c #F1FFFD", +":@ c #F0FFFC", +"<@ c #EEFDFA", +"[@ c #F2FFFE", +"}@ c #EFFBF9", +"|@ c #EEFAF8", +"1@ c #F6FAF9", +"2@ c #F8FCFB", +"3@ c #FBFDFC", +"4@ c #F6F8F7", +"5@ c #EDEFEE", +"6@ c #F5F5F7", +"7@ c #FFFEFF", +"8@ c #FDFBFE", +"9@ c #F8F6F9", +"0@ c #FEFCFF", +"a@ c #FFFDFF", +"b@ c #FAFCFB", +"c@ c #FAFEFD", +"d@ c #F9FDFC", +"e@ c #FAFEFF", +"f@ c #FCFFFF", +"g@ c #F4F8F9", +"h@ c #FDFDFB", +"i@ c #F9F9F7", +"j@ c #FAFAF8", +"k@ c #F8F8F6", +"l@ c #FCFCFA", +"m@ c #FBFBF9", +"n@ c #F7F7F5", +"o@ c #FEFFFA", +"p@ c #FAFBF6", +"q@ c #FCFDF8", +"r@ c #F3F4EF", +"s@ c #F9FAF5", +"t@ c #FBFCF7", +"u@ c #F8F9F4", +"v@ c #FAFCF9", +"w@ c #FEFFFD", +"x@ c #FAF9F7", +"y@ c #FEFDFB", +"z@ c #F5F4F2", +"A@ c #FFFEFC", +"B@ c #FBFFFF", +"C@ c #F6FBFE", +"D@ c #F7FCFF", +"E@ c #E9EEF1", +"F@ c #F5FDFF", +"G@ c #F4FCFE", +"H@ c #F2FAFC", +"I@ c #F2FCFD", +"J@ c #F4FEFF", +"K@ c #F4FDFC", +"L@ c #F6FFFE", +"M@ c #EBF4F3", +"N@ c #F3FCFB", +"O@ c #F2FBFA", +"P@ c #F5F9FA", +"Q@ c #F6FAFB", +"R@ c #F8FCFD", +"S@ c #F3F7F8", +"T@ c #F1F5F6", +"U@ c #F4FEFD", +"V@ c #F0F9F8", +"W@ c #EEF7F6", +"X@ c #F2FCFB", +"Y@ c #F5FFFE", +"Z@ c #EAF3F2", +"`@ c #F3F5F4", +" # c #F4F2F3", +".# c #FCFAFD", +"+# c #FBFFFE", +"@# c #F9FDFE", +"## c #F8FAF9", +"$# c #F7F9F8", +"%# c #FCFEFD", +"&# c #F5F7F6", +"*# c #F9FBFA", +"=# c #F4F4F2", +"-# c #F6F6F4", +";# c #F4F6F5", +"># c #F1F3F2", +",# c #F9FBF8", +"'# c #FBFDFA", +")# c #FBFAF8", +"!# c #FEFDF9", +"~# c #FFFEFA", +"{# c #FFFCF9", +"]# c #FFFDFA", +"^# c #FFFEFB", +"/# c #FBFBFD", +"(# c #FDFDFF", +"_# c #FCFCFE", +":# c #FCFDFF", +"<# c #FAFBFD", +"[# c #FDFEFF", +"}# c #FDF8FC", +"|# c #FFFCFF", +"1# c #FBF6FA", +"2# c #FEF9FD", +"3# c #FFFBFF", +"4# c #FFFAFE", +"5# c #F8F9FB", +"6# c #FEFEFF", +"7# c #F8F7F5", +"8# c #FDFCFA", +"9# c #FAF8F9", +"0# c #FFFDFE", +"a# c #FEFCFD", +"b# c #F7FBFC", +"c# c #F7FBFA", +"d# c #F3F2EE", +"e# c #F7F3F0", +"f# c #FFFBF8", +"g# c #FFFAF7", +"h# c #FFF8F6", +"i# c #F9F1EF", +"j# c #FFF5F9", +"k# c #FCF1F5", +"l# c #FFF4F8", +"m# c #FFF8FC", +"n# c #FBF0F4", +"o# c #FBF2F5", +"p# c #FAF1F4", +"q# c #FFF9FC", +"r# c #FFFBFE", +"s# c #FFFBFD", +"t# c #FFFAFC", +"u# c #F9F3F5", +"v# c #FAF4F6", +"w# c #FFFCFD", +"x# c #FFFAFB", +"y# c #FFF8F9", +"z# c #FEF5F6", +"A# c #FFF6F7", +"B# c #FBF2F3", +"C# c #FFF9FA", +"D# c #FFF6FA", +"E# c #F7EBEF", +"F# c #FFF3F7", +"G# c #FFF7FB", +"H# c #F8F2F4", +"I# c #F6F0F2", +"J# c #F7F1F3", +"K# c #FFFAFD", +"L# c #FCF3F6", +"M# c #FFF6F9", +"N# c #FDF4F7", +"O# c #FFF8FB", +"P# c #FFFBFC", +"Q# c #F7EEEF", +"R# c #FDF4F5", +"S# c #F8EFF0", +"T# c #FCF3F4", +"U# c #FAF1F2", +"V# c #FEF9F6", +"W# c #F2EDEA", +"X# c #F8F3F0", +"Y# c #FDF9F8", +"Z# c #FFFEFD", +"`# c #FFFCFB", +" $ c #F7F5F6", +".$ c #F4F9FD", +"+$ c #E4E9ED", +"@$ c #E8EDF1", +"#$ c #F9FEFF", +"$$ c #EDF2F6", +"%$ c #F6FBFF", +"&$ c #F2F7FB", +"*$ c #FAFFFF", +"=$ c #E3E8EB", +"-$ c #F4F9FC", +";$ c #F0F5F8", +">$ c #F5FAFD", +",$ c #F8FDFF", +"'$ c #F2F7FA", +")$ c #F3F8FB", +"!$ c #EFF4F7", +"~$ c #EEF3F6", +"{$ c #EDF2F5", +"]$ c #F1F6F9", +"^$ c #EBF0F4", +"/$ c #F3F8FC", +"($ c #E9EEF2", +"_$ c #F0F5F9", +":$ c #EFF4F8", +"<$ c #F1F6FA", +"[$ c #EEF3F7", +"}$ c #F0F6F6", +"|$ c #FDF5F3", +"1$ c #F5EBEA", +"2$ c #F6ECEB", +"3$ c #FFF5F5", +"4$ c #FFF9F9", +"5$ c #FFF7F7", +"6$ c #FFEFF3", +"7$ c #FCE9ED", +"8$ c #FFEDF1", +"9$ c #FFECF0", +"0$ c #F4E1E5", +"a$ c #FFF0F3", +"b$ c #F8E9EC", +"c$ c #F6E7EA", +"d$ c #F9EAED", +"e$ c #FFF5F8", +"f$ c #FFF9FB", +"g$ c #F8E8EB", +"h$ c #F5E5E8", +"i$ c #EFDFE2", +"j$ c #FFF4F7", +"k$ c #F3E3E6", +"l$ c #FAEAED", +"m$ c #FDEDF0", +"n$ c #FCECEF", +"o$ c #FFF7FA", +"p$ c #F8E3E8", +"q$ c #FFF3F8", +"r$ c #FFEFF4", +"s$ c #F9E4E9", +"t$ c #F6E1E6", +"u$ c #FBE6EB", +"v$ c #FFEAEF", +"w$ c #FFF2F7", +"x$ c #FFF4F9", +"y$ c #FFECF1", +"z$ c #FFEEF3", +"A$ c #FCE7EC", +"B$ c #FAE5EA", +"C$ c #FEEEF1", +"D$ c #F7E7EA", +"E$ c #F7E8EB", +"F$ c #F3E4E7", +"G$ c #F6E6E9", +"H$ c #FFF2F5", +"I$ c #F2E2E5", +"J$ c #FFEFF2", +"K$ c #FFF3F6", +"L$ c #FAEFED", +"M$ c #FBF0EE", +"N$ c #FCF1EF", +"O$ c #FFF5F3", +"P$ c #FFF6F4", +"Q$ c #FFFDFB", +"R$ c #ECE7E4", +"S$ c #E0DBD8", +"T$ c #FEFAF9", +"U$ c #E6EAEB", +"V$ c #EAF1F7", +"W$ c #F3FAFF", +"X$ c #DEE5EB", +"Y$ c #F5FCFF", +"Z$ c #F7FEFF", +"`$ c #F2F9FF", +" % c #F6FDFF", +".% c #EFF6FC", +"+% c #F0F7FD", +"@% c #DDE4EA", +"#% c #EBF2F8", +"$% c #F6FEFF", +"%% c #F4FCFF", +"&% c #E9F1F4", +"*% c #EFF7FA", +"=% c #E7EFF2", +"-% c #F3FBFE", +";% c #EEF6F9", +">% c #E5EDF0", +",% c #EDF5F8", +"'% c #E6EEF1", +")% c #ECF3F9", +"!% c #E6EDF3", +"~% c #E8EFF5", +"{% c #F1F8FE", +"]% c #E9F0F6", +"^% c #EEF5FB", +"/% c #F4FBFF", +"(% c #E7EEF4", +"_% c #E7EFF1", +":% c #E4ECEE", +"<% c #F6FCFC", +"[% c #F4FAFA", +"}% c #E7EBEC", +"|% c #F6F1EE", +"1% c #E4DCDA", +"2% c #A69C9B", +"3% c #897D7D", +"4% c #918383", +"5% c #B7A7A8", +"6% c #EFDFE0", +"7% c #F9E9EA", +"8% c #FDE2E7", +"9% c #B59CA0", +"0% c #9C8387", +"a% c #998084", +"b% c #AF969A", +"c% c #FAE1E5", +"d% c #F5DFE2", +"e% c #F7E1E4", +"f% c #BDA7AA", +"g% c #988486", +"h% c #927E80", +"i% c #A18D8F", +"j% c #E4D1D3", +"k% c #F3E0E2", +"l% c #EEDBDD", +"m% c #CCB9BB", +"n% c #927C7F", +"o% c #9A8487", +"p% c #A58F92", +"q% c #EBD5D8", +"r% c #F2DCDF", +"s% c #DBC5C8", +"t% c #998386", +"u% c #836D70", +"v% c #8E787B", +"w% c #E4CED1", +"x% c #FBE5E8", +"y% c #917B7E", +"z% c #806A6D", +"A% c #92797D", +"B% c #D5BCC0", +"C% c #F4DBDF", +"D% c #FBE2E6", +"E% c #F3DADE", +"F% c #9E8589", +"G% c #9D8488", +"H% c #C0A7AB", +"I% c #EFD6DA", +"J% c #F0D7DB", +"K% c #A88F93", +"L% c #957C80", +"M% c #AE9599", +"N% c #F6E2E4", +"O% c #F7E3E5", +"P% c #F0DCDE", +"Q% c #B8A4A6", +"R% c #957F82", +"S% c #A48E91", +"T% c #F1DBDE", +"U% c #F9E3E6", +"V% c #786265", +"W% c #806C6E", +"X% c #948082", +"Y% c #FFF4F6", +"Z% c #FFF0F2", +"`% c #DECACC", +" & c #857173", +".& c #877375", +"+& c #D1BDBF", +"@& c #FFF7F9", +"#& c #E8D4D6", +"$& c #9B8789", +"%& c #9D898B", +"&& c #D4C0C2", +"*& c #F9E5E7", +"=& c #F5E1E3", +"-& c #F3DFE1", +";& c #988986", +">& c #968784", +",& c #958683", +"'& c #BCAEAB", +")& c #E8DAD7", +"!& c #EDE2DE", +"~& c #EFE5E3", +"{& c #9A928F", +"]& c #AEA6A3", +"^& c #FBF7F4", +"/& c #FAF9F5", +"(& c #F2F6F7", +"_& c #EFF3F4", +":& c #C9CDCE", +"<& c #858F98", +"[& c #869099", +"}& c #E4EEF7", +"|& c #E9F3FC", +"1& c #EBF5FE", +"2& c #C6D0D9", +"3& c #818B94", +"4& c #727C85", +"5& c #8E98A1", +"6& c #CED8E1", +"7& c #F3FDFF", +"8& c #828C95", +"9& c #C5CFD8", +"0& c #E8F2FB", +"a& c #87919A", +"b& c #838D96", +"c& c #B1BBC4", +"d& c #E2ECF5", +"e& c #F0FAFF", +"f& c #DFE9F2", +"g& c #909AA3", +"h& c #7F8992", +"i& c #AAB4BD", +"j& c #E0EBF1", +"k& c #EBF6FC", +"l& c #E8F3F9", +"m& c #A8B3B9", +"n& c #848F95", +"o& c #859096", +"p& c #98A3A9", +"q& c #E3EEF4", +"r& c #DDE8EE", +"s& c #B6C1C7", +"t& c #828D93", +"u& c #8C979D", +"v& c #909BA1", +"w& c #DEE9EF", +"x& c #E9F4FA", +"y& c #E4EFF5", +"z& c #C6D1D7", +"A& c #869197", +"B& c #838E94", +"C& c #8B969C", +"D& c #D0DBE1", +"E& c #E2EDF3", +"F& c #F1FCFF", +"G& c #D9E4EA", +"H& c #8F9AA0", +"I& c #889399", +"J& c #7F8A90", +"K& c #CBD6DC", +"L& c #E5F0F6", +"M& c #DCE7ED", +"N& c #919BA4", +"O& c #BBC5CE", +"P& c #E5EFF8", +"Q& c #EFF9FF", +"R& c #DEE8F1", +"S& c #8D97A0", +"T& c #8A949D", +"U& c #ADB7C0", +"V& c #E7F1FA", +"W& c #98A2AB", +"X& c #8B959E", +"Y& c #949EA7", +"Z& c #E6F0F9", +"`& c #B2BCC5", +" * c #8F99A2", +".* c #848E97", +"+* c #BDC7D0", +"@* c #808A93", +"#* c #D5E0E2", +"$* c #E5F0F2", +"%* c #ECF8F8", +"&* c #D3DFDF", +"** c #818B8C", +"=* c #899394", +"-* c #8B9596", +";* c #D7DFE1", +">* c #E7ECEF", +",* c #BABFC2", +"'* c #F5F9FC", +")* c #F3F7FA", +"!* c #FFFBFB", +"~* c #FFFCFA", +"{* c #F1E7E6", +"]* c #8D8181", +"^* c #746666", +"/* c #817172", +"(* c #A89597", +"_* c #FFEEF0", +":* c #FFEFF1", +"<* c #A18488", +"[* c #7E6165", +"}* c #816468", +"|* c #9F8588", +"1* c #FFECEF", +"2* c #FFEAED", +"3* c #B89FA2", +"4* c #7B6567", +"5* c #7A6466", +"6* c #887274", +"7* c #FCE8E9", +"8* c #FFF4F5", +"9* c #FFF1F2", +"0* c #CAB6B7", +"a* c #80676A", +"b* c #856C6F", +"c* c #8D7477", +"d* c #F2D9DC", +"e* c #FFEBEE", +"f* c #E3CACD", +"g* c #886F72", +"h* c #967D80", +"i* c #846B6E", +"j* c #F3DADD", +"k* c #FFE7EA", +"l* c #866D70", +"m* c #90777A", +"n* c #7F6568", +"o* c #D5BBBE", +"p* c #FFE6E9", +"q* c #FFE5E8", +"r* c #886E71", +"s* c #81676A", +"t* c #B89EA1", +"u* c #FFF1F4", +"v* c #FFE8EB", +"w* c #957B7E", +"x* c #8A7073", +"y* c #7C6265", +"z* c #A1878A", +"A* c #FFECEE", +"B* c #FFF1F3", +"C* c #B39A9D", +"D* c #775E61", +"E* c #F7DEE1", +"F* c #FCE3E6", +"G* c #D1B8BB", +"H* c #957C7F", +"I* c #927C7E", +"J* c #F5DFE1", +"K* c #F0D7DA", +"L* c #D5BCBF", +"M* c #8C7376", +"N* c #91787B", +"O* c #9A8184", +"P* c #FAE1E4", +"Q* c #FBE2E5", +"R* c #876E71", +"S* c #796063", +"T* c #836A6D", +"U* c #D4BBBE", +"V* c #7A6763", +"W* c #75625E", +"X* c #7B6965", +"Y* c #B7A5A1", +"Z* c #FBECE7", +"`* c #FFF7F4", +" = c #FFFAF6", +".= c #887E7C", +"+= c #8A827F", +"@= c #F7F2EE", +"#= c #FDF9F6", +"$= c #F7F9F6", +"%= c #EDF1F2", +"&= c #B8BCBD", +"*= c #6C7982", +"== c #6F7C85", +"-= c #707D86", +";= c #ECF9FF", +">= c #F0FDFF", +",= c #F1FEFF", +"'= c #C6D3DC", +")= c #717E87", +"!= c #6B7881", +"~= c #78858E", +"{= c #D6E3EC", +"]= c #6E7B84", +"^= c #C5D2DB", +"/= c #EAF7FF", +"(= c #6D7A83", +"_= c #AFBCC5", +":= c #7B8891", +"<= c #65727B", +"[= c #929FA8", +"}= c #E9F6FE", +"|= c #EFFCFF", +"1= c #97A4AC", +"2= c #6A777F", +"3= c #6D7A82", +"4= c #849199", +"5= c #A7B4BC", +"6= c #647179", +"7= c #C5D2DA", +"8= c #6C7981", +"9= c #7B8890", +"0= c #D8E5ED", +"a= c #E7F4FC", +"b= c #D5E2EA", +"c= c #6F7C84", +"d= c #637078", +"e= c #CCD9E1", +"f= c #77848D", +"g= c #6A7780", +"h= c #68757E", +"i= c #B8C5CE", +"j= c #E5F2FB", +"k= c #A5B2BB", +"l= c #EBF8FF", +"m= c #88959E", +"n= c #75828B", +"o= c #84919A", +"p= c #A9B6BF", +"q= c #E4F1FA", +"r= c #76838C", +"s= c #EDFBFC", +"t= c #F0FEFF", +"u= c #CDDBDC", +"v= c #687375", +"w= c #6E797B", +"x= c #6F797B", +"y= c #D0DADC", +"z= c #D3DBDE", +"A= c #989DA1", +"B= c #FEF6F4", +"C= c #F4E8E8", +"D= c #7C6E6E", +"E= c #6E5E5F", +"F= c #7F6C6E", +"G= c #9C888A", +"H= c #F8E2E5", +"I= c #FFE6E8", +"J= c #A18486", +"K= c #795F60", +"L= c #7A6061", +"M= c #917778", +"N= c #FCE4E4", +"O= c #FFE7E7", +"P= c #B09B9A", +"Q= c #735E5D", +"R= c #7E6A69", +"S= c #7F6B6A", +"T= c #FEEAE9", +"U= c #F9E5E4", +"V= c #FFEDEB", +"W= c #C0AEAC", +"X= c #796365", +"Y= c #7C6668", +"Z= c #7E686A", +"`= c #EFD9DB", +" - c #FFE9EB", +".- c #FFEAEC", +"+- c #DBC5C7", +"@- c #735D5F", +"#- c #6A5456", +"$- c #E7D1D3", +"%- c #FDE7E9", +"&- c #FCE6E8", +"*- c #745E60", +"=- c #C6ADB0", +"-- c #7E6568", +";- c #745B5E", +">- c #AD9497", +",- c #897073", +"'- c #71585B", +")- c #977E81", +"!- c #FBE5E7", +"~- c #F6E0E2", +"{- c #A58F91", +"]- c #755F61", +"^- c #FFE9EC", +"/- c #C3ADAF", +"(- c #6B5557", +"_- c #786264", +":- c #F9E3E5", +"<- c #FFEDEF", +"[- c #D8C2C4", +"}- c #705A5C", +"|- c #675153", +"1- c #E6D0D2", +"2- c #FAE4E6", +"3- c #766062", +"4- c #D1BBBD", +"5- c #F7E1E3", +"6- c #7D6863", +"7- c #745F5A", +"8- c #826F69", +"9- c #B4A19D", +"0- c #F5E3DF", +"a- c #FAEBE6", +"b- c #F8EAE7", +"c- c #726763", +"d- c #837977", +"e- c #FFFEF9", +"f- c #F9F8F4", +"g- c #B5B9BA", +"h- c #6C7884", +"i- c #717D89", +"j- c #67737F", +"k- c #E9F5FF", +"l- c #E6F2FE", +"m- c #E5F1FD", +"n- c #BCC8D4", +"o- c #697581", +"p- c #727E8A", +"q- c #D4E0EC", +"r- c #E0ECF8", +"s- c #BAC6D2", +"t- c #E3EFFB", +"u- c #687480", +"v- c #6A7682", +"w- c #A2AEBA", +"x- c #E7F3FF", +"y- c #E2EEFA", +"z- c #EBF7FF", +"A- c #74808C", +"B- c #798591", +"C- c #636F7B", +"D- c #919DA9", +"E- c #E2EFF8", +"F- c #8A97A0", +"G- c #69767F", +"H- c #727F88", +"I- c #7D8A93", +"J- c #E3F0F9", +"K- c #E1EEF7", +"L- c #E9F6FF", +"M- c #79868F", +"N- c #5F6C75", +"O- c #E7F4FD", +"P- c #BFCCD5", +"Q- c #626F78", +"R- c #DCE9F2", +"S- c #CBD8E1", +"T- c #7A8790", +"U- c #66737C", +"V- c #C8D5DE", +"W- c #DEEBF4", +"X- c #6B7783", +"Y- c #66727E", +"Z- c #B4C0CC", +"`- c #DDE9F5", +" ; c #E8F4FF", +".; c #76828E", +"+; c #9BA7B3", +"@; c #E4F0FC", +"#; c #F1FDFF", +"$; c #7A8692", +"%; c #788490", +"&; c #F0FCFF", +"*; c #9AA6B2", +"=; c #6D7985", +"-; c #6F7B87", +";; c #DCE8F4", +">; c #B5C1CD", +",; c #DCECEC", +"'; c #E1F1F1", +"); c #EAF8F9", +"!; c #C5D3D4", +"~; c #647273", +"{; c #788385", +"]; c #C9D3D5", +"^; c #F1FBFD", +"/; c #C9D1D4", +"(; c #8D9296", +"_; c #FEF8F8", +":; c #FFFAF8", +"<; c #DFD3D3", +"[; c #AD9F9F", +"}; c #8C7C7D", +"|; c #917E80", +"1; c #B7A3A5", +"2; c #E7D3D5", +"3; c #EDD5D5", +"4; c #C6AEAE", +"5; c #9E8686", +"6; c #968180", +"7; c #B6A1A0", +"8; c #E0CBCA", +"9; c #F8E4E3", +"0; c #FFECEB", +"a; c #BCAAA8", +"b; c #988684", +"c; c #948280", +"d; c #A29390", +"e; c #EADBD8", +"f; c #FBECE9", +"g; c #F6E7E4", +"h; c #D1C3C0", +"i; c #988686", +"j; c #938181", +"k; c #A39191", +"l; c #CFBDBD", +"m; c #FBE9E9", +"n; c #FCEAEA", +"o; c #CDBBBB", +"p; c #9E8C8C", +"q; c #978585", +"r; c #A29090", +"s; c #FFF0F0", +"t; c #FFF6F6", +"u; c #DAC8C8", +"v; c #A99797", +"w; c #958383", +"x; c #958182", +"y; c #BDA9AA", +"z; c #F3DFE0", +"A; c #FFF3F4", +"B; c #E4D0D1", +"C; c #AC9899", +"D; c #8F7B7C", +"E; c #BEAAAB", +"F; c #E7D3D4", +"G; c #FFEDEE", +"H; c #B19D9E", +"I; c #907C7D", +"J; c #937F80", +"K; c #A28E8F", +"L; c #EFDDDD", +"M; c #BEACAC", +"N; c #A69494", +"O; c #948081", +"P; c #A59192", +"Q; c #E0CCCD", +"R; c #FFEFF0", +"S; c #CDB9BA", +"T; c #9D8B8B", +"U; c #8B7979", +"V; c #A79595", +"W; c #DBC9C9", +"X; c #FAE8E8", +"Y; c #D3C1C1", +"Z; c #A49292", +"`; c #8F7D7D", +" > c #A18F8F", +".> c #CBB9B9", +"+> c #F4E2E2", +"@> c #FFF8F8", +"#> c #D0BEBE", +"$> c #AC9A9A", +"%> c #9C8A8A", +"&> c #CCBABA", +"*> c #F5E3E3", +"=> c #FEECEC", +"-> c #F6E4E4", +";> c #A48F8A", +">> c #96817C", +",> c #9A8781", +"'> c #C4B1AD", +")> c #F4E2DE", +"!> c #FDEEE9", +"~> c #D9CBC8", +"{> c #AFA4A0", +"]> c #B6ACAA", +"^> c #DDD8D4", +"/> c #FEFBF6", +"(> c #FDFCF8", +"_> c #F6F5F1", +":> c #E2E6E7", +"<> c #C5C9CA", +"[> c #7F8B97", +"}> c #838F9B", +"|> c #9DA9B5", +"1> c #CCD8E4", +"2> c #EEFAFF", +"3> c #BDC9D5", +"4> c #8E9AA6", +"5> c #75818D", +"6> c #909CA8", +"7> c #C2CEDA", +"8> c #8B97A3", +"9> c #B1BDC9", +"0> c #D3DFEB", +"a> c #7D8995", +"b> c #7C8894", +"c> c #BBC7D3", +"d> c #DBE7F3", +"e> c #EFFBFF", +"f> c #D5E1ED", +"g> c #9EAAB6", +"h> c #86929E", +"i> c #9FABB7", +"j> c #AEBBC4", +"k> c #7F8C95", +"l> c #A6B3BC", +"m> c #DDEAF3", +"n> c #9FACB5", +"o> c #D3E0E9", +"p> c #C0CDD6", +"q> c #89969F", +"r> c #CCD9E2", +"s> c #EDFAFF", +"t> c #98A5AE", +"u> c #8B98A1", +"v> c #C1CED7", +"w> c #DBE8F1", +"x> c #B0BCC8", +"y> c #CBD7E3", +"z> c #828E9A", +"A> c #AAB6C2", +"B> c #D0DCE8", +"C> c #D2DEEA", +"D> c #F2FEFF", +"E> c #DEEAF6", +"F> c #85919D", +"G> c #99A5B1", +"H> c #C8D4E0", +"I> c #87939F", +"J> c #7E8A96", +"K> c #8995A1", +"L> c #D6E6E6", +"M> c #E9F9F9", +"N> c #EBF9FA", +"O> c #C3D1D2", +"P> c #8D9B9C", +"Q> c #7A8587", +"R> c #97A2A4", +"S> c #BFC9CB", +"T> c #E1EBED", +"U> c #DAE2E5", +"V> c #BBC0C4", +"W> c #FCFBF9", +"X> c #EFE5E4", +"Y> c #DACECE", +"Z> c #CFC1C1", +"`> c #D2C2C3", +" , c #F8E4E6", +"., c #DDCBCB", +"+, c #C4B2B2", +"@, c #C6B4B4", +"#, c #DCCCCC", +"$, c #F4E4E4", +"%, c #FCECEC", +"&, c #F9EBEA", +"*, c #E3D5D4", +"=, c #C5BAB8", +"-, c #C0B5B3", +";, c #F6ECEA", +">, c #FAF0EE", +",, c #F5EBE9", +"', c #D9CFCD", +"), c #D3C5C4", +"!, c #CDBFBE", +"~, c #D1C3C2", +"{, c #EADCDB", +"], c #FFF7F6", +"^, c #FFF9F8", +"/, c #EDDFDE", +"(, c #CBBDBC", +"_, c #DBCDCC", +":, c #F7E9E8", +"<, c #FDEFEE", +"[, c #E7D9D8", +"}, c #CCBEBD", +"|, c #D9CBCA", +"1, c #FCEEED", +"2, c #FFF4F3", +"3, c #F6E8E7", +"4, c #FFFBFA", +"5, c #FAECEB", +"6, c #DACCCB", +"7, c #D2C4C3", +"8, c #DED0CF", +"9, c #ECE1DF", +"0, c #F1E6E4", +"a, c #D4C6C5", +"b, c #C1B3B2", +"c, c #CEC0BF", +"d, c #FEF0EF", +"e, c #F4E6E5", +"f, c #C6B8B7", +"g, c #CEC3C1", +"h, c #E6DBD9", +"i, c #F7ECEA", +"j, c #F5E7E6", +"k, c #E1D3D2", +"l, c #D5C7C6", +"m, c #EBDDDC", +"n, c #CABCBB", +"o, c #E6D8D7", +"p, c #F8EAE9", +"q, c #ECDEDD", +"r, c #DECBC7", +"s, c #D2BFBB", +"t, c #D0BEBA", +"u, c #E4D2CE", +"v, c #FEEFEA", +"w, c #FFF9F6", +"x, c #F7ECE8", +"y, c #E3D9D7", +"z, c #D3CBC8", +"A, c #ECE7E3", +"B, c #FBFAF6", +"C, c #F7F6F2", +"D, c #D0D4D5", +"E, c #B5BFC9", +"F, c #B3BDC7", +"G, c #BCC6D0", +"H, c #D7E1EB", +"I, c #F1FBFF", +"J, c #F2FCFF", +"K, c #D5DFE9", +"L, c #B8C2CC", +"M, c #BAC4CE", +"N, c #C0CAD4", +"O, c #D3DDE7", +"P, c #EAF4FE", +"Q, c #C8D2DC", +"R, c #E9F3FD", +"S, c #EEF8FF", +"T, c #D8E2EC", +"U, c #B9C3CD", +"V, c #C6D0DA", +"W, c #C7D1DB", +"X, c #DFE9F3", +"Y, c #E4EEF8", +"Z, c #C3CDD7", +"`, c #B0BAC4", +" ' c #CCD6E0", +".' c #E0EAF3", +"+' c #AEB8C1", +"@' c #CBD5DE", +"#' c #EAF4FD", +"$' c #D6E0E9", +"%' c #B6C0C9", +"&' c #C8D2DB", +"*' c #DDE7F0", +"=' c #D4DEE7", +"-' c #BFC9D2", +";' c #C7D1DA", +">' c #E3EDF6", +",' c #E1EBF4", +"'' c #C4CED7", +")' c #ACB6BF", +"!' c #B5BFC8", +"~' c #D5DFE8", +"{' c #EDF7FF", +"]' c #CFD9E3", +"^' c #C1CBD5", +"/' c #D1DBE5", +"(' c #DEE8F2", +"_' c #C2CCD6", +":' c #BDC7D1", +"<' c #C9D3DD", +"[' c #E5EFF9", +"}' c #E6F0FA", +"|' c #D0DAE4", +"1' c #BBC5CF", +"2' c #E1EBF5", +"3' c #C4CED8", +"4' c #BEC8D2", +"5' c #D2DCE6", +"6' c #BFC9D3", +"7' c #D8E6E7", +"8' c #E7F5F6", +"9' c #ECFAFB", +"0' c #D6E4E5", +"a' c #B7C2C4", +"b' c #ACB7B9", +"c' c #C4CED0", +"d' c #DFE9EB", +"e' c #E8F0F3", +"f' c #E3EBEE", +"g' c #D0D5D9", +"h' c #ECF1F4", +"i' c #FAF5F2", +"j' c #F1E9E7", +"k' c #E4DAD9", +"l' c #DCD0D0", +"m' c #E1D3D3", +"n' c #EDDDDE", +"o' c #F8E8E9", +"p' c #F8EDEB", +"q' c #EADFDD", +"r' c #E0D5D3", +"s' c #E5DAD8", +"t' c #F4E9E7", +"u' c #FDF3F1", +"v' c #FBF1EF", +"w' c #F3E9E7", +"x' c #EFE7E4", +"y' c #E0D8D5", +"z' c #E1D9D6", +"A' c #DFDAD6", +"B' c #FBF6F2", +"C' c #FAF5F1", +"D' c #EBE6E2", +"E' c #E0D8D6", +"F' c #DFD7D5", +"G' c #E3DBD9", +"H' c #EDE5E3", +"I' c #F7EFED", +"J' c #F8F0EE", +"K' c #EEE6E4", +"L' c #E1D9D7", +"M' c #EBE3E1", +"N' c #F4ECEA", +"O' c #E7DFDD", +"P' c #E2D8D7", +"Q' c #E7DDDC", +"R' c #F4EAE9", +"S' c #FCF2F1", +"T' c #E3D9D8", +"U' c #DED4D3", +"V' c #E5DBDA", +"W' c #E9DFDE", +"X' c #FAF0EF", +"Y' c #F0E6E5", +"Z' c #DFD5D4", +"`' c #E8DEDD", +" ) c #FFFBF9", +".) c #F6EEEC", +"+) c #E5DDDB", +"@) c #FFF8F7", +"#) c #F9EFEE", +"$) c #FBF1F0", +"%) c #F3EBE9", +"&) c #DDD5D3", +"*) c #FFF7F5", +"=) c #FCF4F2", +"-) c #EFE7E5", +";) c #DED6D4", +">) c #E8E0DE", +",) c #F5EDEB", +"') c #FBF3F1", +")) c #E6DEDC", +"!) c #F0E8E6", +"~) c #EDDEDB", +"{) c #E5D6D3", +"]) c #E1D2CF", +"^) c #E9DBD8", +"/) c #F9EBE8", +"() c #FEF3EF", +"_) c #F8EEEC", +":) c #EEE6E3", +"<) c #F1E9E6", +"[) c #FEFAF7", +"}) c #F8F7F3", +"|) c #EEF2F3", +"1) c #E1E5E6", +"2) c #DCE3ED", +"3) c #D8DFE9", +"4) c #E1E8F2", +"5) c #EEF5FF", +"6) c #F0F7FF", +"7) c #E6EDF7", +"8) c #DAE1EB", +"9) c #D5DCE6", +"0) c #D6DDE7", +"a) c #DEE5EF", +"b) c #E9F0FA", +"c) c #E7EEF8", +"d) c #D7DEE8", +"e) c #DFE6F0", +"f) c #F1F8FF", +"g) c #EBF2FC", +"h) c #DDE4EE", +"i) c #D4DBE5", +"j) c #E9F2F9", +"k) c #EDF6FD", +"l) c #ECF5FC", +"m) c #E1EAF1", +"n) c #D3DCE3", +"o) c #D0D9E0", +"p) c #DAE3EA", +"q) c #E6EFF6", +"r) c #EAF3FA", +"s) c #E5EEF5", +"t) c #CED7DE", +"u) c #DBE4EB", +"v) c #E8F1F8", +"w) c #DDE6ED", +"x) c #D1DAE1", +"y) c #D6DFE6", +"z) c #D9E2E9", +"A) c #D4DDE4", +"B) c #E3ECF3", +"C) c #EEF7FE", +"D) c #D9E0EA", +"E) c #D3DAE4", +"F) c #D2D9E3", +"G) c #DBE2EC", +"H) c #E4EBF5", +"I) c #CED5DF", +"J) c #E5ECF6", +"K) c #ECF3FD", +"L) c #E3EAF4", +"M) c #E2E9F3", +"N) c #E8EFF9", +"O) c #E4EFF1", +"P) c #ECF7F9", +"Q) c #EFFBFB", +"R) c #E5F1F1", +"S) c #D7E1E2", +"T) c #D1DBDC", +"U) c #D9E3E4", +"V) c #E5EDEF", +"W) c #F1F9FB", +"X) c #EAEFF2", +"Y) c #F7FBFE", +"Z) c #F8FCFF", +"`) c #F9F4F1", +" ! c #EBE1E0", +".! c #F5E9E9", +"+! c #FFF3F3", +"@! c #FAF2F0", +"#! c #E9E1DF", +"$! c #E8E3E0", +"%! c #FCF7F4", +"&! c #F9F5F2", +"*! c #ECE8E5", +"=! c #E7E3E0", +"-! c #EAE6E3", +";! c #EAE9E5", +">! c #E1DDDC", +",! c #E7E3E2", +"'! c #F0ECEB", +")! c #F7F3F2", +"!! c #FAF6F5", +"~! c #F2EEED", +"{! c #EFEBEA", +"]! c #DFDBDA", +"^! c #E9E5E4", +"/! c #F5F1F0", +"(! c #FCF8F7", +"_! c #ECE8E7", +":! c #DEDAD9", +"~ c #F0F1F6", +",~ c #F4F5FA", +"'~ c #FAFBFF", +")~ c #F6F7FC", +"!~ c #F1F2F7", +"~~ c #FBFCFF", +"{~ c #F8F9FE", +"]~ c #F7F8FD", +"^~ c #F9FAFF", +"/~ c #F5F6FB", +"(~ c #F6F7FB", +"_~ c #F2F3F7", +":~ c #F1F2F6", +"<~ c #F3F4F8", +"[~ c #F9FAFE", +"}~ c #F5F6FA", +"|~ c #F4F5F9", +"1~ c #F7F8FC", +"2~ c #F5FBFB", +"3~ c #F0F2F1", +"4~ c #FBF9FA", +"5~ c #F8F6F7", +"6~ c #F9F7F8", +"7~ c #FBF9FC", +"8~ c #F9F9FB", +"9~ c #F9F7FA", +"0~ c #FAF8FB", +"a~ c #F7F5F8", +"b~ c #FAFAFC", +"c~ c #F8F8FA", +"d~ c #F3F3F5", +"e~ c #F7F8FA", +"f~ c #FBFCFE", +"g~ c #F7F7F9", +"h~ c #FEFAFB", +"i~ c #FDF9FA", +"j~ c #F7F3F4", +"k~ c #FAF6F7", +"l~ c #F3EFF0", +"m~ c #F9F5F6", +"n~ c #FCF8F9", +"o~ c #F8F4F5", +"p~ c #FBF7F8", +"q~ c #F6F2F3", +"r~ c #F9FBF6", +"s~ c #F8FAF5", +"t~ c #F4F4F6", +"u~ c #F5F6F8", +"v~ c #F9FAFC", +"w~ c #F6F7F9", +"x~ c #F6F6F8", +"y~ c #FCF6F6", +"z~ c #FFFDFD", +"A~ c #FFFAFA", +"B~ c #FFFCFE", +"C~ c #FEF8FA", +"D~ c #FFFDFC", +"E~ c #FFFCFC", +"F~ c #FAF4F4", +"G~ c #FDF7F7", +"H~ c #F8FAF7", +" . + @ # $ % & * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * = = * - ; $ > % , ", +" - * > @ & ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' & & ' = * * = # , + ", +"+ + . # # ; $ & ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' ' & & ' = * * * ' , ) ", +". + . ! ~ { ] ^ / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / / ( ( ( / _ _ : < * # ", +"+ + [ ^ } | 1 2 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 3 3 1 4 5 6 7 8 - ' ", +", + 9 0 a b c d e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e e f e e e e f g h e ] > # ", +"+ + 9 0 i j k l m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m m n m o p q r s - t ", +" u s o v w x y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y z z z z y l l A B & ' ", +") , - C q D E F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F D H I F G w F F F G G G E E z F F J E F G y E E I I I I E E F z l G F J I F G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F G G G G F E H w G I D F G G G G G G G G I E E G G E E I G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F D l G F G w z F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G z F I J F E y G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F G G F F E J K L = * ", +"* ; ' M p D E F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G y F F G E I w J F F G G G E E E G F E z J G F F F G G G G G G F N F F E I F F I G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F G G G y F F F G F w D G G G G G G G G E E G G G G E E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F D I F I J F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F J N v F F I G F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F G G F F E J K L = * ", +"O * = P q y G F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G w G F G G I I F F F F F G G G G F F F F G z z E F F F F F F F F v z J G G E G E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F E y Q z G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F I D z G F E E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G R N w F G E E F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F G G F F E J K L = * ", +"' $ * P p z G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F J v y F F F F F F F F F F F F F E E F F w w F F F F G G F F F F J l J G I G F G G G G G G G G G G G G G G G G G G G G G G G G G G G E E E E I E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F G G G G G E G G G F F F F F G H D F E F G S G G G G G G G G F F G G G G F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F G G G G G E D F F E F E w I E G G G G G F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F G x R G F E G G G G G F F G G G G G G G G G G G G G G G G G G G G G G G G F F G G F F E J K L = * ", +"' - = C p y E E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G E J E F F J v R E E E E I I I I J y l w F G E F E E I I I I E E I E E F z R D G G G G G G G G G G G G G G G G G G G G G G G G G G G G E I I J J E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F G G E E E I E E E G F F F F l J F z z F I G G G G G G G G F F E E E E F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F G G E E E F G J y l Q N F E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G y R H D J F F K E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G F F G G F F E J K L = * ", +"& - = P q y G F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G D G F F y w F F F F F F F F F G F F E z I F G J J J w w w w J J Q D y I F F F y G G G G G G G G G G G G G G G G G G G G G G G G G G E E I J w w E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F G E I I w w J I I E G G I J E F F l l F G G G G G G G G F G I J J I G F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F G E I I F y E F E G F v I I E G F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G N E F F F l v F I I E G F F F F G G G G G G G G G G G G G G G G G G G G G G G G F F G G F F E J K L = * ", +"' ; * T q y G F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G E F I R v F I o w z z z y y D D n E F I y G F F w w z z z z w w E F F J S U N F G G G G G G G G G G G G G G G G G G G G G G G G F G E I J w z z E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F G E I J D y z w J I I E m F D p E E H F G G G G G G G G G I w z z w I G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F G E I J F A V W X Y z Z J I E G F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G w F o | ` ...+.J I E G F F F F G G G G G G G G G G G G G G G G G G G G G G G G F F G G F F E J K L = * ", +"& - = C p z E E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G I G z v F E d @.#.#.#.$.$.%.%.&.*.=.F F I F F w w w z z z z w w G l F v V -.;.G G G G G G G G G G G G G G G G G G G G G G G G G F G E I J w z y E E E G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F G E J J l l D y z J J I F z >.,.'.v E J G G G G G G G G E J z y y z J E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F G E J J U E Z ).!.~.F z J J E G F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G R F w H {.X #.{.J J E G F F F F G G G G G G G G G G G G G G G G G G G G G G G G F F G G F F E J K L = * ", +"= ' * -.m z w F G G F F F G E I F D G v I F z F D E z I F G D F z w F G E G J G F E J I w E k h ].# +.r m ^./.s (.R J D F I F w D Q G F w E n F E F I E _.9 ~.E E G J w F F N E G k F F E I I F E J F J w l E F y F R E G n I G :.J G :.F l I G F F E I F F E I w G J I F I F D F <.G F N F I w G G G F Q F F J J x G G G z R F G G F E F l E G <.F D S F w J J F F ).# [.k z w z F v J G J F F G F Q J F v w E F v v F G J G y F z F J l F G F y E E F J F F z H F F F E F }.F G F G G y F F G w I w |.1.~.I w D I v G I F S F F x F G E F H G F N F G z I I D F w y z G F S F v F G J J G z F x G l I F q G E F I Z G j 2.3.4.J J I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I E F F Q z w F J I E S G F E l E F E J y z G E I J w I E J F w j X 6.}.G E F F 7.8.9.F F F w F F y F :.z G 0.,.a.I D U G J o F F :.E F F G F x G G F <.K F w N l F I Q k G F I l G z x U 9.G F b./ +.l F F F v z I E G w G E z F E G G F z N I G w I F F F G F l k F N U F J K F J w F U z E F E F E F N Z v {.$.'.:.E R w J F H c.F G D H I F G y E y E F F F N G k E z B d.e.E E F F Q R F S G N E F F G w E F F G k F F v I F F F y y E y F I v G G y F x l p w I w |.1.~.I J y G y F F F H F w I F D w F F G E E l I F E F F Z F F E y x F E F z k I E J F l G F N F F G N k l F x <.R (.f.b J J I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I E F v J F F F z F l G F F G w F E F F J I F F z G G F F y J w q s g.h.Q y :.z Q N F F k J S F J N F G D x i.j.<.Z l G G F G F :.I F F c.F F J F J F E G v G F F S F F E E G S F F D E F D k 9.8 $.k S Q D z E F E J F l E F x E G D v E J E y D F <.F J E q H F F F I c.F F F F Q F G N F I D G v J F F E F /.' k.z F D G J F I G H S J D F J l I v F F R J G F F U G :.$.X Z G H F E H F F x G F E z E F Z F y m F y D G F F F F v v F w F G J l F I x J S I I z I J l.< m.I I D F F I w F E w D F w G F v G F E F I D H H y F F I G F v G E l G E F F w J F E G F I H <.E F G F Q F w o n.o.=.J J I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I w y p.| q.m r.5 5 s.F v H G F G U D E F I w F G F E F G l y v t.] 9 k F F S d Q z R F F G u.p.p.v.w.F x.y.9 #.'.z.h o e A.p.<.E F a.1 4 y :.| 4 k.f F w B.d {.C.F D 9.F D r.c 3 2 h.o q F p D.; f.v.6 4.F w F E.F.A.3 d m F S J F I F v f l.1 E F | 7 B.D F J F l z F e.v.7 G.Z G F C.a 5 4 +.l I 4./.z.e.7 8 H.I.B.s.a.F l z G D b 1 c f l J j z.} 9.q b 3 | t.:.G U l.J.K.[.4 e D N F H w.r 6 u.^.F I G 3 6 q.v S i } 4.G.L.7 3 E.F S h.c /.e G n =.1 q.M.h E D I J l.< m.I E E F y J F p N.w.{.4 |.Q F g } z.Q O.a h.N.Q F K y x F q 1 h.v.A F F F p F F h.4 B.6 q J F F S n J P.} f 1 Q._ k.J J I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I I e 5.R.].S.P.T.^ i.b x H F F x F F J F G l I F J y w E w F w ^.X < +.9.S 4 U.p J k E i ~.].V.b.~ W.c X.Y.@ Z.`.P ;. +M.i.+ ~.F S 7.$.J.P.'..+-.++@+5 I..+#+$ $+<.F F I %+&+Y.Q.,.W.*+r.G ;.n.J.> 2.n.0.d Z 9.*.=+s -+;+(.>+F F y S N =.,+_ W.@.'+2.C %.(.O.G t.F 4.Y.;+C Q.=+*.F l y.)+) $.5 q e.!+~+-+X.P.{+]+^+P @+} R D J F <.%+W [ l.E n P./+f.(+_+Y.^ ^+Y.c.l :+<+@ 1.[+}+0.F.E 9.,+Q.~.=+<+m.U v e.*+|+1+v.@+2+$ ;+~.3+4+~ k.n b *++ i.P.e *+5+L T 6+^+f l J I D.< 7+I G G J v F x 8.8+@+9+8 ++X.a.0+2+t L.'+2.L 1.b.U I y E k.$+a+b+] 3.L.D F Q R Y c+(.@+s d+{.F N E m e+^ ..8+: ; 3.f+J J I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I <.F G.: 9 g+u.D 7+- g+l F w E Q I x U l F G l Q E J E F E F J 9.X ++g+&+h+ .: p G G S 0.K.[.z E ;.8+r.c.K ] ].E.F Q D Z M.g.e+N Q R |.- : 0+x.l (.)+T.'+K F ] t M.w k i+1+@+R E N.{ : z.J F I t -.Z H F y D 8+H.f Q k ~.d.y.z m E l G E z e+4+{ :+x.j+k+K.D.G F z M _ f+E K <+u 7 G I D.~ ^+} I Q -.m.E.R Z P.l+c G J y F G l Z w H m++ 7+N F x [+= 8 *.k c.M 6.h F E H $.n+j F J F F V.3+m+U y 2.6+S.w F E.k+{+@.m...W.$+=.0.; 7+I F F +; |.q U.d+4 v H 7.> g+N J E D.< 7+E F F I w x o+!+_.S j w.T.v.z o V.+ g+| w m <+K.*.D <.E.{+C e.H <.-.6.A H F |.p+_.a.D u._ s 4.D ^.B + '.F K q.( )+f+J J I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I I F C.$.^ +.J z v < d.l F Q G J z F F l v F F F l w F F w G z t.#.- e+l.:+k+V.+.K F S `.+ |.F S Z e n l I !+^+z w J J E L.> ` k E w y.[ 7+y F :.q+- e+k v E L.g.r+E J x B.r.G :.J #+|+L.K :.F &.1.j D E :.N.o.-.Z F J 7 1+M R H :.v G J x g+4+s+<.F E m.p+s.w R {.- U.E K D 6 /+h+l F q t+n+0.t.9+c+g F F F r+~+L.y F x R I F F w J Y % 7.G w Z U.~+X.D E R @.^+l.t.J G K.j.n z w c.h & `.F F F a./ s C.I l W ~+` S y A.N.F d R.b+C.q S _+( o S N./.U E I z.@ ( H w E D.f._.E F G G F k u+& 7+G F F b F.v I P % }.G F R y.o.#+R N /.j.>.:.D F 7+% S.G.q *+3. +F y l U.!+v.E e ++{ F F Z :.c+1+4.J J I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I R J x j.v+>+w F o & |+:.z H G x Q F t.w+i.i.V.<+E.k I F y E E m W ]+m F q 5 @+c.G D J z.@ 1..+G.Q F D F m ++] c.w E l F B., V D J G 2 < r+:.E w D.o.0.S G <.5 O $+F k E x I H F v >.x+X.F F R !+{+9.E D I q++ m+I D v }.0 i.c.z G F D D F ` p+L.H I <.s+x+'+x F <+! B.v G F p.f.{ H F D H [+o.W.[+=.F m F D 2.3.6 v F E F y x v w F '.x+m.F J G r+; L.F K F '+- '.w F S )+d.Z G F w ,+H.:+y v R f d.#.K v c.0.~ 1 F N E F l c.Q.j.h F l y+I.H J F y S F y A /+n+R w E L.f._.E F I F D F f+x+|+^ | D I E z m : 4++.G 9.E r./+_ k F 3+n+a F E Q | % n.F x.W.W G.k F y @.g.P.9.r+|+_.F p E R b+y+z.J J I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G E F F G J K E ^.d.{+^.F Q 9.R.j.l E :.D I R F c.j.+ . + V.=.R G E E I v :.( 6.j z G z E.F H F w Q j 9 # l+[+j+F R ^./ v+Z F G <.F 5 , y.D F S [.p+z+Q F U Y ! m+R E Z 6 t 8.K G z F z %.o.R.g.$ V F G Z 2+v+c.H l R *+Z.]+++R.1.R.H.3.w.F E F F K F A+$ w.z E Q u+|+s.Z l T - l+u /+* i. 6.z ^.G v n <+@ {.H k G l c.V !.i+S w w F R R G J H X.x+B+m F H t+~+a v E p 8.6.X.F y y 6.1+R H Q l #++ 6+; &.9 # l+R.j+F e.c+^+| N H G G F H V ++_.F V )+F k F l G @.6.++R.* 3+l F H i+< z+w I F D I E R m i. o.3+=.G l v v+K.t.l F D d {+#.Q k 0 > % 3+6.t < ) _ n 4.0 H.R.++|+~+< g.q+o 5+- l.K F Q x (.W.F.E G E E E F F G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F G J F N n : 0 p Q F :.!.!.S l F I <.I J E N F F m F w F F F E F D t.W [ q N J H F :.G z Q E o w j+!+ -+Z y ^.2+v+c.U D y E [.. q+H v D 5 O C+k z E p.l+;.Z z F h ) [+E F R D++ }.O.R 8.u y.x G z /+3+:.F D D ).* h.l K <.F l x F v w I G Q F ` O 2 v w F 0+H.S.D F 8+t r E H k S w k l E F Z s+&.$ l+^.E o E F (+t w.F F x E E F I G J [.; S.G G I S.$ 2 D F z %+- '.N J F ^+y+N Q G F 7+Z.v.D w F I F =.J G J 9+y+f+F F w x K H f 1.#+E.b+;.J w Q E+J.F+9.G r O d+N I F 4 = w+G F E D F G :.F }.F $.; v+c w F v++ m S l F N.^+{+o y Q.W 9.Z t.J E H I E k.W.-+q G F R N r.S I A+t S.N D R n b+/+q.D D D z E F F I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E w F x <.( ~ c.n G <.x+R.F <.I G z D y n Z F E z y G D I F R l E Z V.@ c.z E k F B.a+h I D S F Z e ] $.q.G E i._ m F H F F V x+` F :.F c Z.r+F H F z.x+r+U n y G.= s+^.Q c+|+5 F I F 7+g./.v F y 6.~ p G n G i++ %+w F F F x :.F E z z F J G m.4+/.F D F ,+l+X.F y >.]+A.v l F l F F J K R 1 M e.2 $ T m k F J ` x+A.k J E F S Q E H D B.. ` F o F u+& 2 D S x V ; E+:.F F %.1+m F Q Z y.* t+F E D q D F y :.m 2.d. +I R <.v v F q B j.u+d+q l J e W.T F E D U J.: D H D i+4+A+G S F F N l h J F k S [+4+|.R G L + r.E D F s.n+F+K v B u g F w F x F F K =.V.-+}.Z I y G F F Q ;.' C+w w F H b+d.q.F F I J E F F E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E z E F ^.$.#.E.F G E.++++<.I w D F F F D F F U H F F D F F Q I F C. .g.j+F F x C.).D++.R + i U F q -.0 g F R ].W.h G O.Q U 7.u a+y F R m+l+` E F y :+)+q+S F v 5 4+T.F F P ~+Q j F A.8+p+y.v F Z ( f.B.F C.C.}./ %.U I N p A E.D S S Q F F S (+o.X.G I <.A+!.'+R E r X n.b I D z F.C.F F N.5.S.x E.:++ 5+=.K F y.! h+z R e.S G G U J H E+& $+z J F Y.p+'.E F U >.t E+D F :.X u 6 F r.<.<.{+$.h E l E t.i G J U b+u d y F I F G F c.L.O 1.m.H w v z.1+5+9.J k S.> #.H F H *.o.` R F :.F F k #+r+K Z l B+i.2 k Q P ~+P.F F r...K.Y I F v.%..+^.F N I s.F.F x m.3.'.F I I t.i ^.F >+: 1+ +F z d &./+r y I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F G F F I y v R y.p+W./.Z r.q+9 - B+w F l F v J S F J I I v F F F l x F K %+< ++(+y.M.y.g+3.-.G :.++Z.s+%+8.0 7.x v <.y.o.k+y.S.G.i+T @ ( u.F c 8+[ V.5 D >+B 4+s z.I e.F++ Q.q.O.E+6.w+M.[.E+*+x+C e G D V 6.-.[.s+e Q z.M 5.7.w.Y z+M.>+I z l G Z a W & b+f n q.T ; -.3 F G 7.y+T.A.E+7 C+w.C.y.`.W.k.z H '+* x+k+e l p.V.$.I.M./.E.F E v v F.C H.L a z c ] O <+h w d C $ n.=.y v z+$.;+P.z+e w [.0 c+D.z+_+z+P.k N E+0 < G+g F F Q U J y e.( )+d <.F R }.{+P '+/.m.` / 1.L.c.F.2.# d+w.E H R F H ,.u ;.1 5+P (.x.F x 0 @ %.m+y.A+B [+m F J j+r+~ 5+y.,+v.C+B.E z >+@+] 7+/.L.0+[.| S D r+)+a+m+P.'+] & (.r.m y G I J E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F J y H n %+9+0.m+r.G.` Y.a+;.Z G F G G F x l v D G z y E G H k I E.s+a+5+$+&+` r+[+9+z.=.R m+7+(+0.9+A.z G Q F z _.w+;.7 t.b _.9+` 4 v h u+@.@.l.<.r 8.a+).w.:.4._...(+X.F w ,+7+I.I.a 1 $+C+f v I v o+h+` M.y D Q 4 (+h+U.m.k.m F E J y G Z 4._.P ` h.p N.A+U.t+p.J N l f+;.0.C ~.f U F 7+0.m./.v C.~.~.U.w+q.l :.p.@.$+q+a.I U l F Z e _.-+G+6 <.} e+@+@.z.m k.h+Y..+ +k F Q V Y.A+6 Z F l f h+g+7+h+q.p F K t+&+).q+u.k D k x G F o a :+p D F <.F j+'+5+~.w.C.I.$+S.>+g u+F+(+L.<.F N H F s.9+C+9+m+y.}.S F l D+% (.~.9+~.4 Z F n F m z o+_.G+h+7+U D N :.D n 7+r+G+8.m+j+l J F }./._.7+C+a 4.2.7+A K w F I z I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F G J D F F k E G S F F l F E n v F F l K G F E F y F F z F F F J J y n F F l U N Q I F :.F F H E.G y J p F I y J N ^.F k R F G Q F l k E I H l :.Z F Q D J Q w F l N F H F R l F E.F 9.y F I H z R x G w H G I F o v F x F v D G l D N S x J F G y H F l F N <.y l z F v x k p I F N J D z F z I F K F v E z I k F I z E G I F F F w k F I E I l J F N w F R G F R y F Q F v R F D S F Q F <.G F m x F S F E E E R l F v E F F F F w S y F R l y E Q E q G F K E F j+E o F E H G F D F <.G J I N w F E :.o J R D F 8 p+m z F y z l v F F n F E N l J S K F F E Q F K I G w R E E N I F J k E H J E :.F D J F F E I E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F G w D Q k J G E w N G D E l J x G E F F w E F D G G F F J R l I y w F Q R F F F K F H J F N G <.E E N F y y N F l F S F <.H F l S N F l y F J w F z E v F E F Q w F Z l F x o F D Q F I :.Q F F z z I E Z F D j F E U <.F v l I l J E F D N Q N F E S F l z F G Q G N E G G F k :.F l <.G K I y R F k F I v E J J U F F w w E R D F Q G v y I F w p F y F v F l D F K F H F E E F F D E y E F S G F <.F v F <.w F :.E y F F l Q I J F F n y F m F F :.F l Q F U F F R E l y w F G E D F y N U G D R F z F N G z F ].' t.z F l F J v F y G E.w z z J E F :.Z y F k F ^.l F G J F I l F F D y F I v F Q G I w w E F F I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F z z z z z z z z w w J I E G F F F F F F F F F F G G G G G G G G I I I I I I I I D D D D D D D D I I I I I I I I I I I I I I I I w w w w w w w w G J y z J I w D I I J z y D l v J J w w w w w w E E E E E E E E D D D D D D D D F F E I w z D D z z z z z z z z I I I I I I I I z z z z z z z z I I I I I I I I w w w w w w w w I I I I I I I I w w w w w w w w I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I z z z z z z z z I I I I I I I I w w w w w w w w m G R R F +.=+. b x F H S F I E.w w w w w w w w z z z z z z z z F E z l l z E F I I I I I I I I G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F I I I I I I I I w J I E G G F F F F F F F F F F G G G G G G G G I I I I I I I I w w w w w w w w I I I I I I I I I I I I I I I I E E E E E E E E F E J J E G I w J w w w w z z z J J J J J J J J E E E E E E E E E E E E E E E E F F G E I J w z I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I E E E E E E E E I I I I I I I I E E E E E E E E I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I I J J J J J J J J F F v N h T + ~+9 B+v F k S G I E E E E E E E E I I I I I I I I F G J z z J G F I I I I I I I I G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F J I I E G F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F G G F F G E w w J J J I I I J J I E E G G G E E E E E E E E F F F F F F F F F F F F G E E I F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G E E E E E E E E Z I F E F H m G F F E w D I F F F F F F F F F F F F F F F F F F F F E E E E F F G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F I I E G G F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I I I I E E E E J I E G F F F F G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F E I k S F F l x x l F F E E H F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F E E G G F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F F G E E G F F G G E I J J I I E G F F F F G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G v F F D v G w J G F E N l F G F F F F F F F F F F F F F F F F G F F F F F F G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F G G F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F G G G G G G G G E F F F E I I G F F F E I J w w I E E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F D w F F D w F F J y F F E E D G G G G G G G G F F F F F F F F G F F F F F F G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F E G F F E I E G E E E I I J J J E E E E E E G G F F F F F F F F F F F F F F F F F F F F F G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F l E w H I F J N N E F E y D E G F F F F F F F F F F F F F F F F F F G G G G F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F E G F F E E G F w J J J I I E E E E E E I I I I F F F F F F F F F F F F F F F F F F F F G G G E F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F E I E G F E I F G E F F F w F F F F F F F F F F F F F F F F F F G E E G F F G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J F H F F w F F N R E G m F G I F F F F F F F F F G G G E E I I I l E U F w F q G F y v F Q G F D z G D G F l G w G G E G w F E G G R F w x E F E v F F w F F l F w F z y <+G+n G F w w w G F Q F F k E F v J F G D F G F J l F F F G D J G G F G I F I I J G F v F k F F R I E H F y N F F y F E F I G F E E F I J F E w z F F Q I E J K F E Q I w F I y F F J z J F F E G I E y J I l F J F G H F Q F F R <.F F F l F E F N J G w y F y F F k I G F J I z z F G G R z G F D N G J F F D G F z F D I F D G G I F w I v G F I F y I w F F R J I J R F y z F F G F F z G F G F F l F F w z F F E G F F y F N y N E F U F G J F R F l G F I F G y y F z w F G F E H F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J w J J w z F F D F F F Z F E G I F F F F F F F F G G G E E I I I F p N O ~+> &.[ P.Z F w w F D F J w z I l F F F I G y k y w H G v F F N E F m H F G x R F G S E F G F q.3+,+:.D <.z F y F E w D H D F F I z H Q w x E F z w G R z G F F I l N R J v E F G Q Q J Q w E I k I F F G J z G w v w v D F z R F E H F z G G G z z F G I E F F J F R y J D H F k e...8 G.D G E H E J K F F z y y I G G F y y N F F z J F F z :.z F E <.I E F J l w E J y k H G F F I H E F F D D w G I G I I w J J D z J F :.y F R G R F F F G D N D z F J U S F G Z F z F >+C 8 z.v R y R y z v v D F l J F F F J l l D l v F l F I N E I <.Q R F F N E G z S R N w F l D J E w R R E F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J <.E I v y w J F w w F J F F F I F F F F F F F F G G G E E I I I Z B+# q R F '.. .+:.S F k m F <.I y F F E.w x E N E F Q N S U F z w H <.J D z F 9.F y z G J Q F F E E e+u f H N G F v w y S w F E I t.p z J N F F F Q k z F k y H l E z l w I F F R R z F F w F N G I l F G J x y N z J l z G F G y y N k D F I F I z E E l N z Z U G z k F E S w E F F j t.5.X +D R G S w F F Q v J w F F y I z F F k w G U F x z z J F I z F F E R E G I G }.G R F F v z z J v E Q S N I F S F H l E w J G w l l x G F z F y I H w N H J y F R E G F Q Z K I z k x c+/ F.E F D J F G F G H J G I J z v y E F y G F I n F F p Z F R F F F n J w H N D G F E v F F J D F w S G F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J F E F w G z D v z I I G w w F J F F F F F F F F G G G E E I I I t.].9+E.I y 9.[+P f D F 2.d+}.l G k x F K F x G y y H H z J l F F l y F F G 9.].*+9.F E w E E F D F A -.;+Q I y F G Z F F H D I F N.`.r+c.y o D w v v S w I F v F z F v v E H D F F I S Q D D J E J w G E z Q z F N F F y z D G F G F F I I J v z z F F G v Q F F H G D E G w.s D.q z y y E K F v F Q F F x H G y D F I z w R F y G y :.H w Q F D F G J G R H F E F x R I I F H E D G N R F I z G D S G F I N x F D z F z y F y w Z G z <.F w E F H w H l F y I w F z L.D+P.G F G Z F H r.F z J x F E H z I D l G D D l N G F l G N J F U R G D F v l J n c D+q+v N F F v z G v D G G Q v F E G F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J F U J F S y E x x F z I v l F E F F F F F F F F G G G E E I I I V R.q+w F I :.5 V E I D D+!.q F I I K F I D y J E F <.l F l G J l F J Z }.E Q !+-.j+w x E F F R l F M.j.D.w F E D F y x I F F y J /.6.h+D F n F R Q F F p J F I G w E v v E J F U G F F G k k F F R F G p Q F G z K G E w F y y F I Z x F E Q J E w F N y F y G <.l J l G F z+K.V l R z J Q x F z F F n F S F v F y J E H y N F D I y F E N F w J G I v G E z k v E E n N E :.F x F I x z F E J z v F G R N <.F N F G F l S I S z D R F J I F E.w G F z Q z E F K F E 6 $.r+E m y F z F G E K I <.I D F E Z I F F F F y N F F Q I Q J F I w F y H K z F N G.3.q+k S J F :.y F w F k z F l G F x F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J y S D +._+y.'.%+X.N D F I J F F F F F F F F F F G G G E E I I I 6 K.D+p y D G F <.F B._.|+o.'+` *.S y Z G._+s+'+%+e.E F U /.,+E+n j B.l.{.6 9+4+V.o+,+v.v G E R G R -+X 9.N I I D N.2 %+0+7.2 D 7 Y. ,.>.7.s.F z F e.` Y *.t+j N F U f /.s+h n s+%+P.k.w F y F G v F w H F l 7 y.z+V u+'.D F I z [.S.'.t+v.E F F a.} e+|.t.p.:+X.d w J C.s.=+= -.y.B+4.<.S.o+2 a.Z Z y.>.|.o +m+[.l.n F y +m+,++.J F i >.[.b l U F F }.7 X.o+>.A.E F I p :+'+s.F y +.w.` w.E v G Q 5 %+|.M.0+u.J w y y S G H R j r+|.L.*.l R H F c.b Y y.*.u+z.l E+v+> ,.S.,+| Z D.G+l.j F D 2 ,+M.m }.[.V S.<.:.F.|.:+'.x.F F F E E.F.V I.r+B.R E Q l.M H.( M.[.k.Q F E r V |.'+k.I F R v y F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J E F {.b.C F+B j.W m N G G G E I F F F F F F F F G G G E E I I I p ] J.8 s+w Z G z F 1 r+# l+~.t+u+}.r.5+h+).@.n.)+*+<.E r.I.!+&.4 [+# + ..} ..f.!.@.).m+Z z F G F d ( (.S y D v 5 M @+u+@+3.d.k [.0.H.s (.h+7 w R 5 *+s ;.h+6+9+u.G U p.;+[ F+s+A+Y.%.~ D.z I H I F D F F o y.T.&+w+g+J./ j+l e P.T $+;.: 8 D.j+R b e+W.j.7.B+0.)+|+Y F p o+Q.$ Q.0+` 2 h t+D+j.>+N m '+J.K._.u+0.b+{+/.G R p.s ++z+R o 5 -.l+_.E S G +.+;+U.[+M v+z+m E 9.[+H.k+o n g (.. L Q z K u+-+.+w+a+Z._.H y R E H F D A.~.-+b.M d+z+F F l z+.+).Y.*+O W j /.k+u L (+t+*.h X.i.v+a J l q+$.u _.o+G+`.O q+E+s+_.b+D+&+H p I i ).C+7+).5.3+m+k :.l.=+u B h+_.l.Z D } ).9+&+B ] z+x G R F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J z H 2.p+A.F }.P.-.G y R y F F E F F F F F F F F G G G E E I I I k j L * ].b.e.R F k D N n+!+A F E E k.[ ;.z w f D+d.F.N J D v+n+..%+_+2+b+G A 6+T.E F Q E z F y z _+%.w.Q F R <.M ].{.F E.w+L v w } 1.8.^.F J D p f.M 9.J k r+~+,.}.F w (+l+$+2 Q y z+W.`.t.F y D F l D E >.{+Y.Z F }.{ ,.:.9.w+& Y k y >+s 1+c v G q ^ x+e+r G {.# P N F S /.f.;.R S F I n M y+h H G l ^+3+A+c F B.J.#+p G F :+l+m.F v F /.+ u+Q F m b.++V F <.a v+%.4 N F F.R.s U Q F u.[ 5.I J c 6+).p k H -+`.y F N F x y k %.y+:.F i $+[ | z a.5.`.d F F *+ .F F E+f.t+F E F w K -+j.{.F G v Y.[ <+k.R r.n+J.@.e N h ^ 8 r.G E S.)+%+F J 7 R.;+y G l L.6.(.x S F G 3 X }+^.I }.v+W.3 G Z J F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I F G %.)+i+S I R j+J F H F I Z F F K I E Q G F D F F F F F G E I v D Z 2 J.J.g.X.z Q k G 0 o.j F k F m f+F w Q K -+/+z.D J H }+J.~.D l f r.F a.3+C U E F F x z F r.c+`.C.F y l Z _ p+a y E ^.e.J I f+9 ).F D x G @.R.y.U F E o -.9 | F v :+!.z+F v G e =+,.{.G y F F D v E...6+h v N w r.h y 4./+5.o F S v l.1+U.R H F v+3+i 9.F w /+R.v z N '.9 %+H J w v Q M D+i z I J d.y+z.F G U y+2+J F R [.4+r+F E <.D.! u+x F D.W.,.y H E y 7.o.[+k R j W.<+<.w F f = P J J D.&.,.j Q E A <.z E D G F K B.- h+G k E a R.[+D >+!+i.r J w 9.>+Z Z v.p+q+F v w z o 5+].4.R J <.G+& *.F z D ].+ +.F y H 2.|+G.G Z w p.k F n }.$.1+D y R w.1.u+J q F G Y @ A.w z F >.> r+x J I I E G F F E J w U 5.* = ", +"= ' * -.m z w F G G F F F G E I <.z a l+' n.q m v F E z J w w F b.n+J.p+{ 2 z w G G F F G E I J F l S I n G+# ' w.w F K J.y+N k E H F :.v F F S 5+f./.F F j @+X 1 I z I G H f %.C <.y E J F F E i+/ ` S J I R Z ;.++++F+q E N F F h.p+7+K z F G T |+b F }.q E g+; %+F S z+~+l.N w F K -+y+l.I F R F I F u.%.8 q F F I z w x ,+p+5+G G n S c D+b.c.F E X 2+t.I w o i.6.I F y *./+'.E G E Q K b._ c l w F { D+e l D <.y+|+Q z F {.n+t+n l F c t $+F F ;.x+;.F D l k 3 )+<+S G S i.,.o v E +Z.Q.I F }.`.9 t |.F H :.Q l D R z p #+$.B.E w F X.4+`.y n I.[ ]+G+k E J F I D.' I.H E F G K `.6+F.J S F h+/+s.l N D b+W.>+y N K ).!+h o G p F I m G ^.y+/+l G G 2 o.` I E <.a.;+!+D.E G q V ! #+F K k I E G F F E J w U 5.* = ", +"= ' * -.m z w F G G F F F G E I F F N 2 R.$ + $+9.F I F l v F J #.l++ + !+o+l l E E G G E I J w D G q K F F v.6+B r.E F o._ J S K F n F E.{+ % [ @ l.E z v C+[ a F w F w z j 1+k+H o E R v z n @.^+A.F H F D v G 0+4+) @ ` H E S w.W.S.t.y G t.W.6.k.H F F z G+# A+I U r+! e F J R U #+j.3 E I l F N F s./+`.9.Q J v k F H u+p+,+n E F Q d 0 y+e.F D { {+c.F :.K 2+& <.l H ;.[ y.:.z F H p #+$.h.F w z #.6++.l R l d.u F y :.s+!.B+w v H } l+e+H Q .++ S.N w F Z a.d.Q.n y >+g.Q.:.z E A R.;+E p F k 7+* + * 2 S F E I S F G V.) p+ ) ++Z.) !.I z m %+< > J.:+x F F D.~+l.R F <.v J Y./+h w H G `.R.i+I J R 8+J.r I E E...o.p.F R R J i+!.. . # * y G z y.R.~.e.E F G &.~+* l++ - + n+U k v I E G F F E J w U 5.* = ", +"= ' * -.m z w F G G F F F G E I H k J F F k._ , A+Q w F J R F N G F F k k F E G I I E E I J w z k E.F F v l +8 : i Q F 6+3+q o G F e.|+&.d F z 9+p+i+F H p *+n+b F l N x F <.)+T.Q R F J w E E./ C >+F S E F w C.F F 1 ++$ ,+z F k.p+q+t.F F z ( D+| R y H k q+) B+F w '+[ '.9.J E Z ;+K.5 S N F G H I i+&.`.Z D F y x y :.;.= h+<.K G l h %.n.k G Q ].3+>+J F J 6.= E J F /.6+m+:.E E G o b.0 4.F E E 0 1.j+F F J !+, I G E A.p+7.G S Q a < ` E I [.< P.F w x :.1 ^+B q z ^.1+P Z I D O.p+V.z G J N F I (+O ; w.J z w R E F W )+O.F z E Q w F I I G F U Y 3++ Y N N B.! M.:.Z F z l $+1+4.E F G `.!.{.F D y T.l+x.E E Z a+o.d v J b !.T }.v w v+& y H F u.1+A+E v Z n ( X A y N F z F x J F I I E G F F E J w U 5.* = ", +"= ' * -.m z w F G G F F F G E I F J e.E U t.A n+#.K w N F l w y x :.G F v l w F I I E E I J w z t+<+^.w v F c.b.W k E :.)+1+<.F N l b+4+:.N H U u+|+6 l x U B ].x.y l F G z C.!+5.x G Z z k F '.f.Y S E w z F m A E E n G.p+s o x 5 [ 5+S F p J $+, $+v v F Q ~ p+h.D D A+!.'+G :.E +.0 { e.G E F z F F d { ~ p k I E E N F r 1+|+v G x F /.H.$+C.x J .n+C.m k E ++!.F Z m m+! >.F J E.F ^.8+( u.l Q N }+^+F.l R x D+Z.R S <.L.g.A+E F U /.! e+F Q 2 ++i.:.F F F u+!.G+Q G <.o.=+q F v {.O d+F F j+e.F z D a = @+S J F F I v h+t s+z F E w l H l ^.i G p v q.g.C Q R z.< _.E F Q D t.*+n+4.z o F (.p+5 D p J F+p+>+R <.x 5+)+q.J K /+!+K F F C.V.# F x o v.!.(+k R N F ` ~+k.F Q G E R F n J k I E G F F E J w U 5.* = ", +"= ' * -.m z w F G G F F F G E I F e.J.4.G F h $.-.R G <.F J w G G F v z F v Q J E E G G E I J w (+++w.E w y 2 W.e+H F Q Q.!.Y n o |.n.# f I K +X - L.l F z P J.Y q I I v G r.( ~ c l {.S F D *+&.t.E E F D y F.^ D.N l g u n.G l g j.<+=.=.c x +o.D+4 v F 6 [ ).y H H (+9 @+^.S k S.{+C+^.Z S E N F F n (+1.w+D x Q F.1 k r.-.)+u+:.F x.b. .5 R F H ( i.a.y z E.R.x+q w F 6 R.P <.E.N.I a.<+3+{.F F j+V.)+5 F F +.( )+c.F D 3 n+-+}.z +@.) _.<.F n B $ m+^.E q.T ^ z.F I A #.D+{.:.9.'.= ] N S B.T p w G m+]+8.F F y E w E +.!+F+A J l U e }.F 6 / c F F y.> -+G y a K.v+i :.A.z A g+j.v.F z :.U.[ [.E F R C ' N.F F t.8+++A.^.l 1.1+v m 9.*.2+O :.F l f+1+T.^.z c q b d.c+j+w E J 7 p E N I I E G F F E J w U 5.* = ", +"= ' * -.m z w F G G F F F G E I I Z /+p+r+$+`._ i+H F N y E I G l I H y F I G F G G F F G E I J c W.1+G+S.2.c+_.a.N E z l.2+d+8.z+j A+6.$+8.t+Y.5+J.<+F.j r+6.o.$+F.F :.m F Z u+|+<+B+u+>+N d ].C+S F I G J y x.# d.8.t+c+=+h.F J =.<+i.9+$+L.o U m+L V.[+#+D+<+u.F w F '+@ i...r+(+: b.r F F E G y N E F r Y.^ r+(.u+P./.k J e.g+9 b.V M .L.z w U t+= H.@.C.Z h+J.$ 8.E.F i U.R.7+A+,+q.P.~ 9 $+G.t.P.J.* $+e.E.A+O + h+9.N 9.b.3.-+e+>.m.. $.o+Q F {.;+( 2.&+*+M s.k F F K |.f.8+[+t+G+H.< u+j+s+H.n.;._.( C+x.F D U :.S G G [.^ ] 0.z+I.C+7+^.q.f.^+w+B+C ..p.F w F.`.{+h+I.S.>+t+n+$ <+a.G m+!+& b+b m V 6++ 0.f p S.y+! *+^.y B+1.*+B+e+X.d+! .+i J U `.^+C 8.%+A G D. .Y.8.h+` h+p.D v D I E G F F E J w U 5.* = ", +"= ' * -.m z w F G G F F F G E I I y o+o+r+2 z+C.F K F F R G G J z w F F z w w w F F F F F G E I o a t+%+E+0+5 y J G F S F 1 7.m+p.J w g 8.M.L.C.+.M.'+o y w.7.B+z+c E F I E v k i+'+*.g F F 8.f.h.:.F l R F F m D.:+P.;.l.}.w G J F t.[.*.m+E.F F Q a X.*.:+,+G F J :.S >.J.[+0+:+,+/.H I Z F D I F N E F J Q M.:+:+X.h S E F I Z l.'.8.E+g I F I v [.m+[.M.K t./.L.B+o+x F D E.B.y.*.x E B.z+,+:+o y v.r+,+z.>+Z i+M.B+E+:.v F o ,+'.o+{.v I.[.5 E l F S A+'.,+E+u.F y l F I k L.*.,+h N s+I.} :.E.} z+I.l.M.c.G l F F I I E v G p.V '.u+'+o F G m [.*.z+X.P.^.G y F F E.'.m+y.c.F [.M.,+*.t.Q h _.[.V e F i+0+:+s+x.F p.:+_+X.E.Z J L.'.o+M.H k.m+z+Q E D >+2 |.m+N N F S 4 ,+y.Y S.y F D G z I E G F F E J w U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G H y I F N v %.T y y z J E G F F F F F F F F F F F F F F F F F F F F F F F F F F F D F D 7.9 | q F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F G l F J L.1.P.y z w J E G F F F F F F F F F F F F F F F F F F F F F F F F F F E :.Q k t+p+B.F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F S N F F d+1+R z z w I E G F F F F F F F F F F F F F F F F F F F F F F F F F F y I F c.-+x+$+U F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F G G G G G G G G F F F S r.n+,.U w w J I E G F F F F F F F F F F F F F F F F F F F F F F F F F F F G +.8.4+H.^+A+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F G G G G G G G G R F J v z x J F J I I E G G F F F F F F F F F F F F F F F F F F F F F F F F F F Q F J J S F q :.F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G E E E E E E E E F F F F F F F F F F F F F F F F G G G G G G G G F w G F H F F ^.I E E G G F F F F F F F F F F F F F F F F F F F F F F F F F F F G E Q E F F Q G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I I I I I I I I E E E E E E E E F F F F F F F F F F F F F F F F G G G G G G G G I o l F F R z F E E G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F Q D y F l m x F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I I I I I I I I E E E E E E E E F F F F F F F F F F F F F F F F G G G G G G G G E F F U G F D y G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F D J F F F S F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G G I I F F z y E G E I w w I F F F F F F F F F F F F F F F E J w R F K F G v I y v Z F F z F F H y l z F F F E G E E E E E I I E I E F F J D w F E F G H F G q y I J y l D J F F F F F E z D w F G F F G J J E G F G J z J F F G G v I F I z F E y E F F z D J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G F F w D w F F F l y I F F F I J F F F F F F F F F F F G E I J w l F I l w x U F F G l N F J l F F F F I l H y F G G G G F F F F G E E F F E E G J F G I F E F z z J E G G F G E G E G F F G I J J I G F F F I z J G F F F F J l F F E J E G F F F E I E F F F G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G N E F I E F F w F F F E I E F F F F F F F F F F F G E I J J J J F j+E F E I w U j F F l F w N F k l G F J z I F z w E F F F E J F G I E F F J D F D Q F Z a.l K z w I I I I J z F G I J G F F I E J w J G F G J J J w y z E F F w F F E F F y v J J I E E E J w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G y G F F F G E F F F F E w w I E G G G G G G G G F G I w w w J I E+ .9 + , @ 6., *+6 l F l w F N G F F F F G J D J w F F G F F E G F F F F F F F F G v F G F F F F F F E I G F F w F G y v w F F F F J y z G F F F G E I J E F F F F E J I F F G F F G F F F F G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G F l x D F F J J R y E F F F I v G G G G G G G G G E J w w J I E F p.]+W.I F j Y /+%.B.F S H F Q F E y v y G F F F E w l Q N E F E F F E w w I E S F G x F o 6 R l z E F F F F E y F F F G F F I I F F F G J z D l z G F F G J J I w D v y E F F F F I y l y I F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G I I I G F G F F F F F z y G F J E E E E E E E E G E I I I I E E E E.& 4+l S F F ... `.F I Z F w D E F F F G G G H E E E F F J F F E I E F F F I F l l J F U.3.S F G I y l l D D F D S H z J y v I J w J F F F F F J z J w l z F F G F F F F I l N D J G F G E E E E E E E E E E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G y F E Q v F J :.c.l F y Q y G E E E E E E E E E E E G G G G G G G a W.&.H v F q D.! ^ S F x I I F y Q R w F I l R F H m E N p I R D G F w l D I F l Q F K j.g.p R l J E G F G E F z J F G Q H F F z R N I E H m G y z F G N R y F q Z J x H F w G G E D Q R z F E E E E E E E E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G F +.P.a+V t.G.S.A+z.x F G F F I E E E E E E E E I E F F F F G G F F.o.& R l c.F s+3+V.j+G y G R {.>..+_.1 Z G w v R Y 2.7+m.e+{.S G F 9.l.(+&+m.c F <.3 $+l+!.T.@.y.f+x F I K j+*+q+3 x.w.C+[+'+I y w F F c.2 7+9+A+v.o F G D z t.t+(.A+9+,+K E w N a.*.[+G+w.p E E E E E E E E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I F K /.W. .m+,.t + F+F H v G n J E l J F y v w E J J I E E G F F F =.R.|+E y F y 5+l+B+N E z ^._+P '+S.9+^+M.v H j w+V._+S.~.+ G+y I q b+9+B+Y v+/ f K F.6 !.) V 7.i+j+H E J S p (.f.] P.m+0+0.% %+y l l c.-+d.'._+` R.G+:.R F p.;+@.,+>.8 6+O.F Q f ,.0.m+;.%.e+j F E I Z F N F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I Z F Z 5.2+u+%+D.j.).S I I G E I F G G F F G E J J I I E E G G F I r f.$ J Q :.X.3.0.Z F l E 6 1.q+p F e.^ 1.A.F } f.B+Z K F 8.` l S n.p+d F E g #.#+r.l K 8 )+G.I w w J w l l y d 3+~ l.x F f+)+< q.F :.*+n+6 l z >+B o.s+Z w .+% A.F F Y }+e R x 6+-.n F <.L J.1 H E F F F N E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I x F D B 6+*.9.F C.r.F H l y z H n F I <.Q N N F I I I E E G G G y q 4+l+$.x+f.8+q.n :.l F o ).6+{.x E G [.u *.w v.t ..<.F Z k 9.F j+%.T k x j+t.#+1+g F N _ 6+<.I y N H l J G G | j.5+m J E l C+|+l.v 1 6+P Q n F z c /+0.U S P Z.'+q l n F :.G k.H.7+G x F A.)+@.J I z D z E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I E k t.T $.N.E z G F I I G v m 9+# 9 + ++*.J F J E E E E E E E E F h.= 4+S :.,+@ ..q F x k E.^ d.O.y I F y.O &+q ^.0 ]+ _.F F E k 0+9 ` S F F H U.3+z.D v )+g.9.y J E G E w v S 3 /+$+v S :.J 0+# 8.F %+p+(+p E J k E.^+8 +.I p.+ K.#.q.F p q F #.^+7 F I K d )+^+F F y R z F J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I w Q k c+#.q.F D R w R I F l l t+f.p+% 3+'.J F D E E E E E E E E G +3.Z.w G m 8+, t+k o F F 3+$ t )+! 6.& ! G+I H F (.^+9 > P.x J [.!.%.- $ o.* J.y+o+p F 3+3.p F E E F E N l F h R.@+R l v F I.* C+F s+4+[+m F G m i ~ &.O.F y ^. .O L 4.v F ^ ' [ p+o.J.o.Z.=+y w F E G w D F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I y J J #+y+p.F F G z I E I Z E J y F F y N N y E G G G E E I I I <.f+!./+:.S n p.++v++.F z 6 1+;+j I Z E I F q I E H o :.C+2+J.4.F L.p+w+p F F F U F G z F n+2+A y H v I J l y F h.< Y.y z v F z+J.7.m s.g.b+F 9.Q y e 8 : }.F :.F F b T.u ] E D 8+!.p.F F F k F a.G k v G I H F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I z w Z T n+d I J R y G F E x F G J N l I G F F F F G G E E I I J F ^.j.+ J w F | B ~+#+a.F j t+_ 4 F z l G ^.K F O.j J F o %+6.`.m w.].Y.n v q I F y I <.c.$.|+r.F w D G F J Q :.g !.,.C.F F m L l+B.Q +~ 3.a.F F E X.o.c+^.F w.<.:.y A T 0 {.D %+!.B.z r.D F w F F R N z I R F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I R z n W %.q.y z N F I p J F E I E F F G E J J F F F G E E I J J K i % o.K w k F v.J.2+r I }.1 3+).Q z N E [.r K h+b+i m l {.H.2 F U *+3+[.F G Z +.Y E.E E -+* 7 K +. +o E F F F 4.! / g l Q a !.T.j+F t.@.x+8+F D +.F+1+d F j+1.u+z D O.] v+^.F S K./ 9.E J F o+1 x F E H G l E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F E G F F F I w y F =.h+W.# -.k.E y z w J E G F F F F F F F F F F F F G E I J w w q.c+$ ' *+e.F F R a+; D+*+J K %+,.T <+c+(.M. +R z+6.n+..c+D+P.>+<.J G.0.{ }+g+c+2.3 >+R F 3 v+)+<+r+d U w G E z h.p+O X ..-+j.m.r F F l q h+3.Q.`.C ^ 1 S l E.1+J.M 5+C T.B.k F J 3 M D+-+F+2.>.r.U z F E w J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F E G F F F I w y y Q =.A.D.b 9.k w w J I E G F F F F F F F F F F F F G G E I J w q c Y |.h K v R G G.A.g p.I F k k.3 1 3 c r.R F }.w.{.d u.4 K F D F v +6 4 {.z.a.z S R F k u.b 3 O.S E E J z l b 3+-+s.B.3 1 n y F D E F j+i+u.1 f G.E I l F 6 i+3 w.B.g v F R F <.a w.c p.p.^.x y F F J w I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F E J w y G F I G F w <.I I E G G F F F F F F F F F F F F F F G E I I J D G F F y H v z v z G J <.J E l F w N H y G F G v S w S Z S F y z w F F J R Q D l F H H G F v I N E F G w J E I i Z.b.U :.E F v E w <.Q G F v z Z w F F R k I N F y N y F F E y N F E D E H x F F F F E w J G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G F F F F E I J G G z v y G G w G G G F F F F F F F F F F F F F F F F G G E I I J I w D v D E F z G F H F F G H F J y z G F w H E v z F F E E D I D y G G y z F l y z G E F z N w J z v D E F G d [ 5+F I k D G y J G G v J G I F w J l I F H J S l G F l <.S w H G J y F F D z G E J w J G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G F F F F G E E I E I J J I E I F F F F F F F F F F F F F F F F F F F F G G E E F J v D G F F w I I E H F D G F w w w I F F G J G v l F E F F E F G J w w J I E F G G F z G F E G G I w I I v Z 0+o.-+ +R x Z G Q F F G G F J F I w F G F G S G I E E I E F F G F F w D G F F J J w w J G F F I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F G G I E F F F G I J F F F F F F F F F F F F F F F F F F F F F F G G F F F F F F E I I I J D G w G J F F F F F F F F E E J G l F F E G G G E E G G E E D w E D w F E F F F F F J <.9.{+1.#.&+i F J F y S v G l G F D I E G G G w D G F F E z z E G I I F F F E I G F F F G G F F G J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F E I E E G F F F F F F G G G F F F F F F F F F F F F F F F F I G F I y y E F J F G I I E F z G F G E I E E I F F E F J F I F I E E G G E E G J J G F F G G F J E G G G I N Z U F G U N w Z J F G E F F F E E G F l z F F F z J E E w y y w J y w F F I y w E F F F F G F G E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F G G G F F G F F F F F F G G G E F F F F F F F F F F F F F F F F F F F G G E J w F F I F z l I F F G I E F F G J J I v E F E N I G E G F E J J E G F E I F I w G G F F E E F F E F F R H F F Q G y G E F J y l F v F E G I y G l J I G F F F F F F w z E F F F E J E G E I E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F I F E I F J z G z J F F z w F F F F F F F F F F E F F w F F F G J F F I l F E w F F F F F F F F F F F F F F F F F F G E I J w w l l D y w J J I G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F R E F F F E I F G z N y E E J E F F F F F F F F w w y z I v S F F N F F F l v F F F F F F F F F F F F F F F F F F F G G E I J w D y z w J I I E G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G F F F F F F F F G G F F F F F F F F F F F F F F l F F l J F E y G z w F F F J N F F F F F F F F G F G F E G J E F v G D E w R F F F F F F F F F F F F F F F F F F F F G E I I J w w J I E E G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G G G G G G G G G E E G G F F F F F F F F F F F F F F w R z F I E I E F w S z F z E E E E E E E E I z w F N E F o G I F j G z F J G G G G G G G G F F F F F F F F F F F G G E I I I I E G G F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G I I I I I I I I I I E G G F F F F F F F F F F F J N l G G Z ^.S w l S R N Z <.I w w w w w w w w F F F I G Q S F v E Q k F y E N G G G G G G G G F F F F F F F F F F F F G G E E G G F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G J J J J J J J J J I I E G F F F F F F F F F F F F G E Q e C+)++ u /+p+++6.O =+t.w w w w w w w w H E v R Z #+p+I.l N v F F R G N E E E E E E E E F F F F F F F F F F F F F F G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G J J J J J J J J w J I E G G F F F F F F F F F F S z F I E +.*+J./.k F F K G+b+O.I I I I I I I I t.F F E E X.-+a G N E j+X.N z F E E E E E E E E F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G G G G G G G w w w w w w w w w w J I E G F F F F F F F F F F G F J S F U &+; Y F F Z F F.l.:.E E E E E E E E F H N F Q :.D I F Z G h+g.c.S G E E E E E E E E F F F F F F F F F F F F F F F F F F F F G G G E G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J z H F N G H H E D F I z F F F Q F I z N I G F J G F G E z R [+4+} m H F G S J D y F o F Q <.F S Q E J G n D v J :.F p ;+! C.F v v G F y v I F J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J J F A F A.(.*+<+%+G.F F y y w F z F F J F F G I E F G G w R [+t >.F G o 9+Z E F +.9+).<+h+9.=.|.-+M o+C.t+B $+k.F 2 ).x++ #+<+#++.U w I I F F w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J G I 9.'.k+u+s.8.d.[+U F y w x E F F I J w D D F I G G F J R &+9 } y D | d+x.G J C.X.# . _.E S i+i.n.b G v.{ 3+Y F =.w.] # v.k.4.j x G F G F G w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J I J a.1.] U G y ^ f.[.H N F l I w F F J v F J x w G G F J R 0.l+|+J.u 1.J.g F Q F E _.+ t+k G B+F+=.w F F u+9 '.H F J Q.@ +.F E E F F E J G F E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J F N 7.l+o+F R v p.R.@.z y F J D F n Z F E F F z w E G F J R 5+~+'.w I c O 4.m F G F x 5++ _+B+-.a F Q t.E s+9 L.F F Q Q.# ^.y F F F E w J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J ^.F ( y+w.C. +x S.H.B N I J E v x 8+, + + 6+[.F J E E G z Q 5+l+m+E N r a+l z :.I k E F f.3.2+6 F E D v H '+p+D.w Q Q W [ p y E J E G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J D F ^++ &.$.X { Q./+a+j D I F F <.C+0 .v+n.1 I I G I I y S 5+9 7 I I I y R Q v F x F D 3 - X +.z y F F y P.~+X.F F I <+$ S y I F F F F F E E E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F G G F F E J J p Q.d.e.N F F k F w F F z l y F m N F y v F D E G I J l x 5+[ X.G m F :.K h 9.D U x 3 ^ a+)+M C.I D Z F [.9 w.I l H 8 ' K H F G w D z E G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I :.E r+6+>.F F l G x E J D J F I G G G G G G G G G F I y F Z ~.* |.F w I Q q.,.A.G F p.Q.,++.M./+.+G F x F _.6.X.F w E B + j+J F l F F J z F F w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I D F k.{ 5.3 D J F >.X.R G p <.G G G G G G G G G z J E F w F.*+~+i+<.F I A h+^+b y A.n.F+z I +.-.! A+i F E *+o.;.I F ^.*+l+o++.c.f+j R D z G F E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I w w J f+#+_ 5.#.D+P.m F F F G N G G G G G G G G G E G w r.I.$.) $.n+( v+~ f.1+f+} ].+ y+G.N V 1.- R.(+N.>.4+ i.M.F I A {+p+,._.f E.D J y w E E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I G m J I G.z.O.q U U F z ^.K F G G G G G G G G G l l w F E q +r m a.}.b c.i +F m F.r.e.D w R G.r.N.m F r.d x.a.j z Z G U C.a.+.N E F w N l I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I Z G E G F G F m J q K F F G G G G G G G G G G G E F J y l R S v U k G l J F F l l I F R <.:.F y w w R H l F G E E F F G U Q o F F E D R H z F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I F G D U H J y z :.G G <.n J F I G G G G G G G G I F E D z F F F E G F l G :.z w F x :.^.F F F <.F F v N F S U I v K l D F I N H z D v D I F E w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I F x R F G <.N G F F N H J F w F G G G G G G G G F F F J y y l S J S :.w G D w w Z F F z w k S F S R y w G z I F F J F Q H G y l J J E F F G w y F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F G G F F F G E I F H F I R y E N I F l z F F J F G G G G G G G G G J E F I w I E Q F F z l <.N G v F E a.F F w H F E E J H G E x S I G E F N G S y w E E w y I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"= ' * -.m z w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I y U 5.* = ", +"' & = s F.j C.>+}.A >+=.=.a.r.A j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j+j t.j C.j+r.j+j F.Q.% @ ", +"= & ; ].|.7 |.|.E+Y /.'.|.|.|.|.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.[.V o+V o+Y /.E+l.0 - Z.", +"% & * $.y.:+s+E+[.V Y |.D.D.|.'.Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y L.2 B.'./.D.'.s+I.$.* t ", +"@ ' * {+[.V l.i+*.E+'.l.D.D.l.|.Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y |.L.l.*.o+l./.:+7.{+$ # ", +"; ' % y+:+,+M.Y /.Y *.o+o+*.E+Y o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+o+[.V o+o+Y D.D.Y s+d.H.' ", +"& O % n+s+M.M.o+} B.D.|.'.|.D.7 l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.l.2 B.B.s.D.s+>.%+_+&.H.Z.", +"- O ; #.o+/.|.B.w w z z z w J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J z v H v c.3 *.2 >.%.% ~+", +"> * $ %.s+m+X.'.D z I F F F F E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F J I F <.A._+'.s+].]+& ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+K+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+J+G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F E E E E E E E E E E E E E E E E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G E E E E E E E E G G G G G G G G E E E E E E E E G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+E E E E E E E E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F E E E E E E E E E E E E E E E E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G E E E E E E E E G G G G G G G G E E E E E E E E G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+E E E E E E E E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G G G G G G G F F F F F F F F E E E E E E E E E E E E E E E E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G E E E E E E E E G G G G G G G G E E E E E E E E G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G G G L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+M+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+L+E E E E E E E E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F N+O+P+Q+R+S+T+R+U+U+U+V+W+X+X+Y+X+Z+`+ @.@.@+@`+@@#@@@$@W+%@W+&@W+*@=@-@;@>@X+,@%@*@W+W+'@)@!@~@!@;@'@{@!@!@]@;@^@'@/@'@(@_@:@W+;@-@W+=@W+*@%@X+W++@<@[@W+W+-@}@=@W+X+%@%@W+}@;@,@|@>@-@1@2@3@O+4@3@5@F F 6@7@8@9@7@0@a@G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G O+O+b@N+c@d@e@f@g@f@h@H+H+i@j@k@i@J+J+l@H+m@m@H+l@J+J+h@k@i@l@H+h@H+H+h@n@H+m@H+m@H+o@p@p@I+L+o@I+p@q@I+r@I+I+s@I+s@t@L+I+I+I+L+L+q@u@q@t@I+L+t@L+o@H+H+H+m@J+h@n@J+H+H+h@m@l@k@H+H+J+H+i@l@l@H+H+H+h@n@J+H+h@H+H+J+v@P+v@w@P+h@h@i@m@H+x@y@H+H+z@A@G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F N+N+N+N+O+G J+h@o@L+u@u@u@u@L+o@B@C@D@E@D@F@'@F@G@H@H@I@W+J@J@J@;@K@L@M@!@/@L@;@N@N@;@{@;@{@L@O@P@Q@f@e@R@S@f@R@R@f@B@f@T@S@S@B@U@;@U@N@V@W@/@!@;@K@/@L@L@X+X@Y@N@K@/@/@L@L@;@L@;@K@Z@K@]@'@'@L@Q+w@`@N+E F H N I #7@a@0@7@0@.#G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G O+O+b@N++#c@@#B@g@B@`@##$#$#N+%#&#$#$#*#N+O+O+N+*#$#&#*#N+N+##4@4@$#*###*#%###4@4@3@H+H+H+J+=#=#J+H+j@J+m@h@l@l@h@j@H+J+m@k@i@j@h@J+J+H+j@i@l@H+H+-#;#4@*#b@N+%#$#N+`@*#*#N+N+N+*#;#$#b@%#O+N+b@*#>#N+3@N+%#4@$#$#$#4@O+O+##,#'#w@h@H+H+l@k@A@)#)#H+G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F N+N+N+N+O+G J+h@o@!#~#I+I+{#]#^#.#9@F /#F (#_#(#N+:#<#:#[#N+[#[#N+%#N+;#%###O+O+N+N+%#3@O+##N+N+}#|#}#a@1#2#a@3#4#4#3#3#3#3#a@a@5#[#N+N+N+(#6#F F F F [#N+N+N+N+z w I F F G I F F F E F H E G E y@H+7#H+8#H+A@7@7@9#0#a#7@8@0@.#G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G O+O+3@O+f@+#@#f@@#f@B@f@g@b#f@f@R@R@e@B@S@T@T@S@B@e@e@e@f@f@B@R@f@@#f@R@f@@#f@b#f@f@c@2@d@f@f@f@f@c@c@c#f@2@c@f@d@c@d@+#c@c@2@c@+#f@c#d@f@f@+#d@f@f@f@f@e@e@f@B@@#B@B@f@f@R@f@B@f@e@f@f@B@f@B@f@@#b#e@b#e@f@f@f@B@R@f@+#c@d@+#2@%#%#O+%#F w E z J+H+G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F B@B@N+N+O+G h@y@d#e#f#f#g#h#i#i#j#k#l#m#j#n#o#p#q#r#s#t#u#u#v#t#w#x#y#z#A#B#C#z#A#y#z#C#C#y#C#A#m#D#E#F#l#3#D#G#F#F#j#l#j#l#j#j#H#I#J#p#K#|#L#M#N#O#K#L#O#v#s#u#P#A#Q#R#S#T#B#P#z#B#C#P#U#C#A#T#V#^#^#V#W#X#Y#Z#`#Z#0#9#a# $7@7@G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G O+O+O+3@f@+#b#f@f@@#B@D@.$B@+$@$#$D@$$%$&$*$*$&$%$$$C@B@E@=$B@-$C@B@B@-$C@;$*$>$,$'$D@-$-$)$#$B@)$)$B@!$*$;$#$B@>$#$)$*$*$B@-$C@~${$'$!$B@#$B@]$'$D@%$B@*$%$^$@$%$B@*$B@/$D@($D@_$#$,$:$#$$$,$<$#$*$B@#$[$_$,$*$B@,$!@W@}$'@B@B@T@P@P@%#N+O+N+O+F J G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F B@B@B@O+O+G y@y@f#f#|$1$2$3$4$5$6$7$8$9$0$l#M#M#a$b$c$d$e$q#s#f$g$h$i$j$e$e$K#k$O#l$m$n$n$K#n$o$p$q$r$q$q$s$t$u$v$w$w$x$y$z$A$B$O#o$K#m$C$n$i$e$D$o$K#a$O#E$O#F$a$a$G$o$H$K#C$m$e$I$J$m$n$j$K$o$L$M$N$O$P${#Q$R$S$Z#T$7#y@=#F F G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G O+O+N+*#+#c@g@@#@#U$V$W$X$'@Y$Z$Y$`$ %Z$.%W$W$.%Z$ %+% %!@Y$'@@%`$#%`$ %!@Y$`$`$`$W$$%%%F@&%*%%%=%$%'@-%'@&%F@;%'@;@%%F@>%,%=%'@F@%%F@'%$%>%F@F@;@'@#%)%#%'@!@Y$'@!%+%~%{%'@Y$'@]%`$^%~%'@/%Z$+%)% %(%'@+%W$!@)%)%(%!@W+I@!@_%!@:%<%[%B@@#}%B@[#N+<#G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F *$*$B@+#O+G y@`#|%1%2%3%4%5%6%7%8%9%0%a%b%c%d%e%f%g%h%i%j%k%l%m%n%o%p%q%e%r%s%t%u%v%w%H$H$x%y%z%A%B%C%D%E%F%G%a%H%I%c%J%K%0%L%M%N%O%P%Q%t%R%S%T%M#U%f%V%W%X%O%Y%Z%`%h% &.&+&P%@&#&$&X%%&&&*&=&-&;&>&,&'&)&!&~&{&]&X#^&/&H+n@J+j@G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G O+O+N+$#+#c@(&P@_&:&<&<&[&}&|&1&2&3&4&5&6&7&7&6&5&4&8&9&|&0&}&a&<&b&c&d&e&f&g&h&<&i&j&k&l&m&n&o&p&q&l&r&s&t&u&v&w&x&y&z&A&B&C&D&E&F&G&H&I&J&K&x&L&M&N&b&h&O&P&Q&R&S&8&T&U&V&f&0&W&N&X&Y&Z&R&0&`& *.*T&f&J@|&+*@*b&N&#*$*%*&***=*-*;*F@#$>*,*'*)*f@e@G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F *$*$*$+#O+G y@!*~*{*]*^*/*(*_*:*9$<*[*}*|*1*2*a$3*4*5*6*7*8*9*0*a*b*c*d*e*e*f*g*h*i*f*j*j*k*l*m*n*o*e*p*q*n*r*s*t*p*u*v*w*x*y*z*A*B*A*C*a*D*m*v*E*F*G*c*H*I*J*J*K*L*M*N*O*K*E*P*Q*R*S*T*U*e*2*J$V*W*X*Y*Z*`* =.=+=@=#=/&I+i@J+$=G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G O+O+O+&#c@c@g@R@%=&=*===-=;=>=,='=)=!=~={=`+`+{=~=!=]=^=`+,=/=*=]=(=_=>=+@;=:=)=<=[=}=W+|=1=2=3=4=;=,=;=5=6=3=2=/=W+>=7=8=3=9=0=a=,=b=c=2=d=e=`+$@|=f=g=h=i=;=W+j=~=h=]=k=l=|=+@m=n===o=$@>=|=p=-=h=f=q=W+/=i=!=!=r=s=t=$@u=v=w=x=y=F@;@z=A='$)$e@e@G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F !@*$*$+#O+G `#!*B=C=D=E=F=G=:*H=I=J=K=L=M=N=O=N=P=Q=R=S=T=U=V=W=X=Y=Z=`= -.-+-@-Y=#-$-%-&-B*#-*-D*=-p*d*1*S*--;->-Q*k*k*,-g*'-)-!-!-~-{-4*]-l*Q*2*^-/-(-@-_-:-<-_*[-}-|-]-1-2-A*:-4*3-Z=4-:-5-<-6-7-8-9-0-a-b-c-d- =e-f-!#s@I+,#G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G G G G G G O+O+%#`@c@+#R@f@(&g-h-i-j-k-l-m-n-o-p-h-q-r-r-q-h-p-o-s-t-m-k-u-p-v-w-x-y-z-A-B-C-D-q=l=E-F-G-H-I-J-K-L-k===M-N-O-j=l=P-Q-G-M-R-E-j=S-]=T-U-V-O-E-W-X-Y-Y-Z-`- ;t-.;X-h-+;@;r-#;$;X-v-%;&;r-@;*;=;-;i-r-l-;;>;u-o--;,;';);!;~;{;w=];^;'@/;(;%$B@D@D@G G G G G G G G F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F !@*$*$c@3@J Y#_;:;<;[;};|;1;2;H$3;4;5;6;7;8;9;0;a;b;c;d;e;f;g;h;i;j;k;l;m;n;o;p;q;r;o;s;t;u;v;w;x;y;z;A;B;C;D;D;E;F;G;F;H;I;J;K;L;5$L;M;N;O;P;Q;R;z;S;T;U;V;W;s;X;Y;Z;`; >.>+>@>#>$>`;%>&>*>=>->;>>>,>'>)>!>~>{>]>^>/>(>_>s@I+Q+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G F F F F N+N+$#O+f@2@B@e@:><>[>}>|>1>`+2>3>4>5>6>7>2>2>7>6>5>8>9>t-W+0>+;a>b>c>d>e>f>g>a>h>i>q=/=R-j>k>T-l>{=$@m>_=k>f=n>o>>=L-p>q>)=[=r>;=s>p>t>M-u>v>/=;=w>h>$;}>x>m-#;y>g>.;z>A>`-&;B>|>b>a>i>C>D>E>A>F>b>G>H>D> ;Z-I>J>K>L>M>N>O>P>Q>R>S>T>'@U>V>+$B@&$*$F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F *$*$*$c@3@J W>_;|$X>Y>Z>`>j% ,:*->.,+,@,#,$,%,&,*,=,-,=,;,>,,,',),!,~,{,],^,/,~,!,(,_,:,<,[,~,},|,[,1,2,/,~,!,_,|,3,4,5,6,(,7,8,9,h#0,a,},b,c,d,e,3,{,),f,g,h,i,j,k,(,f,l,m,&,<,m,a,b,n,o,5,p,q,r,s,t,u,v,w,x,y,z,A,f#B,C,m@J+,#F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G F F F F N+N+*#N++#1@R@R@}%D,E,F,G,H,I,J,K,L,M,N,O,P,P,O,N,M,Q,K,R,S,T,G,U,V,W,X,I,Y,Z,`,M, '.'|&V&6&c&+'@'#'}&P&$'+*%'&'*'}&.'='-'%';'>'#'f&,''')'!'~'{'1&*']'^'G,/'S,W+('_'^':'<'['7&}'|'Z,1'Q,X,S,2'3'L,4'_'X,;@I,5'G,6' '7'8'9'0'a'b'c'd'e'$%f'g'h'B@'*B@F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F *$*$B@c@%#I 8#T$i'j'k'l'm'n'o'R;p'q'r's't'u'v'w'x'y'z'A'B'C'C'D'E'F'G'H'I'J'K'G'L'L'M'i#B=N'O'E'P'Q'R'S'R'T'U'V'W'1$X'Y'T'Z'T'`'j' ).)+)O'E'k'@)#)$)%)1%&)O'.)*)=)-)L';)>),)')')-)))F'))N'=)J'!)~){)])^)/)()_):)<)i'[)})7#J+H+i@F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G F F F F N+N+3@N++#1@Q@Q@|)1)2)3)3)4)5)6)7)8)9)0)4)6)6)4)0)9)8)a)b)6)c)d)9)a)e)b)f)g)h)i)d)e)j)k)l)m)n)o)p)q)r)k)s)n)t)u)j)k)r)v)w)x)y)q)k)j)s)z)o)A)B)C)l)q)D)E)F)G)c)g)H)D)E)I)i)J)K)L)d)F)0)8)7)f)g)8)i)D)d)M)g)N)2)E)i)D)O)P)Q)R)S)T)U)V)W))$;$X)Y)e@Z)B@F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F e@B@B@O+%#E y@8#]#`)-)W' !.!+!@>@!j'#!$!W#i'%!&!*!=!-!;!})})B,C,>!,!'!)!!!)!~!{!]!^!/!T$Z#(!_!:!=!*!e#{#^&*!!c!~!d!T$e!^!f!^!~!!!(!d!g!h!i!_)v'j!i#|%%!Y#(!7#x@H+F E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G F F F F N+N+3@O++#2@Q@Q@g@k!l!l!m!n!o!p!q!m!r!s!t!,$,$t!s!r!u!v!w!e@x!y!z!z!A!A!A!B!C!D!E!E!#$F!G!m!s!s!l!H!o!o!I!J!K!L!p!D@p!M!L!N!O!q!%$%$P!Q!Q!L!t!R!p!S!O!Q!H!G!p!p!G!I!O!s!I!,$B@R!l!O!O!Q!q!,$D@T!U!r!I!G!p!p!G!m!U!N!V!W!W!X!_%Y!Z!`!'@k!R@B@R@5#[#[#F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F B@B@[#O+O+G h@y@ ~#=9!.~g#:;:;h#`#!!+~~!b!Y#H+H+)#7#@~k@m@l@j@i@#~$~x@y@H+A@8#)##~%~W>x@W>A@)##~8#y@H+H+x@&~z@)#W>8#8#W>)#x@)#W>n@J+l@7#*~&~$~A@)#8#x@$~*~j@j@@~)#%~$~$~7#)#W>x@y@7#=~=~$~)#W>x@8!`).~f#]#]#`#T$d!Y#-~-~-~a#0#0#F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G F F F F N+N+*#%#+#+#@#R@b#R@;~>~,~'~N+:#)~!~~~{~]~'~'~]~{~~~[#:#:#[#^~/~)~'~{~{~{~]~)~/~)~)~:#'~(~_~:~<~[~[#}~'~~~(~}~[~~~'~}~(~|~_~(~[#[#[~1~(~}~}~(~1~1~1~^~'~:#N+N+:#^~)~{~^~~~N+N+:#~~:#~~^~'~[#[#^~)~)~^~~~N+N+[#'~]~/~N@K@<%<%2~2~Q@Q@B@3~%#N+4@&#F E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F [#[#[#N+N+G J+J+u@f-f-f-/&[)#=^&7@0#a#a#a#0#0#E F G y F 3@N+3@O+I z D D w J J z I F F J J F F I y I F E y v z F v D J E I z z I b@G F G z w F F G F F E E F I 4@4~-~0#7@7@7@0#-~7@-~4~-~7@7@-~5~H+x@z@$~W>H+W> $6~-~7@7@a#.#.#0@F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G F F F F N+N+*#3@+#f@B@@#e@B@7@0@.#8@a@a@0@.#7@7@0@8@8@0@7@7@.#0@a@a@.#7~0@7@8@0@a@a@0@0@a@7@8~_#6#6#(#_#6#F _#6#F 6#(#F F 6#6#6#6#_#(#F F (#F F _#_#(#6#6#(#0@7~9~9~7~.#.#0~0~0~9~9@a~0~8@a@7@7@a@a@a@0@0@0@0~7~.#0~9@9~.#a@+#+#+#+#c@c@N+N+N+;#F G D z H+H+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F N+N+N+N+N+F J+J+o@o@L+L+o@I+I+I+8@0@7@7@7@(#b~c~b~b~d~6#e~N+f~N+F 6#(#6#6#6#6#(#g~b~6#F 6#_#8~g~*#O+N+N+N+O+N+N+N+%#O+N+N+b@*#3@N+3@N+F y z E z F F J v v b@N+N+(#(#_#8~8~/#6#F g~c~b~(#F F (#/#w@w@N+O+E G G G I -~a@7@a@8@8@0@F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G F F F F N+N+%#3@c@c@B@e@B@f@7@7@w#h~i~h~P#0#j~k~P#0#0#P#k~j~l~m~w#7@7@w#n~m~0#7@7@0#P#h~i~h~h~w#7@7@P#n~k~m~w#P#h~i~h~P#P#P#w#0#0#P#h~i~P#w#i~i~i~h~w#7@7@7@7@w#P#P#w#0#0#0#i~w#7@0#0#7@0#P#o~n~P#w#P#h~p~q~7@7@0#P#h~h~w#7@N+N+O+3@v@,#,#j@H+l@H+h@8#y@H+H+F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F F F N+N+P+P+V+r~R+U+S+S+R+s~7@a@0@0@6#6#6#6#6#F g~F t~f~u~[#8~_#F F 6#_#/#/#6#_#_#(#_#8~/#6#N+[#:#f~:#N+:#v~N+5#w~<#N+[#[#N+[#w~f~F /#F F x~6@/#F 6#6#N+[#<#9~8@7@7@a@8@7~9~a@7@7@0@0~0~.#a@2@c@O+O+N+N+%#b~6#b~0~7~0@a@a@a@F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G F F F F N+N+N+%#2@2@e@B@f@f@y~4$z~z~!*A~!*z~z~z~!*_;_;!*z~z~a@B~t#C~f$s#B~s#f$f$t#s#a@a@a@B~D~`#4,4,4,`#D~D~Z#`#`#D~D~`#4,4,Y#T$D~Z#D~4,`#D~4,D~Z#D~4,Y#(!(!A~!*z~E~A~_;_;4$E~z~4$F~F~4$E~A~E~z~E~_;_;!*z~E~_;G~G~4$E~z~z~!*,#H~H~v@P+H+J+h@h@J+H+W>H+H+8#8#F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F J I G G F E v F G R F F H F F N E H E E y F F l G D F D E J D I l G E F G N F D F F z D I F E F y w F G z w F G G G G G G G G F F F F F F F F F F F G G E E E G E F F I I E J G G G G G G G G F F F F F G G E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F J F F E I F F J G E G F E z w F F z D G F I w G F J G I E v w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F J I E G F F F F z w G G J E G z G G G G G G G G F E I G I F I J E F F G G F G I F F F F F F F F F F F F F F F F E G F F F F G G l E Q F F R F E F F F F F F F G F F F F F F F F E E E G G F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F G E w l z G G N G D E G y F v w F E J F R F E F J z G F Z G F G F F l y F F I J E D z F G Q k J F F F F F F J G G G G G G G G F F F F F F F F F F F G G E E E I F z D G G w F G G G G G G G G G E E G F F F G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I J I F F F w I G G G F F F R w F F G E G F I z E E F F E l F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G G G F z z G I E F F G G G G G G G G F F I F F E G E Q H y E F G G F F F F F F F F F F F F F F F F F E G F F F F G E w F E F z J F H F F F F F F G G F F F F F F F F E E E G G F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F v w F F E z l H E F z J J y F F R G H F E J J N E l F K F F w S G J y I F E w Q E F F G y z I F F F Q :.x D F G G G G G G G G G F F F F F F F F F F F G G E E E I J E G J I E J G G G G G G G G J w w I G F F E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F J w E F G E F G F G I I I J y F F G D x <.R y J I F G I E F w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G E J J w w w E N y F F E J l G G G G G G G G R I E F J K l G F I w E E z w G F F F F F F F F F F F F F F F F E G F F F G G E I D v E H I E v F F F F F G G G F F F F F F F F E E E G G F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G J y y J F F G K z F G E F w k F F w J F F F z I l v F <.k H F w y D G I y F G F D z G I F l q x F F G F E I J G G G G G G G G F F F F F F F F F F F G G E E E F y G F D z F z G G G G G G G G I w z w E G E J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I w I F F w D w F J y E F w w E E D N z F F F F F I G E w J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I I I I I I I I F E F F w E F y G G G G G G G G F w Z H F G F G D Q R I F G z z F F F F F F F F F F F F F F F F G G F F F G E I F I E F G F F J F F F F G G E E G G G G G G G G E E E G G F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G I I E J l Q F G I <.Z z E F K R G E D l F G E F N F p E G x w J z z x K J F z w E F z I E G R F I v w G F F G G G G G G G G F F F F F F F F F F F G G E E E I l k <.v I E G G G G G G G G G G J w w I E w y F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I E F F I D y E H Q R D J J J I N R v I F E D R N H w F F J J E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F F F F F G w y I w N E F I G G G G G G G G y G I G F w <.Z F I y y J G F G F F F F F F F F F F F F F F F F G F F F F G I I R G I H F G l I F F G G G E E E I I I I I I I I E E E G G F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F y F F G z D J F F H G F F F R J E v F F y F J H R l J U F z w E N I Q w F F E ^.E E G F x G F :.F I G E Q Z R D G G G G G G G G F F F F F F F F F F F G G E E E x G F E F D S y G G G G G G G G F E J J I I w D F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F G z y I F F <.F F y l F G k F G E y S k y F G F F F I E J I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G I y v R F :.<.F F I D k G G G G G G G G D F F l R G I F E.D F y S y F F F F F F F F F F F F F F F F F F F F F F G E I J I F F <.I F J F G G G G E E I I J J J J J J J J E E E G G F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F E I D v w w v H F K H R z F Q G F p w N H F E H F S v F C.W., `.e.y R F y p F E F R R F J F e B ! &.Y I F J F F G G G G G G G G F F F F F F F F F F F G G E E E w F K q F F R F G G G G G G G G G I J I E E I w F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I F G v z F z m z E E l S Q z F D G G y J F I <.9.I F D N F F J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G G G I z N S <.k+6./ 2 y F F F G G G G G G G G F w Z R F q w+# )+e+c.F F F E S F F F F F F F F F F F F F F F F F F F F G E J w F O.Q F J F G H G G G G E I I I J J J J J J J J E E E G G F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F I J F l 6 ] + + W.m+D F 6 n++ + d.d F w F z F N G Z E F g { i.4.E F D m.x+` E N F F F m G F +s L 4 F S k I v G G G G G G G G F F F F F F F F F F F G G E E E F f+;+V.q.F S E G G G G G G G G I J J I G F G E F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F y F F l J F m c 1+H.+ [ Z.+ p+B ^.y J Q F G w.] n.a F F l F E z F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G F F F F E J z x.P _ } F G H G G G G G G G G G H F E S z G :.4 > G+K F R D F F F F F F F F F F F F F F F F F F F F F F G E J w ;.! (.w w v G F G G G E E I I J w w w w w w w w E E E G G F F F F F F F F F F F G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F l E G v O.V.; p.v v v H O.5.$.i z Q F G w G E z F :.Z E.=+] e.E S D t+$._+G J E Q F N G J c.F+/+p.G Q w F R y E G F I G I I w F I y F y G x D E F D w l I z F e U.8+h x F F y G F F H E F w w J v N a E y l G E F E F G Q z F F F I z F J E F F F F F F F F F F F F F F F F F F F G G E E E N.)+t Q F G /.$.!.m.G J U G C.T C n w G w F F z F F Q F w E l F F F G F Z J l E F Z I D l w F D I F y G E Q F R F R I F S R F G N @.^+5 I F F Q F z F F I G I E F z H F z R y G.- [+w E w w G G w F I D F F J F I F n F F :.G z I I I F E D y F m.8 u+y F J F l J G w G F F w F w F t.N.E D J F R E F N F G k E I E G F F F G G G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F D G F w ^.U.]+s.z J E I N.( e+F I I <.F G w F N k z F U { v+F.F <.F E S l <.F E F k F Q I F _.$.u.G l z F G E F I v w G F F I I S F l G x F G F D D N D z H R v z z F I E H F l v G G I H F y G F c n+%+x F F I F H x F F I y E J w F J z E F F F F F F F F F F F F F F F F F F F G G E E E +!+f.D v F S e. .1.~.w F H y y F R l F J Q F G z F E F w z J G l E z v D F l F l F F F I F x F <.I F Q F G E.F J F F E F J D y l ~.|+v.J F y F q G R D F G H F z z F q I F D B.& $+J F G G F I J G F J y w G F y F I l E I D F F F y E w E w z F :.R G v J I G J I G F Z v F J G x w+d+i G w I I F H E v F E N I E G F F F G G G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F E G z F F G H m+O t+l J J G /.( h.}.q F k w F J Q F N E G U s v+ +G <.R D F F H F Z G N F G H A [+#.{.I I z w F <.w D S F z K K J E N F v E N G E F v w F G k F F H F F l H F c.w G F k D G U F F F :.V 1.>.U J J v G D w J K H U F y Q G v I F F F F F F F F F F F F F F F F F F F F G G E E E G.W.u F I G F F y.t j.9.G <.U F E N F w y N J R E K y l E N F <.F y v l F w Z G w l l N w w D J I G E w K F :.F S G m D J w w F n A+3+b E l n F F F l <.v N D F l I w H K F p O.O (.z F F F E l F H E F N H w S N S F v Q F w w <.w F G N N F n D E F l D J <.F w F <.I v F F Q F A n+9 r.F k F z F x I H R E S I E G F F F G G G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G G J G G F G h o.d+n D H H 5+`.+.F E F z._+[+$+u+E.F E :.K B X e.F S z.(.0.{.F Z z F }.0.>.B+[+v+/+p.w G J H D N z.(+A+j+g y.q+$+| H F F Z F r.P.` _.h+{.E y H >+m+.+t+A k E.;.*+'.E.v.u+C+u+H Z }.B+^ # }+F+m.V y E g %+[+h+` :+l D Q F H F G F F F F F F F F F F F F F F F F F F F G G E E E >+R.~+E G J v N a.j.[ 5 o >+[.U.M.r.v k I C.y.0.P.g+E+<.D y w j+$+(.~.@.~.r v R S X.m.I.#+B.G U D E+@.8.b z q.$+8.C.F F >+` C+*+P.j.1+h.E z I J =.(+u+e+q+R F R y F K D.7+G+(.Y.' 5+N J G G y k r+h+} e M.t+'+G+F x H I z n 5 h+9+e+y.o J x t.h.m.9+4 S <.b (+g+h.k q+*+V f r.F E+I.= . u+&+~.>+G K q+w+e+7+G+o I E G F F F G G G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F F I E I G F n ,.# F.G l A V._+v E +.v+*+V %+B f.A+o F H Z <+$.x.D x {.8+)+P.G N F 3 `.0 r+r+$+/+< d w w G D Q y c P x+(.I.I.[.].X 4 I w N f+C 8+B+m+{ /+*.F S C.y.2+{+j+F E.,+< p+0._+'+T )+M.G y v.T.l+..;.v.N.F ~.Q.C+S.7.= : t.w y F v F v F F F F F F F F F F F F F F F F F F F G G E E E p K.l+N D F F F D / + |.y }.I.%.X m I J 1 0 c+*.@.$.X c.E F o+U.g+[._+y++ {.F |.B $+V m+6+)+4 w F r.#+!.>.7+{ + 1+L.R w.v+/ M.o+$+= 1+6 w D F s.<+F+%+C+: (+Z E D n ~.-.@+[.7.W.' 5+N J G G y k 8.|+i.u+%+7.9+l+g+F E D Q $+=+8.[.~.{+n.9.F p c b.; _.J k z.P @ (.Y.S.|.p+v+Z R =.E+u p+s+'+B.^.4.g+-+z+m+*+t '+I E G F F F G G G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F G E I I I I y _. s+F E i+d+4.F E X.l+s+F F +$.( 4.F G c.P : r l y Q S.t h+F F n V.O u.F S x.( 2+g J N G F l H E z+' 9+3 m E E+R.&+9.D K &.)++.v F 4.!+i.f+F F j P n+g G v F { !.~. +y h.)+X w D k ,+' >.I z Q k ^ s N.l w 7.9+S G H v v F y F F F F F F F F F F F F F F F F F F F G G E E E r.K.J.z y F G z F W + '+F G q.s .r.<.D n.3+{.F I /.<+q G j+0 i.O.F S 8.u N.c.[+D+r F l _+$ C F c.v M.< c+F+s.y./+} j+9+].4 G y +.d+].k.F v }._ i.Q Q <.(.# :+I z '.3.&+e.G F $+O (.z F F F E l x 1+1.2 Z F F. .+ u.F H P./+A+I F R @+4+.+x E Q m++ (.F y y Y g.s 3 Z <.[+3.|.N F i ^+3+e.z F q m+p+M.R H 4.a+b I E G F F F G G G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F G G I G I l G 4 4+W v R G+2.U l I F +.D I p Q U.6+f+w I j P 8 e F G F /.' I.F Q z.3.=+l z I Z .+i.a G v J F z F R (.# A.G F D 9.2+~ h.E B.' C+F Q c.E 8.f.0+Z Z c.a+0 h k :.F &.{ ^.F w A %.3+F D F A.~+y.F m F r ~ 2+v.E I k a.F E x R l F F F F F F F F F F F F F F F F F F F F F G G E E E r 1.p+F w z y y S T $ &+K F A V.i.O.I N P |+w.l l F r.F m (+K.S.N N G z c F G U ^.I R }.c.4+{ K F y l.R.8+h.I k o G z.x+/ 9.I H w &+K.| F E L.[ _.F R w a 1.T.x U P 4+A.F N D 4 & $+J F G G F I n y+Q.K D D N M.f.$+p i / v+>+F S l f+0 ] =.F y b $ w+J l E /.u %+x F z '.!.t+E m H ,.i.}.w F E 7++ B+m J F x.C.I E G F F F G G G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F F G F E F E H F t.%.x+A j s P.F F Q E v w E D S -.l+j F G n }+&.f I S I 7 [ Y R F m.* M.n c.I A r+K.} F z l J D y <._.W.h.n o x +U.$.1 F &.* l.U F w F q+% ~.G E 9.n.X +.J F y ( < z.w F E.3.)+H N Z D./+7.<.F Q F [.+ @ G+h F w x D w F J y F F F F F F F F F F F F F F F F F F F F G G E E E j 1.l+E F G J I R V.9 z+w H =.<+L b F E 4 & H. .i F K G w @.f.y.F v G J w I x F w l F G S , d.F U E D.g.` J G v y y S.p+q+F E.G :.7+! | S N g+; 4.9.F F Y /+8 E i D+( G.F N y r.- [+w E w w G G S < : Z F G E /.@ 2.v u.&.}+r y E R y g+y+c J I 1 + 5+G F <.e+x+V Z F N v.O 8.F F z ++* Z F k F j 1.H.~+w.N I I I E G F F F G G G F F J F X.L.M._+d.$ * ", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F F F E I E F v h+ w.t.6+h I G 9.E A h.8 J.x+* - C.G z E.F+0 >+Q z F '.H.:+J I $+< _+Z G v H 9+|+h.G F l E E F Q Y.l+d G w F }.g+u u.G b.& m+y J y E '.g.k+F N m b+o.g x F y =+$.O.S w K 3.++H G I %+u ,+k F E k F i+!+O + _.>+G D y I Q G F F F F F F F F F F F F F F F F F y G F F F F F I r.6.W.k G F l w R 3. O.G k j V.v+E.Q I R r.{+; l+0 t.E Z d+3+3 v F F l l z F v e.S.2+t 3.) d.l G G Y 4+I.p F G G H w+> |.U S F E.~.6+z.F G ] . ~+f.R.!.1+9 _ N p ++] c.z G E += g+l G H F N F N j.j.k J F N 6 4+V.I f+l+b.^.F I D A 8+t u.F l p. (.E n z D.l+m+S F o V O e+F S F < )+p w G F F <.T < H./+,+z G G G G G G G G G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F F F E I E F F p.& W m.2.H G N D d ]+M a.:.F b.l+F.y I t.5.0 g F F N M.~+*.I F h+* ~.y I J p u+%.q.G F z l k N l (+u 5 F w <.:.^ 3. +z F+ ,+F F Z F I.' g+S F +.-+8 =.N F o #.o.p E F D p+' w G Q X.R.o+I z F G Q K F 2 &.. r+S E D F y F l F F F F F F F F F F F F F F F F G F F w y z D R =.~+o.w K Z G F p.x+K.p F y q W =+i F w m G y o v+* U.S <.5.1.e.F :.:.G I G n C+3.(+9.R D ; d.E Z <.3 1.S.F w S Z R z+O e+k J v I [+!+i+U v 0.# e.<.J F I x x S G.y+8 O.v y z a ! C+F F k G l G Z $.( :.<.k F Y + `.w e ].C a.G J J v d+j.h.Q E L.# h+E G D B+t E+E G F p.9 I.N G w )+6.U F D l }.G G v T.i.0 d G G G G G G G G G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F F F E I E F F A W.Z. .2 I D G D %.& =.G F j+Q.4+=.R w q V.( N.R k S E+$ 8.F G 2 3.[+N w F i -./+| v J J F G w F h+9 u+z F y F.++V.=.F m+. .E.F I y n.u z.F H A B $.x.<.R E s 2+}.n <.K < /+l H K } p+~.G D K D z.D I E.u.~ Q.n F H F E F v F F F F F F F F F F F F F F F F G F E J I F G z U % f.F E F F G.T.W.m+F J k }.;+B h.F l B.l F =.C.$.#.Q G 7+[ ~.F R G F p z +.|+*+C.w E =.* {+y F :.1 ! w+G w w w F A.K.;+q F v :.M i.f+E z [.]+s+I F v F w F E }.}+K.A.F E I E++ F+Q F R G D F H /+3.i E E F w+' s.I q -.u Y F S l e W.#+E.S F k.@ [+F R N X.9 '.N c.Q s.- '+S Q k X 6+i I Z l q t.Q y r.A+[ X.G G G G G G G G G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F F F E I E F E n B + {+>+J I Z v o.W.:.v Z D.8 x+b G F i P {+e F F N |.J.@.I F f .%.p.D J A.-.i.s.x F G E G v w [+O b.C.v y @.^+0+c.F c.^ ! D.m k 5 : b+Z Q G j M !+f+F F z {+2+e F F >+o.f.k F D 6 ++=+O.Z 4 s.)+} U F {.$ (.H F x F J E G F F F F F F F F F F F F F F F F G G E E F F I H j+! /+p v Q i u+6+M p I S w f+Q.0 6 y R J.u+k F | ] 5.m F h { d.f m z +/.=.u.Z.G+S H N.8.4+~ Q F c./.K.$+m I F D l q.}+%.3 Q v 1 ^ g.Y J F A 0 { +y l D | L.p v %+{+t+m N e.b+J.*+9.F G E S l U t K.Y l k } 2+j.x.y U 7.^+@. +F n (.!+_+D F H X.; @+Q F G _+Z.%+R F H _+t I.w F R C - %+l i A.d.#+H N y *+^+g G G G G G G G G G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F F F E I E F w w 1 f.8+Q F E E E l.u X &+a+_+T & Q.q.9.Y.!.' -+G.p s+v+ ( :+R F a X #.W &+'+,.Z.k+6 R F J F F I &+@ 2+b.C T n.q+U I z E a Y.3+T.0.=+b.f+F I }.#+1.!.P h.E.U.& ~+5+h g C+~+> @+=.z }.$+8 k+B ,+G.4+%.M .+] a+h F E S F J D F F F F F F F F F F F F F F F F F F F G I J D K C.F+= O b.b.8+P ] A.q F D p <.5+W.; &+x.k Z.1+T c+C #+w.R w H L.F+X b.U.2.>.E.p 7+W.M k+>._+3.!.7+:.| L ) 3.~.^.F Q J z 5 &.d+`.0.q+}+t ] i+c.F 6 P D+n.).a+I.4.I F j+T $.d+}+s+I.; ^+u+e.l E v F D Z.O 2+b+`.s 9+O.G F J q ` ].k+k+}+v+[.k G w B.i.[ %.t+^.k.1+; y+M.n 4 .) ( E+t.F h.n+3+..8.c n.x+2.*+b.d+o+E.G G G G G G G G G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F F F E I E F F I F '.e F z F F y D h.2 } } K p s.v.y F 1 z.w.h.y F =.5 Y 6 O.F w k w.6 N.b q o D.3 E.F E S D H Q h+/+_.v.l.A.z.p F I D z F O.w.A.d w.A F R I v a i+w.h.y F B.h.5 u.l v 4.4 | 5 E F v r } '.3 o E h.m+q.v.*.m w I z D F F D G F F F F F F F F F F F F F F F F E F F E E z k E.f+| A.k.3 i+p.a.U I Z N E F B.v.u.i+Z F 4 z.g 7 } +F w y w Q {.z.4.Y p.k F J j h 4.| c G N.6 1 p ^.A.} | a D N G R I F z.1 4 a a.9.w.'.j D F G j B.w.B.c U o G Q F C.c z.w.g q z.i+g Q F z Q w k 3+M M.{.i+%+K R D H v F z s.1 z.b v.F H H F 9.A.3 z. +F <.L.{.A.x.F t.4 6 A.a.F E y h.1 4.q.z h X.s.d E+w.Q G G G G G G G G G G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F F F E I E F F S I G F y k I l F N I F F I K K z N k H m F I G N l F F J H F Z S F F z D n F G v w z w I w F E v C+)+1 v v F F F v <.E l F R y K D G F z k F Z F F v E E N I J D S F E Q v l R z F F J G N F F n F z D J G F F R z E J F I G F F F F F F F F F F F F F F F F w G F E E F G z D F w R F G D I F I G E F y U F z v F I N ^.F I F J I :.H D F H H F Z I F Q l F p F I p v 9.F v E F w F l Q F z G Z x F l w :.:.k F E w F D j <.k F F <.G E o J q G H Q F J D G I v N F G w y I ^.)+ .x.H F N F F E F E G I z F Q S F z F x E F F k y y U R F F F S D <.R F I E n k F I J l :.E I F Q D F F R I G G G G G G G G G F F J F X.L.M.>._ % ]+", +"= - - %.%+M.|.M.z I F F G G F F F F F F F F F F F F F F F F F F G F F F E I E F I F :.F K I F J F l G G D l q F F I F v F G G N v w F J k F I N G F x G Q F F D N F F v D F w v G H ).& u.J H S x y J Z G D l F G I k F y S F J F D v z F G H F z E F R <.F z H F <.F l N F J G I I w F H F Q n G k J F H D F F F F F F F F F F F F F F F F F F G F G y N D J J I F F v F F F z F k F N l I F Z I J Q I E F H E I G I F G N w I R F F E v J G y F F Z E w G F F l k F z K F G v v J F l y F D F F y v F v G S F R G w E H Z I l F F w Q E y U E w F E J N w G y v 3.d.w H N F m J N I G R I I U F U F j J F Z F w F G J E F G w l w J J w N F :.G F F y E G I w D U F Z E y z x G G G G G G G G G F F J F X.L.M.>._ % ]+", +"* ' ' {+:+m+L.o+J J I E G G G E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F G I w z z m B l+P.y E F I E E E G G G F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G E G F F F G z v O.t )+i w l I G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F G F F v Y o+2 S.d.$ - ", +"* ' ' {+:+[.L.*.I I E G F F F G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G I w E.m+n+l+-.y.h H z w w w w J J J F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F l l l D y l R x i.x+&..+s.k F R F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F J G F z D.o+l._+d.$ - ", +"= ' ' #.%+[.D.o+w J I E E E E E G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G E G G G G I J w F t.m F E w F F G G G G G F F F G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F F F F F F E J R F F <.D F D D G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G G F G F F v E+%+,+7.{+]+- ", +"= ' & #.%+[.|.X.I E G F F F F G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G E E F l F I c.k F v D D D D y y y y F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I w y y w w w z z D S D G w x F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F I I F G D B.|.2 7.{+]+- ", +"- * & {+:+M.|.o+y z z w J J w w J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J w w w w Z y F J y G E N G G F F F F F F J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J F G I I E G G G F G w z w F G D J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J J I E G w H D.*.Y _+{+]+- ", +"> H.' #.%+X.|.o+E G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G I S k w w D F E E E E G G G G F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F G I I G F F G G Z I F v Q F I F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F F E D 7 s+7.%+].$ - ", +"+ ) * $.%+X.'.*.D y z w w w z z w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w z z z z w w J F z E F I z y R I I I E E G G G w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w F E E E F F F E G x J F y :.J G w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w w E E J D l i+L./.y.D+; * ", +"+ ) ' {+:+X.'.*.7 7 B.2 2 2 2 B.2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 B.B.B.2 s.} s.*.A.A.%+'.p.l.D.D.D.L.L.7 7 B.2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 L.L.D.7 2 2 7 D.D.u.2 M.v.i+|.D.2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 2 B.B.L.7 k.I.V B.,+_ - * ", +"+ + $.>.B.m+L.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'.'./././.Y Y r+1+]+Z.", +"+ @ ' X B+*._+/.E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+E+*.*.*.o+o+V V [.{+* Z.", +"+ + $ ~ I.B.Y w.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.D.|.|.|.'.'./././.>.j.@ ; ", +") + $ _ P.L.o+'.Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y Y *.*.*.o+o+V V V r+D+Z.# ", +" ' 3.Q.P V.-.T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T T ;+;+Q.Q.-.-.-.W ,.1.& # ", +"+ + % & ' H.H.t = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = * * - - - # > ) ]+", +") + ) ) + + ]+[ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - ' = = = * * - - 9 ~+& & ", +" + + ) ) + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - ' ' ' ' = = * * ]+' # [ "}; diff --git a/apps/DifOdometry-Datasets/CMakeLists.txt b/apps/DifOdometry-Datasets/CMakeLists.txt new file mode 100644 index 0000000000..cd19c0c852 --- /dev/null +++ b/apps/DifOdometry-Datasets/CMakeLists.txt @@ -0,0 +1,37 @@ +INCLUDE(../../cmakemodules/AssureCMakeRootFile.cmake) # Avoid user mistake in CMake source directory + +#----------------------------------------------------------------- +# CMake file for the MRPT application: ReactiveNav3D-Demo +# +# Run with "cmake ." at the root directory +# +# January 2014, Mariano Jaimez Tarifa +#----------------------------------------------------------------- +PROJECT(DifOdometry-Datasets) + +#MESSAGE(STATUS "Makefile for application: /apps/ReactiveNav3D-Demo ") + +# --------------------------------------------- +# TARGET: +# --------------------------------------------- +# Define the executable target: +ADD_EXECUTABLE(DifOdometry-Datasets + DifOdometry_Datasets_main.cpp + DifOdometry_Datasets.cpp + DifOdometry_Datasets.h) + +SET(TMP_TARGET_NAME "DifOdometry-Datasets") + + + +# Add the required libraries for linking: +TARGET_LINK_LIBRARIES(${TMP_TARGET_NAME} ${MRPT_LINKER_LIBS}) + +# Dependencies on MRPT libraries: +# Just mention the top-level dependency, the rest will be detected automatically, +# and all the needed #include<> dirs added (see the script DeclareAppDependencies.cmake for further details) +DeclareAppDependencies(${TMP_TARGET_NAME} mrpt-gui mrpt-opengl mrpt-vision) + +DeclareAppForInstall(${TMP_TARGET_NAME}) + + diff --git a/apps/DifOdometry-Datasets/DifOdometry_Datasets.cpp b/apps/DifOdometry-Datasets/DifOdometry_Datasets.cpp new file mode 100644 index 0000000000..9703398962 --- /dev/null +++ b/apps/DifOdometry-Datasets/DifOdometry_Datasets.cpp @@ -0,0 +1,651 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + +#include "DifOdometry_Datasets.h" + +using namespace mrpt; +using namespace mrpt::opengl; +using namespace mrpt::gui; +using namespace mrpt::slam; + + +void CDifodoDatasets::loadConfiguration(const utils::CConfigFileBase &ini ) +{ + downsample = ini.read_int("DIFODO_CONFIG", "downsample", 4, true); + rows = ini.read_int("DIFODO_CONFIG", "rows", 50, true); + cols = ini.read_int("DIFODO_CONFIG", "cols", 60, true); + + string filename = ini.read_string("DIFODO_CONFIG", "filename", "no file", true); + + + // Open Rawlog File + //================================================================== + + if (!dataset.loadFromRawLogFile(filename)) + throw std::runtime_error("\nCouldn't open rawlog dataset file for input..."); + + rawlog_count = 0; + + //filename.replace(filename.find(".rawlog"),7,"_Images\\"); + const string imgsPath = CRawlog::detectImagesDirectory(filename); + + // Set external images directory: + CImage::IMAGES_PATH_BASE = imgsPath; + + // Load ground_truth + //========================================================= + + filename = system::extractFileDirectory(filename); + filename.append("\\groundtruth.txt"); + f_gt.open(filename); + + if (f_gt.fail()) + throw std::runtime_error("\nError finding the groundtruth file: it should be contained in the same folder than the rawlog file"); + + char aux[100]; + f_gt.getline(aux, 100); + f_gt.getline(aux, 100); + f_gt.getline(aux, 100); + f_gt >> last_groundtruth; + f_gt >> last_gt_data[0]; f_gt >> last_gt_data[1]; f_gt >> last_gt_data[2]; + f_gt >> last_gt_data[3]; f_gt >> last_gt_data[4]; f_gt >> last_gt_data[5]; f_gt >> last_gt_data[6]; + last_groundtruth_ok = 1; + + // Resize Matrices and adjust parameters + //========================================================= + const unsigned int resh = 640/(cam_mode*downsample); + const unsigned int resv = 480/(cam_mode*downsample); + + depth.setSize(rows,cols); + depth_old.setSize(rows,cols); + depth_inter.setSize(rows,cols); + depth_ft.setSize(resv,resh); + depth_wf.setSize(resv,resh); + + du.setSize(rows,cols); + dv.setSize(rows,cols); + dt.setSize(rows,cols); + xx.setSize(rows,cols); + xx_inter.setSize(rows,cols); + xx_old.setSize(rows,cols); + yy.setSize(rows,cols); + yy_inter.setSize(rows,cols); + yy_old.setSize(rows,cols); + + border.setSize(rows,cols); + border.assign(0); + null.setSize(rows,cols); + null.assign(0); + est_cov.assign(0); + + x_incr = 2.0*f_dist*(floor(float(resh)/float(cols))*cols/float(resh))*tan(0.5*fovh)/(cols-1); //In meters + y_incr = 2.0*f_dist*(floor(float(resv)/float(rows))*rows/float(resv))*tan(0.5*fovv)/(rows-1); //In meters //In Hz + + //Depth thresholds + const int dz = floor(float(resv)/float(rows)); + const int dy = floor(float(resh)/float(cols)); + + duv_threshold = 0.001*(dz + dy)*(cam_mode*downsample); + dt_threshold = 0.2*fps; + dif_threshold = 0.001*(dz + dy)*(cam_mode*downsample); + difuv_surroundings = 0.005*(dz + dy)*(cam_mode*downsample); + dift_surroundings = 0.01*fps*(dz + dy)*(cam_mode*downsample); + +} + +void CDifodoDatasets::CreateResultsFile() +{ + try + { + // Open file, find the first free file-name. + char aux[100]; + int nFile = 0; + bool free_name = false; + + system::createDirectory("./difodo.results"); + + while (!free_name) + { + nFile++; + sprintf(aux, "./difodo.results/experiment_%03u.txt", nFile ); + free_name = !system::fileExists(aux); + } + + // Open log file: + f_res.open(aux); + + printf(" Saving results to file: %s \n", aux); + + } + catch (...) + { + printf("Exception found trying to create the 'results file' !!\n"); + } +} + +void CDifodoDatasets::initializeScene() +{ + global_settings::OCTREE_RENDER_MAX_POINTS_PER_NODE = 1000000; + window.resize(1000,900); + window.setPos(900,0); + window.setCameraZoom(16); + window.setCameraAzimuthDeg(0); + window.setCameraElevationDeg(90); + window.setCameraPointingToPoint(0,0,0); + window.setCameraPointingToPoint(0,0,1); + + scene = window.get3DSceneAndLock(); + + // Lights: + scene->getViewport()->setNumberOfLights(1); + CLight & light0 = scene->getViewport()->getLight(0); + light0.light_ID = 0; + light0.setPosition(0,0,1,1); + + //Grid (ground) + CGridPlaneXYPtr ground = CGridPlaneXY::Create(); + scene->insert( ground ); + + //Reference + CSetOfObjectsPtr reference = stock_objects::CornerXYZ(); + scene->insert( reference ); + + // Cameras and points + //------------------------------------------------------ + + //DifOdo camera + CBoxPtr camera_odo = CBox::Create(math::TPoint3D(-0.02,-0.1,-0.01),math::TPoint3D(0.02,0.1,0.01)); + camera_odo->setPose(cam_pose); + camera_odo->setColor(0,1,0); + scene->insert( camera_odo ); + + //Groundtruth camera + CBoxPtr camera_gt = CBox::Create(math::TPoint3D(-0.02,-0.1,-0.01),math::TPoint3D(0.02,0.1,0.01)); + camera_gt->setPose(gt_pose); + camera_gt->setColor(1,0,0); + scene->insert( camera_gt ); + + //Frustum + opengl::CFrustumPtr FOV = opengl::CFrustum::Create(0.3, 5, 57.3*fovh, 57.3*fovv, 1.5f, true, false); + FOV->setPose(gt_pose); + scene->insert( FOV ); + + //Reference gt + CSetOfObjectsPtr reference_gt = stock_objects::CornerXYZ(); + reference_gt->setScale(0.2); + reference_gt->setPose(gt_pose); + scene->insert( reference_gt ); + + //Camera points + CPointCloudPtr cam_points = CPointCloud::Create(); + cam_points->setColor(1,0,0); + cam_points->setPointSize(2); + cam_points->enablePointSmooth(1); + cam_points->setPose(cam_pose); + scene->insert( cam_points ); + + //Border points + CPointCloudPtr border_points = CPointCloud::Create(); + border_points->setColor(0,0,1); + border_points->setPointSize(3); + border_points->enablePointSmooth(1); + border_points->setPose(cam_pose); + scene->insert( border_points ); + + // Trajectories and covarianze + //------------------------------------------------------------- + + //Dif Odometry + CSetOfLinesPtr traj_lines_odo = CSetOfLines::Create(); + traj_lines_odo->setLocation(0,0,0); + traj_lines_odo->setColor(0,0,0); + traj_lines_odo->setLineWidth(3); + scene->insert( traj_lines_odo ); + CPointCloudPtr traj_points_odo = CPointCloud::Create(); + traj_points_odo->setColor(0,0.5,0); + traj_points_odo->setPointSize(4); + traj_points_odo->enablePointSmooth(1); + scene->insert( traj_points_odo ); + + //Groundtruth + CSetOfLinesPtr traj_lines_gt = CSetOfLines::Create(); + traj_lines_gt->setLocation(0,0,0); + traj_lines_gt->setColor(0,0,0); + traj_lines_gt->setLineWidth(3); + scene->insert( traj_lines_gt ); + CPointCloudPtr traj_points_gt = CPointCloud::Create(); + traj_points_gt->setColor(0.5,0,0); + traj_points_gt->setPointSize(4); + traj_points_gt->enablePointSmooth(1); + scene->insert( traj_points_gt ); + + //Ellipsoid showing covariance + math::CMatrixFloat33 cov3d(est_cov.topLeftCorner(3,3)); + CEllipsoidPtr ellip = CEllipsoid::Create(); + ellip->setCovMatrix(cov3d); + ellip->setQuantiles(2.0); + ellip->setColor(1.0, 1.0, 1.0, 0.5); + ellip->enableDrawSolid3D(true); + ellip->setPose(cam_pose); + scene->insert( ellip ); + + //User-interface information + utils::CImage img_legend; + img_legend.loadFromXPM(legend_xpm); + COpenGLViewportPtr legend = scene->createViewport("legend"); + legend->setViewportPosition(20, 20, 348, 200); + legend->setImageView(img_legend); + + window.unlockAccess3DScene(); + window.repaint(); +} + +void CDifodoDatasets::updateScene() +{ + scene = window.get3DSceneAndLock(); + + //Reference gt + CSetOfObjectsPtr reference_gt = scene->getByClass(1); + reference_gt->setPose(gt_pose); + + //Camera points + CPointCloudPtr cam_points = scene->getByClass(0); + cam_points->clear(); + cam_points->setPose(gt_pose); + for (unsigned int y=0; yinsertPoint(depth_inter(z,y), xx_inter(z,y), yy_inter(z,y)); + } + + //Border points + CPointCloudPtr border_points = scene->getByClass(1); + border_points->clear(); + border_points->setPose(gt_pose); + for (unsigned int y=0; yinsertPoint(depth_inter(z,y), xx_inter(z,y), yy_inter(z,y)); + + //DifOdo camera + CBoxPtr camera_odo = scene->getByClass(0); + camera_odo->setPose(cam_pose); + + //Groundtruth camera + CBoxPtr camera_gt = scene->getByClass(1); + camera_gt->setPose(gt_pose); + + //Frustum + CFrustumPtr FOV = scene->getByClass(0); + FOV->setPose(gt_pose); + + if (rawlog_count > 1) + { + //Difodo traj lines + CSetOfLinesPtr traj_lines_odo = scene->getByClass(0); + traj_lines_odo->appendLine(cam_oldpose.x(), cam_oldpose.y(), cam_oldpose.z(), cam_pose.x(), cam_pose.y(), cam_pose.z()); + + //Difodo traj points + CPointCloudPtr traj_points_odo = scene->getByClass(2); + traj_points_odo->insertPoint(cam_pose.x(), cam_pose.y(), cam_pose.z()); + + //Groundtruth traj lines + CSetOfLinesPtr traj_lines_gt = scene->getByClass(1); + traj_lines_gt->appendLine(gt_oldpose.x(), gt_oldpose.y(), gt_oldpose.z(), gt_pose.x(), gt_pose.y(), gt_pose.z()); + + //Groundtruth traj points + CPointCloudPtr traj_points_gt = scene->getByClass(3); + traj_points_gt->insertPoint(gt_pose.x(), gt_pose.y(), gt_pose.z()); + } + + //Ellipsoid showing covariance + math::CMatrixFloat33 cov3d(est_cov.topLeftCorner(3,3)); + CEllipsoidPtr ellip = scene->getByClass(0); + ellip->setCovMatrix(cov3d); + ellip->setPose(cam_pose); + + window.unlockAccess3DScene(); + window.repaint(); +} + +void CDifodoDatasets::loadFrame() +{ + CObservationPtr alfa = dataset.getAsObservation(rawlog_count); + + while (!IS_CLASS(alfa, CObservation3DRangeScan)) + { + rawlog_count++; + if (dataset.size() <= rawlog_count) + return; + alfa = dataset.getAsObservation(rawlog_count); + } + + CObservation3DRangeScanPtr obs3D = CObservation3DRangeScanPtr(alfa); + obs3D->load(); + + const unsigned int height = obs3D->rangeImage.getRowCount(); + const unsigned int width = obs3D->rangeImage.getColCount(); + const unsigned int index_incr = downsample; + + //Load depth image + for (unsigned int i=0; irangeImage(height-i-1, width-j-1); + + + double timestamp_gt; + double timestamp_obs = timestampTotime_t(obs3D->timestamp); + + //Exit if there is no ground truth at this time + if (last_groundtruth > timestamp_obs) + { + groundtruth_ok = 0; + obs3D->unload(); + rawlog_count++; + return; + } + + //Search the corresponding groundtruth data and interpolate + bool new_data = 0; + last_groundtruth_ok = groundtruth_ok; + while (last_groundtruth < timestamp_obs - 0.01) + { + f_gt.ignore(100,'\n'); + f_gt >> timestamp_gt; + last_groundtruth = timestamp_gt; + new_data = 1; + } + + //Read the inmediatly previous groundtruth + double x0,y0,z0,qx0,qy0,qz0,w0,t0; + if (new_data == 1) + { + f_gt >> x0; f_gt >> y0; f_gt >> z0; + f_gt >> qx0; f_gt >> qy0; f_gt >> qz0; f_gt >> w0; + } + else + { + x0 = last_gt_data[0]; y0 = last_gt_data[1]; z0 = last_gt_data[2]; + qx0 = last_gt_data[3]; qy0 = last_gt_data[4]; qz0 = last_gt_data[5]; w0 = last_gt_data[6]; + } + + t0 = last_groundtruth; + + //Read the inmediatly posterior groundtruth + f_gt.ignore(10,'\n'); + f_gt >> timestamp_gt; + last_groundtruth = timestamp_gt; + + //last_gt_data = [x y z qx qy qz w] + f_gt >> last_gt_data[0]; f_gt >> last_gt_data[1]; f_gt >> last_gt_data[2]; + f_gt >> last_gt_data[3]; f_gt >> last_gt_data[4]; f_gt >> last_gt_data[5]; f_gt >> last_gt_data[6]; + + if (last_groundtruth - timestamp_obs > 0.01) + { + groundtruth_ok = 0; + } + else + { + gt_oldpose = gt_pose; + + //Update pose + const float incr_t0 = timestamp_obs - t0; + const float incr_t1 = last_groundtruth - timestamp_obs; + const float incr_t = incr_t0 + incr_t1; + + //Sometimes the quaternion sign changes in the groundtruth + if (abs(qx0 + last_gt_data[3]) + abs(qy0 + last_gt_data[4]) + abs(qz0 + last_gt_data[5]) + abs(w0 + last_gt_data[6]) < 0.05) + { + qx0 = -qx0; qy0 = -qy0; qz0 = -qz0; w0 = -w0; + } + + double x,y,z,qx,qy,qz,w; + x = (incr_t0*last_gt_data[0] + incr_t1*x0)/(incr_t); + y = (incr_t0*last_gt_data[1] + incr_t1*y0)/(incr_t); + z = (incr_t0*last_gt_data[2] + incr_t1*z0)/(incr_t); + qx = (incr_t0*last_gt_data[3] + incr_t1*qx0)/(incr_t); + qy = (incr_t0*last_gt_data[4] + incr_t1*qy0)/(incr_t); + qz = (incr_t0*last_gt_data[5] + incr_t1*qz0)/(incr_t); + w = (incr_t0*last_gt_data[6] + incr_t1*w0)/(incr_t); + + + CMatrixDouble33 mat; + mat(0,0) = 1- 2*qy*qy - 2*qz*qz; + mat(0,1) = 2*(qx*qy - w*qz); + mat(0,2) = 2*(qx*qz + w*qy); + mat(1,0) = 2*(qx*qy + w*qz); + mat(1,1) = 1 - 2*qx*qx - 2*qz*qz; + mat(1,2) = 2*(qy*qz - w*qx); + mat(2,0) = 2*(qx*qz - w*qy); + mat(2,1) = 2*(qy*qz + w*qx); + mat(2,2) = 1 - 2*qx*qx - 2*qy*qy; + + CPose3D gt, transf; + + //Alternative - directly quaternions + //vector quat; + //quat[0] = x, quat[1] = y; quat[2] = z; + //quat[3] = w, quat[4] = qx; quat[5] = qy; quat[6] = qz; + //gt.setFromXYZQ(quat); + + gt.setFromValues(x,y,z,0,0,0); + gt.setRotationMatrix(mat); + transf.setFromValues(0,0,0,0.5*M_PI, -0.5*M_PI, 0); + + //Set the initial pose (if appropiate) + if (rawlog_count == 0) + cam_pose = gt + transf; + + gt_pose = gt + transf; + groundtruth_ok = 1; + + //printf("\n (q0,q0,q0,t0) = (%f, %f, %f, %.04f)", qx0, qy0, qz0, t0); + //printf("\n (q1,q1,q1,t1) = (%f, %f, %f, %.04f)", qx1, qy1, qz1, t1); + //printf("\n (x,y,z,t) = (%f, %f, %f, %.04f) \n", x, y, z, timestampTotime_t(obs3D->timestamp)); + + } + + obs3D->unload(); + rawlog_count++; +} + + +void CDifodoDatasets::reset() +{ + loadFrame(); + filterAndDownsample(); + calculateCoord(); + calculateDepthDerivatives(); + findNullPoints(); + findBorders(); + findValidPoints(); + + cam_oldpose = cam_pose; + gt_oldpose = gt_pose; +} + + +void CDifodoDatasets::filterSpeedAndPoseUpdate() +{ + //------------------------------------------------------------------------- + // Filter speed + //------------------------------------------------------------------------- + + utils::CTicTac clock; + clock.Tic(); + + // Calculate Eigenvalues and Eigenvectors + //---------------------------------------------------------- + Eigen::SelfAdjointEigenSolver eigensolver(est_cov); + if (eigensolver.info() != Eigen::Success) + { + printf("Eigensolver couldn't find a solution. Pose is not updated"); + return; + } + + //First, we have to describe both the new linear and angular speeds in the "eigenvector" basis + //------------------------------------------------------------------------------------------------- + MatrixXf Bii, kai_b; + Bii.setSize(6,6); kai_b.setSize(6,1); + Bii = eigensolver.eigenvectors(); + + kai_b = Bii.colPivHouseholderQr().solve(kai_solver); + + //Second, we have to describe both the old linear and angular speeds in the "eigenvector" basis too + //------------------------------------------------------------------------------------------------- + math::CMatrixDouble33 inv_trans; + math::CMatrixFloat31 v_loc_old, w_loc_old; + + //Express them in the local reference frame first + cam_pose.getRotationMatrix(inv_trans); + v_loc_old = inv_trans.inverse().cast()*kai_abs.topRows(3); + w_loc_old = inv_trans.inverse().cast()*kai_abs.bottomRows(3); + + //Then transform that local representation to the "eigenvector" basis + MatrixXf kai_b_old; + kai_b_old.setSize(6,1); + math::CMatrixFloat61 kai_loc_old; + kai_loc_old.topRows<3>() = v_loc_old; + kai_loc_old.bottomRows<3>() = w_loc_old; + + kai_b_old = Bii.colPivHouseholderQr().solve(kai_loc_old); + + //Filter speed + const float c = 400.0; + MatrixXf kai_b_fil; + kai_b_fil.setSize(6,1); + for (unsigned int i=0; i<6; i++) + { + kai_b_fil(i,0) = (kai_b(i,0) + (c*eigensolver.eigenvalues()(i,0) + 0.2)*kai_b_old(i,0))/(1.0 + c*eigensolver.eigenvalues()(i,0) + 0.2); + //kai_b_fil_d(i,0) = (kai_b_d(i,0) + 0.2*kai_b_old_d(i,0))/(1.0 + 0.2); + } + + //Transform filtered speed to local and then absolute reference systems + MatrixXf kai_loc_fil; + math::CMatrixFloat31 v_abs_fil, w_abs_fil; + kai_loc_fil.setSize(6,1); + kai_loc_fil = Bii.inverse().colPivHouseholderQr().solve(kai_b_fil); + + cam_pose.getRotationMatrix(inv_trans); + v_abs_fil = inv_trans.cast()*kai_loc_fil.topRows(3); + w_abs_fil = inv_trans.cast()*kai_loc_fil.bottomRows(3); + + kai_abs.topRows<3>() = v_abs_fil; + kai_abs.bottomRows<3>() = w_abs_fil; + + + //------------------------------------------------------------------------- + // Update pose (DIFODO) + //------------------------------------------------------------------------- + + cam_oldpose = cam_pose; + + //Rotations and translations (could be better, and I tried it but there isn't any significant difference...) + double yaw,pitch,roll; + math::CMatrixDouble31 w_euler_d; + + cam_pose.getYawPitchRoll(yaw,pitch,roll); + w_euler_d(0,0) = kai_loc_fil(4,0)*sin(roll)/cos(pitch) + kai_loc_fil(5,0)*cos(roll)/cos(pitch); + w_euler_d(1,0) = kai_loc_fil(4,0)*cos(roll) - kai_loc_fil(5,0)*sin(roll); + w_euler_d(2,0) = kai_loc_fil(3,0) + kai_loc_fil(4,0)*sin(roll)*tan(pitch) + kai_loc_fil(5,0)*cos(roll)*tan(pitch); + + //Update pose + cam_pose.x_incr(v_abs_fil(0,0)/fps); + cam_pose.y_incr(v_abs_fil(1,0)/fps); + cam_pose.z_incr(v_abs_fil(2,0)/fps); + cam_pose.setYawPitchRoll(yaw + w_euler_d(0,0)/fps, pitch + w_euler_d(1,0)/fps, roll + w_euler_d(2,0)/fps); + + execution_time += 1000*clock.Tac(); + + //================================================================================== + // Statistics + //================================================================================== + + if ((groundtruth_ok)&&(last_groundtruth_ok)) + { + CPose3D gt_pose_incr = gt_pose - gt_oldpose; + CPose3D cam_pose_incr = cam_pose - cam_oldpose; + CPose3D abs_pose_error = gt_pose - cam_pose; + + //cout << endl << "GT: " << gt_pose_incr; + //cout << endl << "OD: " << cam_pose_incr; + //cout << endl << "AE: " << abs_pose_error; + + //------------------------------------------------------------------------- + // DIF ODO + //------------------------------------------------------------------------- + + //Relative errors in displacement + for (unsigned int i=0; i<6; i++) + rel_error[i] = cam_pose_incr[i] - gt_pose_incr[i]; + + //Absolute error + abs_error_tras = sqrt(abs_pose_error[0]*abs_pose_error[0] + abs_pose_error[1]*abs_pose_error[1] + abs_pose_error[2]*abs_pose_error[2]); + abs_error_rot = sqrt(abs_pose_error[3]*abs_pose_error[3] + abs_pose_error[4]*abs_pose_error[4] + abs_pose_error[5]*abs_pose_error[5]); + + acu_rel_error_tras += sqrt(rel_error[0]*rel_error[0] + rel_error[1]*rel_error[1] + rel_error[2]*rel_error[2]); + acu_rel_error_rot += sqrt(rel_error[3]*rel_error[3] + rel_error[4]*rel_error[4] + rel_error[5]*rel_error[5]); + + ////Relative errors in velocity (m/s)^2 + //se_vel_dif = square(kai_loc_fil_d(0,0)-des_rel_true(0,0)*m_process.t_incr_inv) + // + square(kai_loc_fil_d(1,0)-des_rel_true(1,0)*m_process.t_incr_inv) + // + square(kai_loc_fil_d(2,0)-des_rel_true(2,0)*m_process.t_incr_inv); + + + sum_exec_time += execution_time; + + //Don't take into account those iterations with the same depth images + if (dt.sumAll() == 0) + dtzero_before = 1; + + else if (dtzero_before == 1) + dtzero_before = 0; + + else if (save_results == 1) + writeToLogFile(); + + } + + num_iter++; +} + + +void CDifodoDatasets::writeToLogFile() +{ + char aux[24]; + sprintf(aux,"%.04f", last_groundtruth); + f_res << aux << " "; + + f_res << rel_error[0] << " "; + f_res << rel_error[1] << " "; + f_res << rel_error[2] << " "; + f_res << rel_error[3] << " "; + f_res << rel_error[4] << " "; + f_res << rel_error[5] << " "; + + f_res << abs_error_tras << " "; + f_res << abs_error_rot << " "; + f_res << execution_time << " "; + f_res << num_valid_points << " "; + f_res << "\n"; +} + + +void CDifodoDatasets::showStatistics() +{ + printf("\n=============================================================================="); + printf("\n Average execution time (ms): %f", sum_exec_time/num_iter); + printf("\n Average frame to frame traslational error (m): %f", acu_rel_error_tras/num_iter); + printf("\n Average frame to frame rotational error (deg): %f", 57.3*acu_rel_error_rot/num_iter); + printf("\n Absolute traslational error (m): %f", abs_error_tras); + printf("\n Absolute rotational error (deg): %f", 57.3*abs_error_rot); + printf("\n==============================================================================\n"); +} + + diff --git a/apps/DifOdometry-Datasets/DifOdometry_Datasets.h b/apps/DifOdometry-Datasets/DifOdometry_Datasets.h new file mode 100644 index 0000000000..0763ca2b82 --- /dev/null +++ b/apps/DifOdometry-Datasets/DifOdometry_Datasets.h @@ -0,0 +1,103 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + + +#include +#include +#include +#include +#include +#include +#include +#include +#include "legend.xpm" + + +class CDifodoDatasets : public mrpt::vision::CDifodo { +public: + + mrpt::poses::CPose3D gt_pose; //!< Groundtruth camera pose + mrpt::poses::CPose3D gt_oldpose; //!< Groundtruth camera previous pose + + mrpt::gui::CDisplayWindow3D window; + mrpt::slam::CRawlog dataset; + std::ifstream f_gt; + std::ofstream f_res; + + unsigned int rawlog_count; + bool save_results; + + /** Constructor. */ + CDifodoDatasets() : mrpt::vision::CDifodo() + { + save_results = 0; + sum_exec_time = 0; + acu_rel_error_tras = 0; + acu_rel_error_rot = 0; + num_iter = 0; + } + + /** Initializes the visual odometry method and loads the rawlog file */ + void loadConfiguration( const mrpt::utils::CConfigFileBase &ini ); + + /** Loads the depth image and the corresponding groundtruth pose */ + void loadFrame(); + + /** Creates a file to save some results */ + void CreateResultsFile(); + + /** Initializes opengl scene */ + void initializeScene(); + + /** Updates the opengl scene */ + void updateScene(); + + /** Obtains the filtered speed, updates the pose and saves some statistics */ + void filterSpeedAndPoseUpdate(); + + /** A pre-step that should be performed before starting to estimate the camera speed + * As a couple of frames are necessary to estimate the camera motion, this methods loads the first frame + * before any motion can be estimated.*/ + void reset(); + + /** Shows the average frame to frame error made by Difodo, as well as its absolute pose error + * and its average execution time. */ + void showStatistics(); + +private: + + // Used to ignore consecutive frames with exactly the same depth image (it happens...) + bool dtzero_before; + + // Used to advoid saving results when the groundtruth is missing + bool groundtruth_ok; + bool last_groundtruth_ok; + + float rel_error[6]; //!< Relative frame to frame error in (vx, vy, vz, rel_yaw, rel_pitch, rel_roll) + float abs_error_tras; //!< Absolute pose error in traslation (m) + float acu_rel_error_tras; //!< Cumulative relative frame to frame error in traslation (m), used in "showStatistics()" + float abs_error_rot; //!< Absolute pose error in rotation (rad) + float acu_rel_error_rot; //!< Cumulative relative frame to frame error in rotation (rad), used in "showStatistics()" + float sum_exec_time; //!< Cumulative execution time, used in "showStatistics()" + + mrpt::opengl::COpenGLScenePtr scene; //!< Opengl scene + + unsigned int num_iter; //!< Iteration count + double last_groundtruth; //!< Timestamp of the last groundtruth read + double last_gt_data[7]; //!< Last ground truth read (x y z qx qy qz w) + + /** Saves the following data for each observation (distance in meters and angles in radians): + * timestamp of the groundtruth(s) - relative error (vx vy vz local_yaw local_pitch local_roll) - ... + * ... - abs_error_traslation - abs_error_rotation - execution_time - num_valid_points + + * Clarification: the timestamp belongs to the last groundtruth read, but the groundtruth pose is + * calculated interpolating between this and the previous one*/ + void writeToLogFile(); + +}; diff --git a/apps/DifOdometry-Datasets/DifOdometry_Datasets_main.cpp b/apps/DifOdometry-Datasets/DifOdometry_Datasets_main.cpp new file mode 100644 index 0000000000..14614d90f8 --- /dev/null +++ b/apps/DifOdometry-Datasets/DifOdometry_Datasets_main.cpp @@ -0,0 +1,197 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + +#include "DifOdometry_Datasets.h" + +using namespace std; +using namespace mrpt; + +const char *default_cfg_txt = + "; ---------------------------------------------------------------\n" + "; FILE: Difodo Parameters.txt\n" + ";\n" + "; MJT @ JANUARY-2014\n" + "; ---------------------------------------------------------------\n\n" + + "[DIFODO_CONFIG]\n\n" + + ";downsample: 1 - 640x480, 2 - 320x240, 4 - 160x120 \n" + "downsample = 4 \n\n" + + ";Indicate the number of rows and columns. They must be equal or inferior to what is indicated with the 'downsample' variable). \n" + "rows = 60 \n" + "cols = 80 \n\n" + + ";Absolute path of the rawlog file \n" + "filename = C:/.../file.rawlog \n"; + + +// ------------------------------------------------------ +// MAIN +// ------------------------------------------------------ + + +int main(int num_arg, char *argv[]) +{ + try + { + // Read function arguments + //---------------------------------------------------------------------- + bool use_config_file = false; + string filename; + CDifodoDatasets odo; + + if (num_arg < 2 || string(argv[1]) == "--help") + { + printf("\n\t Arguments of the function 'main' \n"); + printf("==============================================================\n\n"); + printf(" --help: Shows this menu... \n\n"); + printf(" --config FICH.txt: Load FICH.txt as config file \n\n"); + printf(" --create-config FICH.txt: Save the default config parameters \n\n"); + printf(" \t\t\t in FICH.txt and close the program \n\n"); + printf(" --save-logfile: Enable saving a file with results of the pose estimate \n\n"); + system::os::getch(); + return 1; + } + else if ( string(argv[1]) == "--create-config") + { + filename = argv[2]; + cout << endl << "Config_file name: " << filename; + ofstream new_file(filename.c_str()); + new_file << string(default_cfg_txt); + new_file.close(); + cout << endl << "File saved" << endl; + system::os::getch(); + return 1; + } + else + { + for (int i=1; i c #050505", +", c #141414", +"' c #090909", +") c #0A0A0A", +"! c #030303", +"~ c #040404", +"{ c #2A2A2A", +"] c #505050", +"^ c #525252", +"/ c #535353", +"( c #4D4D4D", +"_ c #4F4F4F", +": c #4E4E4E", +"< c #575757", +"[ c #272727", +"} c #1B1B1B", +"| c #595959", +"1 c #CDCDCD", +"2 c #C9C9C9", +"3 c #C6C6C6", +"4 c #C1C1C1", +"5 c #C5C5C5", +"6 c #C4C4C4", +"7 c #C3C3C3", +"8 c #CECECE", +"9 c #565656", +"0 c #D1D1D1", +"a c #C7C7C7", +"b c #CBCBCB", +"c c #D0D0D0", +"d c #D5D5D5", +"e c #2F2F2F", +"f c #5C5C5C", +"g c #EAEAEA", +"h c #E6E6E6", +"i c #E7E7E7", +"j c #E8E8E8", +"k c #E9E9E9", +"l c #E4E4E4", +"m c #515151", +"n c #383838", +"o c #646464", +"p c #F5F5F5", +"q c #FBFBFB", +"r c #F8F8F8", +"s c #F9F9F9", +"t c #FCFCFC", +"u c #FAFAFA", +"v c #F4F4F4", +"w c #F3F3F3", +"x c #5D5D5D", +"y c #363636", +"z c #171717", +"A c #656565", +"B c #FEFEFE", +"C c #FDFDFD", +"D c #FFFFFF", +"E c #5F5F5F", +"F c #353535", +"G c #161616", +"H c #080808", +"I c #0C0C0C", +"J c #343434", +"K c #151515", +"L c #636363", +"M c #5B5B5B", +"N c #373737", +"O c #F7F7F7", +"P c #F6F6F6", +"Q c #F2F2F2", +"R c #626262", +"S c #EEEEEE", +"T c #EDEDED", +"U c #333333", +"V c #3E3E3E", +"W c #727272", +"X c #F0F0F0", +"Y c #B9B9B9", +"Z c #4C4C4C", +"` c #262626", +" . c #2D2D2D", +".. c #303030", +"+. c #242424", +"@. c #252525", +"#. c #282828", +"$. c #A6A6A6", +"%. c #696969", +"&. c #CACACA", +"*. c #ECECEC", +"=. c #3F3F3F", +"-. c #F1F1F1", +";. c #EBEBEB", +">. c #A8A8A8", +",. c #E1E1E1", +"'. c #D2D2D2", +"). c #464646", +"!. c #ACACAC", +"~. c #BEBEBE", +"{. c #181818", +"]. c #DBDBDB", +"^. c #DCDCDC", +"/. c #A9A9A9", +"(. c #949494", +"_. c #EFEFEF", +":. c #545454", +"<. c #1F1F1F", +"[. c #454545", +"}. c #E0E0E0", +"|. c #444444", +"1. c #898989", +"2. c #ADADAD", +"3. c #1C1C1C", +"4. c #787878", +"5. c #A2A2A2", +"6. c #D8D8D8", +"7. c #E5E5E5", +"8. c #DDDDDD", +"9. c #757575", +"0. c #A3A3A3", +"a. c #A7A7A7", +"b. c #878787", +"c. c #AFAFAF", +"d. c #212121", +"e. c #D7D7D7", +"f. c #7C7C7C", +"g. c #BFBFBF", +"h. c #8D8D8D", +"i. c #2B2B2B", +"j. c #8A8A8A", +"k. c #DEDEDE", +"l. c #2E2E2E", +"m. c #3B3B3B", +"n. c #B3B3B3", +"o. c #D6D6D6", +"p. c #969696", +"q. c #A5A5A5", +"r. c #BBBBBB", +"s. c #919191", +"t. c #9C9C9C", +"u. c #CFCFCF", +"v. c #E3E3E3", +"w. c #D9D9D9", +"x. c #939393", +"y. c #8F8F8F", +"z. c #979797", +"A. c #9F9F9F", +"B. c #555555", +"C. c #3C3C3C", +"D. c #959595", +"E. c #9D9D9D", +"F. c #9E9E9E", +"G. c #B1B1B1", +"H. c #9A9A9A", +"I. c #8B8B8B", +"J. c #B8B8B8", +"K. c #8E8E8E", +"L. c #B4B4B4", +"M. c #5E5E5E", +"N. c #494949", +"O. c #909090", +"P. c #B2B2B2", +"Q. c #A1A1A1", +"R. c #BDBDBD", +"S. c #C0C0C0", +"T. c #A4A4A4", +"U. c #9B9B9B", +"V. c #B5B5B5", +"W. c #767676", +"X. c #292929", +"Y. c #858585", +"Z. c #999999", +"`. c #8C8C8C", +" + c #DADADA", +".+ c #A0A0A0", +"++ c #ABABAB", +"@+ c #929292", +"#+ c #B0B0B0", +"$+ c #3D3D3D", +"%+ c #686868", +"&+ c #060606", +"*+ c #B6B6B6", +"=+ c #848484", +"-+ c #666666", +";+ c #1D1D1D", +">+ c #D3D3D3", +",+ c #222222", +"'+ c #7E7E7E", +")+ c #6B6B6B", +"!+ c #6D6D6D", +"~+ c #414141", +"{+ c #707070", +"]+ c #989898", +"^+ c #CCCCCC", +"/+ c #828282", +"(+ c #606060", +"_+ c #1A1A1A", +":+ c #7D7D7D", +"<+ c #434343", +"[+ c #3A3A3A", +"}+ c #838383", +"|+ c #BCBCBC", +"1+ c #5A5A5A", +"2+ c #484848", +"3+ c #1E1E1E", +"4+ c #BABABA", +"5+ c #2C2C2C", +"6+ c #6E6E6E", +"7+ c #616161", +"8+ c #DFDFDF", +"9+ c #6F6F6F", +"0+ c #474747", +"a+ c #D4D4D4", +"b+ c #7F7F7F", +"c+ c #818181", +"d+ c #AAAAAA", +"e+ c #404040", +"f+ c #747474", +"g+ c #888888", +"h+ c #B7B7B7", +"i+ c #313131", +"j+ c #4B4B4B", +"k+ c #C8C8C8", +"l+ c #C2C2C2", +"m+ c #868686", +"n+ c #424242", +"o+ c #777777", +"p+ c #797979", +"q+ c #737373", +"r+ c #323232", +"s+ c #7B7B7B", +"t+ c #4A4A4A", +"u+ c #E2E2E2", +"v+ c #6C6C6C", +"w+ c #808080", +"x+ c #585858", +"y+ c #7A7A7A", +"z+ c #202020", +"A+ c #676767", +"B+ c #232323", +"C+ c #717171", +"D+ c #393939", +"E+ c #191919", +"F+ c #6A6A6A", +"G+ c #AEAEAE", +"H+ c #FFFFFD", +"I+ c #FFFEFF", +"J+ c #FFFDFE", +"K+ c #FEFEFC", +"L+ c #FEFFFD", +"M+ c #FDFFFC", +"N+ c #FFFDFF", +"O+ c #FEFFFB", +"P+ c #FDFFFA", +"Q+ c #FEFEFF", +"R+ c #FFFEFC", +"S+ c #FCFEF9", +"T+ c #FDFDFF", +"U+ c #FCFCFE", +"V+ c #FDFCFA", +"W+ c #FCFCFA", +"X+ c #FCFDF8", +"Y+ c #FBFDF8", +"Z+ c #F9FEF8", +"`+ c #F8FDF7", +" @ c #FCFEFB", +".@ c #FDFBFE", +"+@ c #FDFCFF", +"@@ c #FEFDFF", +"#@ c #FEFFFA", +"$@ c #FBFBFD", +"%@ c #FBFEF7", +"&@ c #F8FDF6", +"*@ c #FBFDFA", +"=@ c #FAFCFB", +"-@ c #FAFAFC", +";@ c #FBFAFF", +">@ c #FCFBFF", +",@ c #FDFDFB", +"'@ c #FDFEF9", +")@ c #FDFFF9", +"!@ c #FBFFF9", +"~@ c #FAFFF8", +"{@ c #FBFFFA", +"]@ c #FBFFFC", +"^@ c #F9F8FE", +"/@ c #F9F8FD", +"(@ c #F8F7FC", +"_@ c #FAF9FE", +":@ c #FBFBF9", +"<@ c #FBFCF7", +"[@ c #FAFBF6", +"}@ c #FEFFFF", +"|@ c #F4FFFE", +"1@ c #ECFFFD", +"2@ c #EBFFFD", +"3@ c #F5FFFF", +"4@ c #FCFEFD", +"5@ c #FAFFFF", +"6@ c #F7FFFF", +"7@ c #F9FEFF", +"8@ c #FEFCFF", +"9@ c #FFFBFF", +"0@ c #F9FFFD", +"a@ c #F7FFFB", +"b@ c #F7FFF9", +"c@ c #F6FFFF", +"d@ c #F6FFFD", +"e@ c #F7FFFD", +"f@ c #FCFFFF", +"g@ c #FFFAFE", +"h@ c #FDF8FE", +"i@ c #FFF4FF", +"j@ c #FFF5FF", +"k@ c #FFF7FF", +"l@ c #FDF8FF", +"m@ c #FFFAFF", +"n@ c #F7FFFE", +"o@ c #F5FEF9", +"p@ c #FFFFFA", +"q@ c #FEF9F5", +"r@ c #FFFBF8", +"s@ c #FDFAF5", +"t@ c #F8FEFA", +"u@ c #F5FFFD", +"v@ c #F1FFFE", +"w@ c #ECFFFE", +"x@ c #EBFFFE", +"y@ c #EDFFFF", +"z@ c #FCFAFB", +"A@ c #FFF9F9", +"B@ c #FFF9FB", +"C@ c #FFFAFC", +"D@ c #FDFBFC", +"E@ c #FCFBF9", +"F@ c #FBF9FC", +"G@ c #FDF6FE", +"H@ c #FFF8FF", +"I@ c #F8FFF4", +"J@ c #F2FFEC", +"K@ c #EFFFE9", +"L@ c #F5FFEF", +"M@ c #F9FFF3", +"N@ c #F9FFFA", +"O@ c #F6FFF6", +"P@ c #F8FFF8", +"Q@ c #F9FFF8", +"R@ c #FAFFF9", +"S@ c #FFFFFB", +"T@ c #FCFFFD", +"U@ c #FBFFFF", +"V@ c #F9FFFF", +"W@ c #FDFFFE", +"X@ c #FFF6FE", +"Y@ c #F2FEFA", +"Z@ c #FAFFFE", +"`@ c #F6FAF9", +" # c #FCFDFF", +".# c #FAFFFB", +"+# c #FAFEFF", +"@# c #FFFCFD", +"## c #FFFCFF", +"$# c #FEF9FF", +"%# c #FCF9FF", +"&# c #F1FFFD", +"*# c #EDFCF9", +"=# c #F1FBFA", +"-# c #FDF9FA", +";# c #FBF2F5", +"># c #FEF3F7", +",# c #FFF5F9", +"'# c #FFF9FD", +")# c #FBFCFF", +"!# c #F5FDFF", +"~# c #FDFEFF", +"{# c #FEFBFF", +"]# c #FCF7FE", +"^# c #FEF4FF", +"/# c #FFF2FF", +"(# c #FEEBFF", +"_# c #FEEDFF", +":# c #FCF5FC", +"<# c #FCFFF6", +"[# c #F7FFF2", +"}# c #F6FFEF", +"|# c #F9FFF1", +"1# c #FAFBF3", +"2# c #FFFBFC", +"3# c #FCFFFB", +"4# c #FFF1FC", +"5# c #FFF9FF", +"6# c #FBFFFD", +"7# c #F9FFFB", +"8# c #FEFCFD", +"9# c #FDFCF7", +"0# c #FDFCF8", +"a# c #FAFBFD", +"b# c #F9FDFE", +"c# c #F6FCFC", +"d# c #F8FEFE", +"e# c #F2FFFF", +"f# c #EFFFFF", +"g# c #EEFCFD", +"h# c #F3FDFE", +"i# c #F8FDFF", +"j# c #F9FAFE", +"k# c #FFF7FE", +"l# c #F9FDFF", +"m# c #FBF8FF", +"n# c #FEF6FF", +"o# c #F9FAF4", +"p# c #F4FDEC", +"q# c #F8FAEF", +"r# c #FFF6FF", +"s# c #FFF8FD", +"t# c #FFF6F9", +"u# c #FFFAFA", +"v# c #FFFDFA", +"w# c #FFFFF8", +"x# c #FAFFF7", +"y# c #F9FFF6", +"z# c #FEFFF7", +"A# c #FFFEF9", +"B# c #FEFFF9", +"C# c #FBFFF7", +"D# c #FFFFF7", +"E# c #FFFDF5", +"F# c #FDFDF5", +"G# c #FEFDF8", +"H# c #FCFFF8", +"I# c #FBFFFB", +"J# c #F6FFFA", +"K# c #F5FFFA", +"L# c #F4FFF9", +"M# c #F0FEFF", +"N# c #EEFCFF", +"O# c #F4FFFF", +"P# c #F3FFFD", +"Q# c #F5FFFB", +"R# c #F2FFF7", +"S# c #F8FFF6", +"T# c #FCFFF4", +"U# c #FFFFF3", +"V# c #FFFFF1", +"W# c #FFFFEF", +"X# c #FEFFED", +"Y# c #FAFFEC", +"Z# c #F8FFEC", +"`# c #F8FFF2", +" $ c #F8FFF0", +".$ c #F9FFF2", +"+$ c #FAFFF5", +"@$ c #F3FFF2", +"#$ c #EFFFF1", +"$$ c #F2FFF6", +"%$ c #F4FFFA", +"&$ c #F2FDF9", +"*$ c #F6FFFB", +"=$ c #F3FFF6", +"-$ c #EEFFEB", +";$ c #ECFFE7", +">$ c #ECFFE4", +",$ c #F1FDE7", +"'$ c #FBFFF1", +")$ c #FFF4FE", +"!$ c #FFFEFB", +"~$ c #FFFFF4", +"{$ c #FBF9FA", +"]$ c #F3E9E8", +"^$ c #FFEAED", +"/$ c #FFE9EA", +"($ c #FFE6E3", +"_$ c #FDECE4", +":$ c #F7EFE4", +"<$ c #FAEDE4", +"[$ c #FFE9E3", +"}$ c #FFE7E3", +"|$ c #FFE8E3", +"1$ c #FDEAE4", +"2$ c #F9ECE3", +"3$ c #FDEAE3", +"4$ c #FEE9E4", +"5$ c #FCEBE3", +"6$ c #FBEAE2", +"7$ c #FFF0E8", +"8$ c #FCEEE5", +"9$ c #F9ECE4", +"0$ c #F8EDE7", +"a$ c #FCF5ED", +"b$ c #F3EFE6", +"c$ c #F3F0E9", +"d$ c #F7FEF6", +"e$ c #F5FFF6", +"f$ c #F6FFF7", +"g$ c #F4FFF7", +"h$ c #FAFFFC", +"i$ c #F8FEFC", +"j$ c #F1FEF5", +"k$ c #EAFFEE", +"l$ c #D0F7D8", +"m$ c #CAFFD3", +"n$ c #C0FFC8", +"o$ c #B8FDBE", +"p$ c #BBFCB8", +"q$ c #C0FCB6", +"r$ c #C5FAB2", +"s$ c #C7FBB1", +"t$ c #C7FBB0", +"u$ c #C7FDAF", +"v$ c #C4FDAE", +"w$ c #C3FAB6", +"x$ c #C6F9B6", +"y$ c #C3FAB7", +"z$ c #BFFCB6", +"A$ c #B8FFB1", +"B$ c #B2FFAF", +"C$ c #B1FFB1", +"D$ c #B6FFB6", +"E$ c #BCFFC0", +"F$ c #BFFFC3", +"G$ c #BBFEBB", +"H$ c #B8FEB6", +"I$ c #BCFFB7", +"J$ c #C1FCBC", +"K$ c #CCF8C5", +"L$ c #D8FDD2", +"M$ c #DBF7E1", +"N$ c #ECFFF0", +"O$ c #F1FCF4", +"P$ c #F9F7F8", +"Q$ c #DEEADE", +"R$ c #9A8B86", +"S$ c #976469", +"T$ c #A45D65", +"U$ c #A35E63", +"V$ c #9D6564", +"W$ c #986762", +"X$ c #9C6562", +"Y$ c #A26061", +"Z$ c #A65E61", +"`$ c #A45F62", +" % c #9F6162", +".% c #9B6362", +"+% c #9D6362", +"@% c #9E6262", +"#% c #9D6361", +"$% c #9F6865", +"%% c #996160", +"&% c #986562", +"*% c #9F6D6C", +"=% c #966966", +"-% c #8B6260", +";% c #956F6C", +">% c #D0AAA7", +",% c #FBFCF4", +"'% c #F8F9F1", +")% c #F8FBF4", +"!% c #FFFAFD", +"~% c #FFF6F4", +"{% c #FFFEF2", +"]% c #F5FFE8", +"^% c #DAFED0", +"/% c #91D38C", +"(% c #6DCE71", +"_% c #57D260", +":% c #51DC5B", +"<% c #4EDF54", +"[% c #51DF4F", +"}% c #57DC4B", +"|% c #5CDC4B", +"1% c #5EDC4A", +"2% c #60DC4A", +"3% c #5FDB49", +"4% c #57DB51", +"5% c #59DD53", +"6% c #58DC52", +"7% c #56DE50", +"8% c #54E04C", +"9% c #4EE148", +"0% c #4CE245", +"a% c #51DF4B", +"b% c #55DC52", +"c% c #58DA56", +"d% c #59DB57", +"e% c #5BDD59", +"f% c #61DE5E", +"g% c #64D762", +"h% c #65C966", +"i% c #64C168", +"j% c #7CC786", +"k% c #B7F3BF", +"l% c #DEFFE4", +"m% c #F4FFF6", +"n% c #FAF8F9", +"o% c #F7F9EC", +"p% c #967774", +"q% c #A2555F", +"r% c #BD5262", +"s% c #BE525F", +"t% c #B35259", +"u% c #AD5355", +"v% c #B35458", +"w% c #BC535A", +"x% c #BF515A", +"y% c #BD525C", +"z% c #BB535C", +"A% c #B7535B", +"B% c #B5545B", +"C% c #B4555B", +"D% c #B55559", +"E% c #B15258", +"F% c #B3545A", +"G% c #B0555C", +"H% c #AA5359", +"I% c #AA585E", +"J% c #AB5C61", +"K% c #A3565C", +"L% c #D0858A", +"M% c #FEF6F3", +"N% c #FBF3F0", +"O% c #FBF6F2", +"P% c #FCFBF6", +"Q% c #FFF5EF", +"R% c #FFEFE2", +"S% c #FEF6DF", +"T% c #F4FFD4", +"U% c #D8FFBB", +"V% c #7ED06C", +"W% c #54D14F", +"X% c #41E548", +"Y% c #30EF3D", +"Z% c #29F436", +"`% c #28F430", +" & c #2CF22B", +".& c #32F02C", +"+& c #37EF2D", +"@& c #39ED2C", +"#& c #37EA2C", +"$& c #30F232", +"%& c #2CF432", +"&& c #2DF231", +"*& c #2DF230", +"=& c #2DF32C", +"-& c #2DF429", +";& c #2DF425", +">& c #2FF327", +",& c #36F02B", +"'& c #3CEC32", +")& c #3EEA36", +"!& c #3DE837", +"~& c #3BE635", +"{& c #3DE83A", +"]& c #47E747", +"^& c #4BE050", +"/& c #48D44F", +"(& c #69D170", +"_& c #A5FCAB", +":& c #CDFFD2", +"<& c #ECFFF1", +"[& c #F8FDF9", +"}& c #FCF8F9", +"|& c #EDE9DE", +"1& c #8F6767", +"2& c #A8525F", +"3& c #BC485B", +"4& c #B84353", +"5& c #B44B52", +"6& c #AF4F51", +"7& c #AE494D", +"8& c #B4494F", +"9& c #B6494F", +"0& c #B64851", +"a& c #B34850", +"b& c #B34852", +"c& c #B14952", +"d& c #AE4A52", +"e& c #B24950", +"f& c #B2494E", +"g& c #B34A51", +"h& c #B14950", +"i& c #B14C54", +"j& c #AD4C53", +"k& c #AB4E56", +"l& c #A94F58", +"m& c #A14C53", +"n& c #DE8C92", +"o& c #FFF3F3", +"p& c #FCF0F0", +"q& c #FDF3F2", +"r& c #FFF8F6", +"s& c #FFFAF7", +"t& c #FFFBFA", +"u& c #FFFDFC", +"v& c #FFFBF2", +"w& c #FFF5E5", +"x& c #FFFADD", +"y& c #F4FECC", +"z& c #DAFFB5", +"A& c #7DCA62", +"B& c #53CD44", +"C& c #43E542", +"D& c #2EF037", +"E& c #24F631", +"F& c #24F72E", +"G& c #27F42D", +"H& c #2FF331", +"I& c #35F234", +"J& c #37EF35", +"K& c #35ED35", +"L& c #35ED33", +"M& c #36F035", +"N& c #35EF34", +"O& c #35F031", +"P& c #33F12D", +"Q& c #33F12B", +"R& c #35F02D", +"S& c #3AED32", +"T& c #3BE733", +"U& c #41E93A", +"V& c #40EB3A", +"W& c #39E632", +"X& c #37E432", +"Y& c #44EC41", +"Z& c #4EE94D", +"`& c #49DD49", +" * c #65CA62", +".* c #A2F6A1", +"+* c #CFFFD0", +"@* c #F1FFF4", +"#* c #FBF7F8", +"$* c #E8E4DB", +"%* c #BE9F9D", +"&* c #B97880", +"** c #CF7984", +"=* c #CA787E", +"-* c #BD7576", +";* c #BB7C77", +">* c #BD7C76", +",* c #C07B76", +"'* c #BD7775", +")* c #BB7573", +"!* c #C07677", +"~* c #C17577", +"{* c #BB7776", +"]* c #C07675", +"^* c #C27676", +"/* c #C57979", +"(* c #C27879", +"_* c #C1797A", +":* c #BE7A7B", +"<* c #C08081", +"[* c #BA7E7E", +"}* c #BB8082", +"|* c #D9A1A2", +"1* c #F6E7EC", +"2* c #FEF2F6", +"3* c #FFF8FC", +"4* c #FFF7FA", +"5* c #FDF7F9", +"6* c #FAFDF6", +"7* c #F7F7EB", +"8* c #FFFFEC", +"9* c #F3F9D7", +"0* c #E2FBC2", +"a* c #9FD484", +"b* c #84DC74", +"c* c #65DE5F", +"d* c #51E255", +"e* c #4CE652", +"f* c #50E354", +"g* c #54E157", +"h* c #58DE5B", +"i* c #5ADC5E", +"j* c #5ADC60", +"k* c #67D656", +"l* c #68D558", +"m* c #67D55A", +"n* c #64D758", +"o* c #60D956", +"p* c #5CDB56", +"q* c #5DDC59", +"r* c #5EDB5D", +"s* c #61D860", +"t* c #5ED85F", +"u* c #5CDB5A", +"v* c #5BDF55", +"w* c #5BE053", +"x* c #5BDB52", +"y* c #60D757", +"z* c #67D65E", +"A* c #8BD080", +"B* c #BFF5B7", +"C* c #E0FEDC", +"D* c #F7F5F6", +"E* c #F2F0F1", +"F* c #F1F0EC", +"G* c #E4D4D4", +"H* c #DFBFC2", +"I* c #E0B9BA", +"J* c #D5B6B1", +"K* c #CDB9AE", +"L* c #CEBCAE", +"M* c #CDBAAC", +"N* c #D2BCAF", +"O* c #CEBBAD", +"P* c #CCB8AD", +"Q* c #CFB8B0", +"R* c #D2B7B0", +"S* c #D3B6B0", +"T* c #D2B7AE", +"U* c #D3B7AC", +"V* c #D4B8AD", +"W* c #D5B7AF", +"X* c #D7B9B1", +"Y* c #D4B6AE", +"Z* c #D1B6AF", +"`* c #D4BDB7", +" = c #D2BFB8", +".= c #D6C5BE", +"+= c #F0E1DA", +"@= c #F5ECF1", +"#= c #FCF3F8", +"$= c #FEF8FC", +"%= c #FBF6FA", +"&= c #F8F6F9", +"*= c #F3FFFF", +"== c #F3FBE3", +"-= c #C4DAB4", +";= c #B0DBA5", +">= c #98D391", +",= c #92D890", +"'= c #91D98F", +")= c #94D790", +"!= c #99D494", +"~= c #9ED198", +"{= c #9FCF9D", +"]= c #9FCF9F", +"^= c #9ECFA0", +"/= c #A8CD97", +"(= c #ABCB99", +"_= c #ABCB9A", +":= c #AACB9C", +"<= c #A7CD9C", +"[= c #A3CF9C", +"}= c #9FD19C", +"|= c #9DD29E", +"1= c #9DD1A1", +"2= c #9ECFA2", +"3= c #9BCF9F", +"4= c #98D498", +"5= c #92D88F", +"6= c #90D988", +"7= c #91D987", +"8= c #9AD88D", +"9= c #A4DB97", +"0= c #B7D1AA", +"a= c #DDEDD3", +"b= c #F0F1EB", +"c= c #F9FFF9", +"d= c #FCFFFA", +"e= c #FFFEFD", +"f= c #FEFFF8", +"g= c #F8F6F7", +"h= c #F4F2F3", +"i= c #EEE5EA", +"j= c #E6DBDF", +"k= c #DAD0D1", +"l= c #D0CDC8", +"m= c #CAD0C6", +"n= c #C2CEC0", +"o= c #C2CDBD", +"p= c #C9CFC1", +"q= c #CCCFC4", +"r= c #C8CEC2", +"s= c #C5CDC2", +"t= c #C7CDC3", +"u= c #CACDC4", +"v= c #CBCBC3", +"w= c #CACBC3", +"x= c #C9CCC3", +"y= c #CACBC5", +"z= c #C9CCC1", +"A= c #CACCC1", +"B= c #CBCBC1", +"C= c #CFCCC3", +"D= c #CCC9C0", +"E= c #C8C9C1", +"F= c #CBCEC7", +"G= c #CCD3CB", +"H= c #D0DAD2", +"I= c #E4EEE6", +"J= c #F4F3F8", +"K= c #F6FAFD", +"L= c #F5F9FC", +"M= c #F0FFFF", +"N= c #EFFCFF", +"O= c #F4F9FF", +"P= c #F5F4F9", +"Q= c #F6F5F3", +"R= c #DADBD5", +"S= c #D0D6CC", +"T= c #C1CCBE", +"U= c #C6D1C1", +"V= c #C9CFC3", +"W= c #CFCCC5", +"X= c #D4C9C7", +"Y= c #D6C7CA", +"Z= c #D6C7CE", +"`= c #D3C8D0", +" - c #D2C8D1", +".- c #CBCDC8", +"+- c #C9CBC6", +"@- c #CACAC8", +"#- c #CACCCB", +"$- c #C8CCCB", +"%- c #CACBCD", +"&- c #CCC9D0", +"*- c #D0CAD4", +"=- c #CECCD1", +"-- c #C8CFC8", +";- c #C0D3BF", +">- c #B9D4B5", +",- c #BAD3B3", +"'- c #C3D7BC", +")- c #CCDBC6", +"!- c #DED9D6", +"~- c #F5EAEE", +"{- c #FAECF9", +"]- c #FBFFF8", +"^- c #F8EDF5", +"/- c #E7E5E8", +"(- c #E0E9E6", +"_- c #DEEFE7", +":- c #DAEBE1", +"<- c #DAE7DE", +"[- c #E5ECE5", +"}- c #E6E8E3", +"|- c #E4E6E3", +"1- c #E1E6E2", +"2- c #E0E6E4", +"3- c #E1E7E5", +"4- c #E1E7E3", +"5- c #E2E7E3", +"6- c #DEE7E4", +"7- c #DEE7E2", +"8- c #DEE8E0", +"9- c #E1E8E1", +"0- c #E2E7E1", +"a- c #E4E9E3", +"b- c #E4E9E5", +"c- c #E3E7E6", +"d- c #E2E8E6", +"e- c #E3ECEB", +"f- c #E5EFEE", +"g- c #EDF9F7", +"h- c #F4F9FC", +"i- c #F6FBFE", +"j- c #F8FFFF", +"k- c #F1EAF1", +"l- c #EEE4EC", +"m- c #EDE0E9", +"n- c #F2DEEA", +"o- c #F7DBEA", +"p- c #FAD9EC", +"q- c #FAD9EE", +"r- c #F9D9F0", +"s- c #F4DBF0", +"t- c #F2DDF0", +"u- c #E4E4EC", +"v- c #E1E6EC", +"w- c #E2E5EC", +"x- c #E5E3EE", +"y- c #E6E3EC", +"z- c #E6E3EA", +"A- c #E8E3EA", +"B- c #EBE1EA", +"C- c #EFDEF0", +"D- c #F3DBF1", +"E- c #ECE0EA", +"F- c #E5E4E2", +"G- c #DEE5DD", +"H- c #DDE4DD", +"I- c #E3E4E6", +"J- c #EAE5EC", +"K- c #F2E4F5", +"L- c #FFF1FF", +"M- c #FFF3FF", +"N- c #FFF2FE", +"O- c #FFF3FD", +"P- c #F8F6FB", +"Q- c #F3F9F9", +"R- c #F0F9F6", +"S- c #F1FAF7", +"T- c #F4F8F7", +"U- c #FAF4F8", +"V- c #FAF1F6", +"W- c #FAF0F8", +"X- c #F7F2F8", +"Y- c #F3F4F6", +"Z- c #F4F4F6", +"`- c #F5F3F6", +" ; c #F2F3F5", +".; c #F1F5F6", +"+; c #F1F5F4", +"@; c #F4F6F5", +"#; c #F9F7FA", +"$; c #F6F5FA", +"%; c #F6F7FB", +"&; c #F4F8FB", +"*; c #F6F9FE", +"=; c #F7FCFF", +"-; c #F6FEFF", +";; c #F7F5F8", +">; c #FAF5FB", +",; c #FCEFF8", +"'; c #FFEEF8", +"); c #FFEDF8", +"!; c #F8F1F8", +"~; c #F5F3F8", +"{; c #F3F5F0", +"]; c #F3F6EF", +"^; c #F4F5F0", +"/; c #F8F2F4", +"(; c #FAEFF7", +"_; c #F9EEF6", +":; c #F6F2F3", +"<; c #F1F8F0", +"[; c #F1F6F2", +"}; c #F5F2F9", +"|; c #FAEFFF", +"1; c #FCF3FF", +"2; c #FDF8FC", +"3; c #FCFAFD", +"4; c #FAFEFD", +"5; c #FFFEFA", +"6; c #F8FFFA", +"7; c #F7FFFA", +"8; c #FFFCF9", +"9; c #FFFBF9", +"0; c #FAFFF4", +"a; c #F6FFF1", +"b; c #F9FEF7", +"c; c #FFFDFD", +"d; c #FFFBFD", +"e; c #F8FFFE", +"f; c #FFFCFC", +"g; c #FFFCFB", +"h; c #FEFDFB", +"i; c #F8FFF9", +"j; c #F8FFF7", +"k; c #F0FFF9", +"l; c #FFFAF9", +"m; c #FFF9FA", +"n; c #F2FFFD", +"o; c #FFFCFA", +"p; c #F6FFF4", +"q; c #F7FFF4", +" . + @ # $ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ $ % @ $ # & . . ", +"+ + . * & & = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = - = - # # ; - % > ", +", - ' ) > ! + + + ~ * ! + ", +"- # % { ] ^ / ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( ( _ : _ _ _ _ _ < [ ; ", +"} ! | 1 2 3 4 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 5 6 7 5 6 7 7 5 8 9 + ~ ~ ", +"@ - + / 0 a 1 1 b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b b 8 8 c 8 1 1 1 d 9 & e ", +"@ ; f g h i j k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k k j j k i i i l i m ~ - n ", +"$ ; ~ o p q r s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s q q t u q u v w x ! # y ", +"z ' ! A r s t B C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C t B q B B D q C q B t C q D C t u D B t q t D t C C q B C B q D D r D B u D B B C C C C C C C C C C C C C C C C C C C C C C C C C D B C C t t B C C C C t t C B C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C D t B t B q D C q B t q C q B q D B t C C C C C C C B C C C C B C t t C C C t C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C q D B t D D t C t C t B B B D t C C C C C t t t C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C C B B C C C C C C C C B t D t q t B C C C C C C B C C C C C C C C C C C C C C C C C C C C C C C C C C B B C t q q E . = F ", +"G H + o s q B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C C u B D D D D D D D C B D D C C t D D q D D q D D s D D t q D B D D t C C D D D D D D D D D D D D D D D D D D D D D D D D B D D C D B B D B B D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D B D C B D D t D B D D B D C D q D D q D D D D D D D D D D C D D D C B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D B C D D B D D t D C D t t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B D D D D D t D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C t q f I J ", +"K H L u t B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C D D D B D B D B D D D C D D t q D D C t D C B D t D D C D D D D D q B D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D C D D D D D D B B D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D C D C D D D D D C C D C B D u D D C D D C D D D D D D D D C D B D B D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D D B D D D D B D D B D B B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D D D D D D D B C D D C t D D D D D D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C t q M I F ", +"G ; L q t B C B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B t B q B C D t t C D t B B D B D D B B D s D C B D B t D C B D B s D D s u B u B B B B B B B B B B B B B B B B B B B B B B B B C D B C D B C B D D B C B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B C D B D B D B B D D D C C B D C t D t q D B D B B B B B B B B D D q D C D B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B D D B D D B C D D s D t D t C B B D D B B C B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B D D u D D D D D B B B B B B C C B B B B B B B B B B B B B B B B B B B B B B B C B B D D B C t q f = N ", +"K - L q u C C B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B C D D r B C B t D D C D C B t C s D D t D D B D D O D q p D t u D B O C D t D D B B B B B B B B B B B B B B B B B B B B B B B B B D B B t C q C t C B D D D D D B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B D D D D t D B q P u C D D B B B C D t D D q B q B B B D D D D D B B u t q D B D B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B D D C t C D C D D D C O D C D D D D D D D D B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B C C t q t C D u P C C B C C B B B D D D B B B B B B B B B B B B B B B B B B D D B B B B D D D D D B t t f = N ", +"@ = L q u B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B q C D C s q B q r D t s O C D q D D q D B D u r p B s s t C Q P D D q D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D C t q q B O u C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D s C u P u q s q C t t s v t B r C D q q B B B D D D D D u q q r O r t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C u q B C B u C D D D P p q t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B t q q P s D q D D s t u q t C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B t q u f - y ", +"% # R t u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D t D D s S O D D D D D D B t t D D B s D B D C D r D T D C P u D s t w O D B C D D D D D D D D D D D D D D D D D D D D D D D D D D B D O B r C B r u C D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C D D s q q v C B u q t q B q t s D D O t D q B B B B D D D D u r u p r P C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B u t C O t 7 U V W X C s r u t B B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C t q P D 1 W n _ 3 u u q t C B D D D D D D D D D D D D D D D D D D D D D D D D D B B D D D B C t u s f - y ", +"@ & R t u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C r q D Y Z ` ...` +.@.#.+.$.D D q D D B C B C D C S D r O D D C v %.y &.B D D D D D D D D D D D D D D D D D D D D D D D D D q D Q D p D C B B C B D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D t D D C t D P *.v O t t s C C D d =.M *.D p u B B D D D D D D B r u w t u D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D q C q -.r ;.>.' V ,.C D u t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D D B C t D D X '.). !.C B B D D D D D B D D D D D D D D D D D D D D D D D D D D D D D B D D D D B C t q M - y ", +"$ = o t u D D B D D D D D D C D B B D D D C D D D D D D C C D C D B B D t D D D t D D r p u ~.{.{.].^.h h /.$ (.B B D B B D B B *.D t D _.*.C B q D -.:.<.4 D D C t D q D D C D D B B D B C D D u D D B D D B t D D u D P C j *.v q D B D D C D B q D D C D q D D B D B B D t D D t D D t D B D D D B t D D D D D C D D t D B D D D D s q s _.q D w w q r D q B 0 #.[.l D -.s D C B D D B D B B D s B }.w D P C D C B D D B B D s D D C D B D D B D C B D C B D D q D D B D D B D D B s O q B D C l [ |.;.D D s B D D B D C D C D D B C B D q D B C D D D u D D D t D D B D C D C D B D D B D B D D C B r P D D _.v q 1.+ 2.D C D u B B D B C D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D B B D D D B B D C D D D t t D u D B B D u D q B D D D q q D D D B D D q ,.3.@.q D C C D 4.5.D t D D u B B C D B q 6.J o q t D Q r D p D D D D t D D t D D C C D D D D D D D D C D C D q D C D C 7.-.B 8. .9.u D B t D D D t D D D D D s D D B D q D q D D C D D D C D D D D t B C D D B D B t D D D D C D B D t D D s %.F i v D u D q B C B r t B D D D D u D D C C D C D C B D 0.<.a.t D D C D D t B D D D D C D B B D D D u D D C C D D t D D q t B B D D B C p v D X s t C k ..=.h D B D t D q D D B t D u D u D C u D D q C C t D D B t D B D B B D C D D C D B t D t D q D D B s r v t B D D b. c.D w t C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D B B D D D B D t B D B D t D C C t D D C D C D D s D D D D D u C C O B q ;.d.3.Q q C t B X q C D C u D D C D C u D e.' f.D t D C D B B B D r D B C B D q B D D B C B C D C s D D D D C D D D D B D D D g.# h.B u D t D D q D D D u t D D C D q D D C D t C B t D D C D q D B D D C C s D t D B C C D t B D D q D D r C i.=.D D C t B B t s v D B C q B D C D s D D D D B q B O D j.- 1 B D B B D D B D u D u D D O D D D D D D D q D D D q D C C D D D t D C B D D B C C D O O k.l.m.h D s D q D B u C D D B D u D B D t D D B D D C D q C D D D C D D q D D t B D B D C D D q D C B q t D t B B u h. n.D D D u C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D D D D D B s o.p.q.6 D r.s.t.u.D D p D t q D s D D D u D C D q C D O u B v.[ [ P D q w.8 t q D B D w x.y.z.A.5 p !.B.! C.D.(./.-.E.F.G.;.t D A.H.2.D X z.(.$._.D S I.(.J.s D D D C q 8 K.K.H.L.D r X A.M.+ N.O.s.P.D q t j p.y.(.e.D t u B D D r j H.Q.R.C 6.y.H.S.t B q B D C c x.x.t.i D D j 5.0.q.t.j D 5 T.U.V.V.W. X.Y.s.0.T B D q D 7.U.5.4 p D ^.Z.F.g.C 7 h.T.3 D D h t.e + %.s.x.a D D q u.`.(.U.g B t D n.H.T. +t '..+r.c.F.q..+/.D v ++t.A.H.D B o.I.(.@+#+D r D D 8...$+k D P t D B D D '.y.z.D.a. +t 4 A.q.T v H.s.E.}.D u D r D C .+1.x.g.D C u D C q g x.O.@+w.t C C s q C n.(.(.Z.%+&+*+D r B C D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B B D D D D t r p 0 V F =+-+E - ;+>+O D B B O t r D D t t u q t u B B D B B l ,+<.D q D W./ u B B t 3 m m.%.9 . ..;.Y.< ~ +.o E '+O )+I + 4 P S 4.G * p.!+o ~+ x.A.{+o C. ]+p C C ^+/+/ E (+_+. F.r P :+<+> [+R (+}+r _.|+1+2+R U X.*+D q p r q v }.9 &+# x.%+x 3+> 4+P r t X H.[._ f 5+m.2 t k.:.. < 6.s D.&+> @+H.x _+{.R 1+6+}.D C X D 1 / ! { ;.s +m. ..O.7+A > 3.S.C 8+9+ .~ 0+o 7+T.t w .+n :.E e =.a+t D D.,+ E.F.. X.1.[ {.b+r S O.) ~ | 4+c+( A L ;+~ H.t q D v.U =.k D D D C q r a.e / 7+=. o D d+;+> f.:+-+9 ; e+8.u P D 2 f+C.R / {.g+D u q B h+: |.L i+{ n.B w C ;.Y.# j+M : G *+u r B t D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D u p D t l 5+3.)+g B 0.' W.t r C C w B u S B q B C s D Q D B D B C 7.<.= 2+x 7+;+)+p C q p ~+_+q C D g+J k D k+> Y.B D D T D %+- ~.v s D c+H 2+>.D q C.G < G.C T @.,+].C C O. T.D C g.& |.p O D l++ t.D B D D w., m.u B -...d.b q C C ;.D B s ] $ M.k+D ^+K : T q D h+ m+B B w.& N.h t r A . Z.C D *+n &.D t s <.V D D u D C D r q D _.=.l.v.D D 8.#.G 6+].t d+~ %.D r D `.! l+q B D D 0.. /+t C 8.> V i C C U.= j.2+K.:.$ 8+b % n+t r t B [.| D A.. @+D D 0 % X.*._.t }...V k C D D D D w.&+E D B P 9 o D D U. ^ ++q D Q. %+p r t n+G j D q L !.q D u.@ C.D t _.e [ 2 D C o+ @+D t *.N > P.D D D r t B D B C D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D t s B C c @ n+t B O 7.' m D s D q D B -.s C B D D B t p D D t B D l } $ Q.!.h.d.{+p D D ^.5+<.'.q D u u.q C 2 ~ p+B Q t B *.q+_+R.D s C '+) !.D u D 1+ 4 D r B !+' 2 B w v.4+C t D *.e , ;.C D 4+~ f+D r C B /+* d+D P B F.&+x.D q D q q D *.r++.l D w t U 3.D D Q / ;+c D r t s+' |+D t g t+K Y 6 #.>.D D r p _+).r q C r D t B C B v.y l.g C q l = F Q D t ;.z | C D t f.H h+D s O S 7+% d D s t W K 4+D D F.* (+e.D v.r.g D [+- +D D 7 U r.s T L.S C D _.n+> u+r t u+..V g C C D r D 2.H |.v B C j u.t B x. n.D s C >+X.F +t 4 ; f.B t D k+$ A l u f.&+~.B Q D Z.+ /.C l l.,+S q D u =+- 2.D v t C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D B D D D B O D e.$ 9 r r D 8.G C.Q D t w p O B 7.<+ .i+X.v+k D s t B C B l +.,+t C D j.W P C q u (.+ } w+l D C t D V.+ q+B s t B Q :+% 7 D D s s+} g.t C q 9++ 7 D D O %+; l+B r B D ;.D t B : & u+s C h+ b+D D u g F ` 6.D t t V.. v+D _.r D t q Q $+i.*.s D O n 3. +C ^+$ N.X B D B /+ E.D D B w.e K V d+D O q C 8+3+: S D B s D O D s D j V [+u+D C u+z ).P B P s I U B O D b+ g.t D B '._+j+_.t B D /+> x.D D $.% @+D D D D D B =+$ (.B D }+N.i B B D p q t D x+> 6.B q h i+$+*.D D D C C p 9 r+5.*.D D u D y+ 2.D q -.-.9 H k+D L @ #+D D B ,.z+<+O i +.U u.u D D $.! f+D V.H R g B C D g+ G.B C D t D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D B D D C u X q ]., : u s B 8.> x+C q t s q O D u.@ ! ! B.l D C D B t B h +.#.O r D X _.D D r t C #+~ % & c+w B C L.% p+B B D O q W.K 7 D B C s+@ h+D u C A - 0 q D q v+H 7 C C C P 7 i.3+3+= @ ;.t D n.+ s.u s v g N > <.,+d.z+{ - [.C C q B Q v w [+#.;.u B s #.X.r B 3 3+- @.<.;+<.{.) w+B q u B S. m.C t u B r j 5+~+O t t D D Q D v D h i+n i u D u+,+t+P C v i [ C.C t C m++ P.p D D l+% ; ,+[ z+d.{.) m+D P A.% D.q Q D s P D u+K e+D k...y.C D C w 6 X.<.,+= &+h D s h e =.h D B B B B D Q W.* z G 2.t C q b.) r.u t D T ^ + 3 D A+. z B+d.3.#.= #.^.h j+&+,+[ <.d._+# A B A. b+D u _.D m++ P.D u P v B B D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D B D D D B C C D t ].@ ] u v D g ) N.q D u s B D D r O s r p t C s D B D r D i @.3.P -.B r t _.l B B r r t q.3.> w+q D J. W.D s u u Q A & |+C X C m+I ++t D D C+H *+w B B W ! 6 D u >+; N.8._.r _ . k.D B 2. }+t t C S e l.,.Q v S X v D s t D t B C p n 5+h D q D J ;+*.C c = L Q s 8+q P *.B O s D g / $++ 7+s s C D P d.$+t B w r B D s D B ;.N n _.D t v.d.0+;.C D _.; F D s D W. b u w B 1 , :._.q s O q T S B C d+H /.P D Q s r T q 9 G ,.A.t+i D S k.; V u+O r 9 $ u+T D u+r+C._.q D D D r D p u u q+$ K ++D D }+ !.D P C p M z g.t 6+@ 8 r i g r Q q D ,._+m.;.B P O O X T D 0. )+k D C C Y. P.q D q q D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D B B D D C C B t D d } _ S D C k.= t+D B q D q u B S C D D B t C t C u u D B i <.} C B p u C W.9 T w +D X D }.` F T D &.! !+D D C D t '+= ~.D u D b+$ g.D O t {+' a D w u W > 5 t u K C.P C C C D+;+S C D L.. m+t D P s R z a+D t p D D B C D O s D D 7.e+ .l D s u n , D D j N V v.D C P D D P D D -.=.y+D R O.D C D S _+).w q B D B B C r D v.n i+,.B C }.E+2+v D B ].d.V t D t }+' !.C D D w.$+D+i B r D q D D D q 5.% E.B r B w s D s c.&+)+A+Y.D u D J ` B q q C [.~ ^.D D }.r+V i C D t t r h l q O C L.. :+t q @+ L.D q D >+B+..u+D F.; T.t D s D u q C ;.(+3.k.C C D P D u D g.' ] _.D D D :+ P.D q s C t D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D B B D D B t q s D k.- x+t D D 7.; =.D O D B B D C D D C B D D D t B D p q D -.B+` t t D t *.[+^ s &.$ 0 D B ;.E+] T B k+. n+p C Y i t C+# |+C r t c+I ~.t D D %+& u.t D D o++ a D j = .C D C 5.` # w C D #+> ( u D r.-.r.# C+B D D C ~.a C u v D u D D i+e g s D D J K B t C Y.+ s.t D D q $.v.D r o+1+B P g 0+& 5.u C X ..K d B e. +u B q T t g F X.u C D -.,+e+r B B g ;+..D u D s. '+D O ~.v 1.+ ]+D C D -.5.u+q D q.# @+C D C D C t u w.X.+ :.-.C P w 3.+.D D D >.@.) S t t k 5+[+;.D B s D s s+y Q D D r. j.B D g+~ o t D D D. j.D B ].i.V ;.C D t ~.4 s C P.! !+D D C u |+5 u v :. 3 u C d U h+t s u B C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D B D D q p t ^.M &+; @+p >+Z &+ g+D C C D D t B D t C D q D B D p v C 6.R . 9.q+4.o+[++ 9.t o. & f.q+0+$+4+D B v W ] o+{+^.@+' ~+0 s T.z + : 7 D t.I ! _ d X p.G + :.u.C b., v+9.s+j.N f +D -.F+ 9 C+I.u+D H._+B.o+f+9+W T.q t s P P T 4. ! 4.S j )+ + R _.D -.9.G (+W.W.W )+ +2 Z x+].O ~.=.. g+v.S T.> { f+9+'.r C P C 7.9+> o j -.< &+b+P i R K.w B +0+~ 7+C+h.D l W {.%+q+W.C+9.d D V.3.. .]+p C -.P B p B g+ '+u D t t '+K E {+!+I.: . ] w.7.A++ &+4.j D X B D D.+ [+f.p+ .L e.D u 9+& 1+f.%+ .A v.s D t h+....4.y+q+-+z.X D p h.} B.f.f+s+C+T.u D l+5+_+9.W.Y.< . C.~.-.P s C C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D C B D u Q u }.=+I.g+Z.Q '.g+@+j.y.s D B t C D D t D D B D B B D s p P w.}+h.`.W :+{+s+b+I.7 p q ]+j.p+y+b+o.D O q C k U.o+6+g t E.1.h.c+6 B F.1.K.w+l+u a.g+g+b+0 X 0.K.s.c+1 u B A.o+p+s.Q ^+K.:+,.u t k F.s+o+S C q q R.s+9.o+O.v D P u r O u X D.1.`.`.,.}.`.y.y.f.*.s O q 0.'+!+p+z.B D 4+4.s.b.^.w ~.c+O.1.y.v.C O q.Y.f+^+D q O D C u+x.h.j.:+*.l c+h.h.p. +*.1.h.O.K.s s t }./+'+1.C q D D A.4.4.f+E.D C t 2.Y.p.}+U.p D P g v u u a+H. +O q _.t s 2.{+y+x.O 3 Z.b+ +}.g+K.g+p.u+P P C s 8.`.}+4.W.b.r D _.D `. w+c+f.W.Q.D t B t -.D >+w+9+q+4.6.D u D O D S.f+f.p+/+q q p q D 1 g+9.4.3 ].`.:+g.X P r B t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D B D D u v D D D D D D r D B D D D t D B D D O D t D B C B D D q C r s C D D D D D C B D t D D Q D t C D B B q B P O D B D D *.D B B B D C q D D u D D u B C C D t D D s D D D B q D C D D D t C D -.Q D r B t D w B P P D D q D D s p D u D -.C t u D t D q D D D t D C p s u D u t D B v P D t D D C u D D D C D D T D q D D s P C D C q D C B B D B D C D t D r r D C t D q D C t D D C t P C D q q D t t B D C D D D D t D O t t r p t C D C P r D D D B D q D p r D C C D B D t B D r w D O B D D D t D r T u D h. J.B D t C r u C s Q C q q D D D D q t B q t D D C C D r q C u B D D D D r B D D B B D D D D D B C D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D B B D D B u O D w u B r u D C t D u w p D D C t D D D D B D D D t D O t s u t p D t D D B P u D Q D s O C s O C p t q C q B D T O B B p T q u t C r q s t D C q B C D t v q q s u 8.t X C D B s P D v u q r D D q Q t t u O v r u D Q D D P t P s C p t q t r D u t D u O g D q s s O Q C t s t B w t t q T q C B r C q q q D t t q t C w v D C O s C q B s B D s q D D v D D q r C t D D v C q D t q D D p t D C s q t q C s C s q O q C s u D Q t D C B Q g D O p D q u C B r r B B D t q B D *.P D r r u O O C u D q f.+ L.B u D B q t D t D r q q S P D w C u X q B C _.r D s D C u t D D C p q u D C r v C t D C D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D B q D u S X t q _.u u q t B D D D D D D D D D D D B B D B q s u t t q t t s u C C t s C s r s w p t t t t q q q u q q q q q q q q O t q t s p q q t q u u t q p _.B t u t t P S D t s P D q p P C q t t C C C C t q s *.s v D v Q D t u B t X X D O P P r q t u O q u s q B D B t O t O D w u v s s u q t C C B B r u u u q C B C B q r r u t C C -.t D r p q C s D r r s r t D u P u t t s r q B p q B B q r s C t t q t t t t q C q t r O t u t D B s u P u r u q r C s s C r q D q w s q u q S q D v w t )+ y.s q u q -.B _.-.q s O s t C u P B r t r t w s C C C Q u w D q D B t u q C B t u t t C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D B D s O u t q t B q q q t B B D D D D D D D D D D D D D D C t t C q u q q u u t q q C r s s P u O t t t C C C C C t t t t t t t t u C t C t u B B C B C B D D t s s D r C t P u C B D t C s q C B C C C C C B B B C B s D u D u q C C D C P u D s B t q q t t t t C C C C B B C C t q C u t u C C u q q t C C C B C B B C B D D B B C t q q t C C q C B C q u t B D u q C q B D t u t B C t q C D D C r O t D B C t t t t t C t t D s t B B q r B O O B t D s r w B q D t t D q B v D t q s -.P t p s D B b+_+{.d.'+D C O D B D t B C t C D D C t t r q s B s B D t u q r t q C C C t q q C B C t t C B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D t C D D D D D B B B B D D D D D D D D D D D D D D B D D D D B D B D D D D D B D D C B B t D D C C B B B D D D B B B B B B B B B D C D D B D D B D D D D D D D q B D B u C t D r D C B q D D C D D B B B B D D D D D D D B D D C D D t C D D B D D D B C C D D D D D D B B B B D t D s D t D D C C B B B B B B D D D D B D D B B D D D B C B D D B C D D t t D D t B D C D D C B B D D D D D D D D t q D D D D B B B B B B B B B C D D D D C C D D B D B D D D D C D B B D C D D D C D D C D D D t D t t D C B D t D D q B u D D D D D D D D D D q C q D C D D C q D q D u D B B C C B B D D B C B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D C D D B B D D C D D D D D D D D D D D D D D D D D D B D D D D D D B D D D D D B D C D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B D D D q D D s B u D O q u D D D D C D D D D D D D D D B D B D B D B D D C B D B q D B D D D D B D D B D D D D B D D D B D B D D D C D D D D D D D D B B B B B B D B C D D D D B D D D B B B B D D D D C D D B D D B D D D D D D D D t D D D D B B D D D D D D D D D D D D B B D D B B D t D t D B D D B D B B D B D D B B D B B D B t B D D D q D D D B C B B D D D B D D D B B D D D D D C D D D C D D D D D B D D D D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D B B D C C D B B t D D D D t D D D D D B B B B D D D D D D D D D D D D B B B D D D D D B B B B D D t D u s D q B C s D B C B D D D D D D D D D D D B D D D B B D C D D t B D t C B D D D D B B B B D D D D D D D D B D B D C C D D D D B B B B B B B D D D D D B D D D D D D D t D D B B D D B B B D D B B D D D D D D D D D D D D B C D D D D D D D D D D D D D B C D D C B D C t D C D C D C D B D B B D B D t D D B D C t D D B C D t D D C B D D B D D t C D D D D D D D D D D D B D D D B D D B D C D B D B D D D B C B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D B C D D D D D D D D D D D D D D D D D D D D D B D D B B D D B D D D D B D D D D D B D D B D D B B B B B B B B D D D D D D D D B B D D B D B D D B B D D B B B C D B C r D D s C B q D B D D D B D D D D D D B C D D D C D B D B D D D B D D B D D D D D D B B D D B D D B B B D D D B D B D D D D D D D B B B D D D D D D D D D D B B B B B B B D D D D D D D D D D D B B D D D D D D D B D D D D C C D D B D B D D D D B D D D D C D D C D D D D D C B B D D D D D D D D D D D D D D D D D C q D D C B B D B C D B C D C D D D D D D D D D D B D D D D D D D D B D B D B D B B B D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D D D B B D D B D D D D D D D D D D D D D D D D B D D B B D D B D B D D B B D C B D t D B t D B B B D D D D D D D D D D D D D D D B D D B D B D B B B D D B B D B t D u r D t q u C u D D D D B D D D D D D D D C D D D C B B D B D C B D B q D D D D D B D D D D D D D D D B B D D D B D B D D D D D D D D D D D D D D D B B D D D D D D D B C D D D D D B B D B D D D D D B D D D D D D D D D C D D D D B C D D D D D D D D D C D D B B D D C C D C D t D t B D D D D D D D D D q D D q C D B D q D t D q D D B B D D C D D t D D D D B D D D D D D D D B B D D D D D D D D D D D D D D D D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D B B D D B B D B D D D D B D D D D D D D D D D D D D B D D D D D B D D D D D C D C D B B D C D D D D D D D D D D D D D D D D D D B D D B D C D D D D D D B B D D D r B B B D t D B s D B B D D D D D D D D D D D D D B D D D B D C D D C B D C B D D D D D D D B D D D D D D D B D C D C D C B B B D D D D D D D D B D D D D D B B D D D D D B B D D C C D D B B D D D D D B B B B B B D D D D D D D C B B B D B B D B B B B D D D t D D t D D D B D B D C D D B D B B B B D B D D D C D D C D D t B D D D D C D B B D B D q D B D D D D B D D D B B D D D B D D D C D t D B D D D D D B B B B D D B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D B D t C B D D C D t C D D C D D D D D D D D D B D D B D D B D D C D B t C D B B D q C D D q D D C D B B D D B D D D B D q B D D B D D B B D D D D u D B C D B B C s 7.#.t.s B p r B B D C D B D D B D D q D B C t D t B D D D D B C D B D B D B C D D B B D t D D C D u D q D B B D B D D D D B D t D D B D B q D C D D D D B D C D D B D B B D C D B B B D B C D D B B D D D D C D D t D D C D B C D C D B B B D D D D B D C D D D C D D C D D D t B D D B D D t D C B D t D D B B B B D B D D D D s D B C D D C D D B C D B D t C D B D B D B D D C D B B D D D D D D D q D D D C D D B D D B D D C D D B D B D D D C D D t B D D D B D C D D C D D D B D C D D D D B C q u M - y ", +"$ = o t u D D B D D D D D q r u u O D C D B t D B t s q D D D D D D D D D D D D B t t D D C C D s 5.3.#.d._+% P.D D C C D D p q D P D r v D B q D s t P j D C p u D s D O s q q D D P D D q D u D D U.& b r D D t D t D s -.D v P D w D D C D D D s D ;.u s t t D D O r D C t q s q B D u B q w D t D O t D q B C v D D r q -.D q r q O D t D D q D C u q P C C D B Q D w q D D q w u C (.= =+D P q q r B v t t q Q D C r r D D s D B u B D w t B r r D q P t C v B C r C q B t h D P q D B B C D t D r u t C B q B t D t r B B q -.D C t q t D r u q D r v D q q D B t Q D v u p F+% >.t D q v D s v D r p C s D u D C C C t u P B C q O D q B t v D D B D D P O r B C w D r t C D s O D u t D D D D B C q u M - y ", +"$ = o t u D D B D D B D D C r X p D p u q O D v D D B B t D B D D D D D D D D D B t C D C q C u %.U k s B y+* b.r S D ].}.D u O u B u X t q C D r D k -.D t u D D w C u q r e.S *.D B p D r D D q O j+~+S ;.Q D D t q u t s t t s c w s v _.D r u O q q D s w r B v r B C w u P D s s C p u q q t t B v D u O P Q D D -.s D D q s s D D v r D t u C P u D q t Q -.C s t t _.2 v D B _.D q...E.r D O D u B B P q O D u t D D -.D r w w B ;.u C B O D u p D u C P D t B r D *.p r D O u B q P t C r O Q D D q O D O C q v r D Q u r D s u D t D r D ;.q w r D p D q r ^.^.B P D Q O =+F R.D D p u u u B C v s P C w D v t C s v D D q P t D X P B D D -.s k.u+r s D B g C C O B t q C -.D s s D D D D D B C q u M - y ", +"$ = o t u D D D D D C B D C r C D P D t O D O C B s B B B D D D D D D D D D D D D D D C r r B 7 G b.t q Q D V v+k D ,.+.| D u C C u C v D r O r s C s C O D s D r P C q C 5 ! '+D s P D B q t q D 5 ; Z.u D D t D X B u t s D D p.' k+p D u C p D X -.t v B C C u D v r Q D D B r C q -.u D t D O t D t q w D D D D p D D t q p D B u P D C t D D C D v t v r p B P B C X %+l.w C u q s D D u u r P q s w t t p B P t q p O B s u q r P D -.D -.s s D D v D D t s -.P D O D D s D u P C D q p B p D C u v B D q C t t s p D C P u D Q D t O q t p D t O u O B t D l J j+p u u v q D C O P t q q B P t Q D r D D C X u D B D C t C s C j B q r O D v s v.{.o D C q s D t u C t q C t D s B D r D D D D B C q u M - y ", +"$ = o t u D D C D D D D D u w q r C s B D C D B C O C u D B D D D D D D D D D B D D B q P O C I.% ++D q B C t.!.D t ;.& 7+D D D p u C t t D D t D s w D u u D u B D D D B c.- 2.C D C D D B t D D 9+<._.P p O D C u D B D C t D 4.~ }.t t D P P p D D s D t r s P q D D D -.t D C D s C r p t s q B B s u B B C B B D D D s D D D C D C D D s u C D D B q C D D t q O D D F n q u D t D D D D w u t D D D B C D D D s D p D C D v s C C D B Q D B Q u B D D C D P t u B D r D w t s D D C s C u D q B u D D t B q C P p r s s g D B D D B v q D D O D C D t B D C i ; %+t D D D D C D B w C D D B q C D C B B r C D t t D s D D p t B C D B C P O q D }.I F+B B t D s r C t D D C u s q C q C D D D D B C q u M - y ", +"$ = o t u D D D D D D D D q O D -.D c !+-+F+:+H.D s B B B D B D D D D D D D D D B C C C u s t >. ( C B P u D D t K.] #.!+7+I.T p D r.L L {+]+D C B a+6+c+d+D k.c+b.L.c+..! e+W {+p.C D C D B v.@.E C D u q r a.6+A+4.=+ +^+9+<. A R {+g.t D C $.-+v+F+2.D B s ;.p+4.Z.D h+A+F+Y.D B X D D D t s w B D D h.F+E f+:+k+q q D i q+A+o w+P D Q q q.W s+>+D 7+v+m+6.D p d+L K {+6+W.6.t.C+m+6 i s a.6+s+d D {+L j.h s B }.p+m+0.Q C e.p+:+.+Q u u D q 2 !+(+F+y.D C q Q b.p+p.X u *.b.f.p.k v v D u+{+C+v+f.q.w B D ;.u q X t D b.(+F+y.w B p s t ;.F+%.A :+p.Q z.:.~ [ F+-+/+^.h.9.I.c p D I.:+Y.X r W 6+/+h D v W v+D.v.u X q D D 8 %.7+W y.*.C B I.).. l.F+-+`.u t t S q+-+F+*+D v D t r q D D D D B C q u M - y ", +"$ = o t u D D D D B B D B B B r u P...Z Y.%. D+s p q D t D D D D D D D D D D D D B C B C q C k U + x 1 D D O t X $.{+&+N g+1.@+O |+f 0+j.m+.. I.t u 8+A f+G.[ + :+t.^ * _ y.Y.2.D q B q D p.{.g.C r t _.g+#.q+g+j+ :+7.y.i+' 9+Y.1.7 D T y+B+9.j.1+> I.*.D Q p.' & W.4.g+E m B C D t C D s r C e.( [+c+K., .+D r t.D+N.j./+ B.0 r P L.N + W.^ s.%. j+e.B 4 '+3.+.9.I.h.8+~.Z g+D s J.$+ 9+m x.{+ M h D i y+ N S D ,.s+ J 8.C P u @+_+R I.!+ f+'.q w q.&+ 6.C j s.* H w.u t t.~+9 j.F+! 5+T Q D C B v q 2 (+).j.W $ f k t D r.j+B.j.}+ _+k /.!+* =.Y.g+E.k F.r+&+G.B D ++i+ '+E I.| %.m+C+}+%.! R Q C r 3 %.n+c+`.[+ w+-.w .+!+> r+`.Y.>.T t r.).E Y.F+[ y+D u g D D D D D D B C q u M - y ", +"$ = o t u D D D B D D D C q t s ;...[ w u D b.: s u q r D C C D D D D D D D D C D D C q u u C s ].<+ #.R v.D q C B e.&+%.D B B D D. Y D C l+G N p C C v.z+t+-+.+5.> `.D d+ d+C C B p D u u C ^ ` _.D s D P.+ o+B B i :.b+B D W ; c D B B D g+ Q.D D P | + (.t D D r+, p.h D O E q.B D C D u C D ;.m $ 1 D q V.. /.t &., y _.C D G+. 9 C O D 5.+ :.q.D D A+&+V.D D B =.n t D D C t J.I 1.D O D U.> j+G.t B f &+r.t D D B+n s t D X [ m.i B D 0. y+D t B q+. y+t B B m , ^.C D B _ E+^.C w [+3.Q D D t.e+Q t u O B B t ( I u+D D H. '+O s m , k q D E.D+8+D k > A t D D C D b.) #+D q D D.) ( 4+D q E . o 3 D D j+K 0 C B c. E.D q ^.@. .g q D u.. f+B D B r }.{.C.w D B ^ $ c.t s t t D D D D B C q u M - y ", +"$ = o t u D D D D B D D D D B B i d.d.1 B t w }.t B C t D C q D s t D D C D D t B D D t t C D Q q _.$.! z+g.D D D 0 @ (+q B C w ;.}.B t D _.i+& _.u D e.{ % l+C D c j D $. z.D D D r s D t l+= >.C C B u d+ m u t t Q T D D v++ 2 q ;.D w.` [ h D B p e.% j+T D r U 5+O B r t 2.I 6+w B D B D s v 3 ' %.B p q s o.i u v+@ /.D h s q |., 1 D r 0. =+D D C G+ p.t B r l.5+r u B D C G.' y.B B D H.+ y.C q D F. a.C B ;.5+n P B D g 5+m.u D _.0+= a+C w D ^.#.U >+D D :.} 7.r D C Z _+k.D X X.,+4 D D s h q r t C q D u., f D q D S ..e+T s ~+# #+B D u l q p }.&+x+q B D D q Y.I n.D B D y.I ]+D r D C+ G.D B D O.+ L.B C O o.C q D -.0+# w.B D 6 &+F+C B D B $.~ /.B D B c., W.D q q C D D D D B C q u M - y ", +"$ = o t u D D D D B B B C t u w S q.> H | ^.u D D p B B q u D 2+{.; - i+^+u q B B C B D D B C C D t D S m+ H u.B D 8 + %.B B D P D D u -.g i n+;+h C D ^+y ).;.D D C D s A.&+@+C B p t B q D o+K ^+D D u -.S M > I x.u u D C C F+& 4 C D q 4+! %+X q -.D 6. .3+1 D *.[+i.i B C t 3 } ^ C D C u u D D b.! g+D D u p D B v $+_+&.D D D u h.z g+B D U.. /.P s D D.. 5.D P X y r+u B P Q D >.I p.C r D A. >.s C t 0. A.D B v [ F _.D C h ` C.v q &.; _ ;.D B q _.t+z a D t m # e.D t -.j+3.u+B q 0.= ' / h B P C P w t C D :+; x.S ;.Q c B+ .'.C *+; > N.>+t v D r 8 &+-+D D w p C s+@ V.C -.D Q.K q.B B s I. *+t B q =+* c.D s w D D g k X / + '.D q 3 . 9+D D q ;.j+% $.Q g Q 2.~ f B D Q Q D D D D B C q u M - y ", +"$ = o t u D D D D D D B t u r D s C 3 #.$ . -+-.C s B s D q t ] i.;+z+Z d D s C t q t C t s O u D r O s B j.) q+w D d > o t O t D P +c.i.+.` > z 6.D D '.X.j+*.C v t D D $.. Q.B X B t D D }.l.j+j D ;.D u D D '+d.; z 5.r D D 9+* &.s t B q.! | v B q u l r+{ '.q D l.i+t r p D a z 2+r r D q D D D j+@ ~.q s P r O _.w U d.a+t C B O b+& U.q D 5.+ .+B t D A. y.B D ;.5+y r s D r B 4 & b+D u D `.~ a.P q D .+! ]+C -._.i+e+Q O u ;.l.0+Q D 8 = [.l C D ;.p L G l+D D t+G i B O t m G 8+D D D b [ G + x X X C D t t t j.! 3++.[ ;+[ F ,+ +D s d e+& M.k q D o.; (+u r D O C U. >.D s D y.I ++D q D c+# T.D t t m+. c.C -.D 6.V.X.+.i.# = ^.t D 5 * !+r p u r ~+K .` #.d.{ ` N.p v *.C D D D D B C q u M - y ", +"$ = o t u D D B B D D D B q s r D D s D S.C.+ 4.O D u X s t r B D D D t C D B B D D D B q q q a+,.v q D t l X.t+Q D o.> o B t C r J.. _ s D D Z E+i O t 6.i.] S D C t u D 5. 5.t B t p p C Q.! E.D B C t B q D B t I.3+E+h+D D F+. 0 P B t ~.H ^ _._.D D a+[+} '.C p ..3.v.B u q k+3.] v D C D C B q A @ !.D _.C X u B h t+} k+D O B D f+- U.D t ]+ D.D B t 2. Q.C B t i.r+q u s B u *+- z.B D D U.! y.D B D 5. U.C D Q ` J C q D ,...m.w C e., e+k D q q _.( 3+P.t D ^ _+k.r D v B.z o.C u D _.D b C.* 9.O t r t r D p+# 6 q C D D t D D C D C D k+: &+o g q 8+&+M.D q t D q g+& Y q q t g+; G.r C D b. h+u O t '+% >.B B 4 = V D D D W 0 D u l+~ %+D D S u n+B+-.B B D D C B D s B s D D D D B C q u M - y ", +"$ = o t u D D B B D D D D t u D ^.5 D q D _.z+r+D t O D B D X D O v C q D C D r u C t s r u C B./ t r w D +[ %+w u 8 ! 7+q u B v } <+D C D C N ) O P P }.+.~+S q t D t t >. ]+D C D u q D : +.,.D u P D C b l D B C #+ b.D D %+ 6 B r D 6.r+I 1 q u D d | *.D -.X.U 8.D Q D >.~ y+D p q D s s D .+ b+B D q C t s O :++ :+q D O C U {. +p D 0.I x.u P D .+! Q.r C S X.n p B D D D L.= /+D r D Q. (.D B D F.+ E.t u *.#.$+t Q D h d.V u r *.( . 4 B q _.w ; J T t q ^ ;+>+w D S 2+@.o.D *.P.B D B X X.@.X q t u q B 6 ~ {+D D p s t D D S #+D -.D r i+d.k D a++ / B s D D u y.H /.D r D F.I /.D q D g+~ !.q B D }+ *+q v { +.O q D q ( + ].D q 8 I | D q D q I.= J.D P C u B D w r p B D D D D B C q u M - y ", +"$ = o t u D D D D D D D B t q t J.{.|+B t ^+G | p s p r t B B t B B B O B t u C B B B C B B D 7+3.V.B D D s+! ~.D D e.@ +.h t G+u.* #.D D P O.+.= S D D l ;+0+;.D B -.C D ++& ( D B p.w D >+@.{+w D C q q D (+|.T u D F. $.D D y+ x.D T T.D /+ ] D q D x+= 2 B v D { - !.q C v i+= +D w B C r t D k l.= d D u D m+d B h+E+ .o.u D >. }+C r B 0. F.D P B F.! E.D D Q ).> Y D r.J.D d+# 1.D u D p.! $.C D B E. .+t u v t+&+1 C u+m+E+X.D D B L.> m.O D B q+ J.D r D -+ 0.D X @+3.&+-.B 0 * L.D B u+& 1+p q t q w Q _.Z ;+u.t t D k+`.S ,.{.0.B D j z+D+X O }.3.B+8+D a.c D :+I J.D p D h.# T.q q B K. J.D r u `.&+4+t t e G B D D x.[ % ].t C u.K l.i D !.8+d 3.<+O q D D H.L.r P D u D D D D B C q u M - y ", +"$ = o t u D D D D B D D D B t D '.+ B.m 3.9 >+u D u P D r r O D q u B t D q B C C t t t t t c. . B.M n+[.Z.p t _.O z. 5+m W.7.@+z )./ x D.).! <+o.k.n + &+=. +t q D B k %++ C.< K.t B g+, r.D O D D s B w+! ./ 0+} h.g D P 8.n 0+x+G.s v (. m.:.N 3.J.D t q C [+; ) j+B.e [.*+D _.D B D O r O D k+=.K < ] M.o+o.D D 6 l., x Z > s.Q u D d+_+. 3+K.u d+z E+!.t s k+K E+: {+&.D.{ + , h.D .+% . K q.v a.E++ G T.D u 5 , _+B.-+U.G . :.w.B p 5.# e B.).K #+t q D q ^.{ % m M.E.[+> V 5 v. . :.M X.| 8 D r v r P X D e.B.# | Z ^ %+D.T _.! :.9 e <+&.O D q F. i.B.s+^.p+$ ! [ 2.D t.% z+>.q E.$ ! i.!.P `.E+ } 6 X S.G $+( M E.x l.a+O T g+! l./ }+v.C V.r+i+B.( B.:+V.B s w q D D D D B C q u M - y ", +"$ = o t u D D D B B D D D D D B v r.c..+F.++k D D C t D B B C D D C D q D C D C D D D C t B D u 4+G.t.0.5.o.D C D q D D S.0.E.S B B 2 A.U.Y D ^.G+G+g S $.G.c./.k D B C D D g h+5.A.C t S V t+;.B t q D D B u+P.q.Q.Q.r.t D B q u 8.++q.V.D C C D 7 A.5.0.'.D B O r t C.d.d+5.Q.5.k.t D O C D t D D s D D l /..+q.!.t D u D D u+a.5.A.*+B C B D c a.L./.a t u.>.P.d+c D D D 8 >.U.].t 6 ++L./.S.D 0 2.c.++0 r 0 /.L.a.1 u D D u.a.U.k+s 5 G.>.g D D C ^+0.F..+^+u D B D B D e./.F.J.p w.c.5.u+w l+!..+F.a.*.B D D t P D D C D T ++Q.A.E. +B D u 6 G+A.5.T.k.C D t B q 4 5.F.;.D V.G.L.a.d D 8 2.L.q.1 D a 2.G.q.a+t k+$.L./.^.P D k+5.Q.2.B v.n.q.v.u B s *+T.F._.C D B k.T.F.0.t.C D q t r D D D D D B C q u M - y ", +"$ = o t u D D D B B B B B D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D B B D D B B B D D D D B B D D D D D D D D D D D D D D D D D D D D D B B C C C D t D ~.I @+D t t u D D D t D D D D D D D D B B B D D D D D D D D D D D D D D C r X =.i.D B D D D D D D D D D D D D D B B D D D D D D D D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D B D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B D D r D u F+` >+C u q s B D D D B D D D D D D D B B D D D D D D D D D D D D D D v P D X V ` w C D D D B D D D D D B B D D D D D B B B D D D D D B B B B B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D B D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D B D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B q D D B 6.{.(+B r s C B D D D t B D D D D D D D D D D D D D D D D D D D D D D D D X Q 0 ! @ l+S B B B B B B D D D B B D D D D D C B B D D D D D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B t D t O 4 i+T.B C q q s C C D D D D D D D D B B D D D D D D D D D D D D D D D D B D '.t+F e $+2 D B B D D B D D D D D D D D D D B D D D D D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D D D D D D D D D D D B C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D C D r B D B B s s C C D D D t D D B D D D D B D D D D D D D D D D D D D D D D D s D D B C D B D D D D D B D D D D D D B B D D D D D D D D D B B D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D B B B B D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D t B D D D D D D B B D D D D B B D D D D D D D D D D D D D D D D D D D D D D B B q D B C B D O u D C t s C C D D D D C B D D D D B B B D D D D D D D D D D D D D D P t t s C D q D B D D D C B D B D D D B D D D B D D C C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D D D C t q t B D B C C D D D D D D D D D D D D D D D D D D D D D B B C C t r t B t t D D B C C B B B B C C D D D D D D D D D D D D D D D D D D D D D D D B t q t C D t D B D B D B D C B t D D C t t C B D C C B B B D D D D D D D D D D D t D u s u Q D B C t C B B t C D B D D D D D B q C B C q q B D D D B C C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D C B D D D C u s O q B C q q B D D D D D D D D D D D D D D D D D D D D B C t q q O t C s r q q r B C C t t C C B D D D D D D D D D D D D D D D D D D D D D D D B D D D D t D D D B B D B D C D D D D C q s s q C t C C B B D D D D D D D D D D D D t D O D D P q t q q C t q t D D D D D D D q P C B t s s t B C B q r s C D D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D B B O D w q q r D D D C D D B B D B D D D D D D D D D D C D t O C -.q s B q D D B C B -.t u C D D t D D D B D B D D D q D D C C D D D C D D t D D D D q D D D B B D D D B B D D D C B D B D s q D v q C t C D D C D C D D q C D t D D v v s B u t s D t O s t D B D B D D D D D B t s O O D t B D u s D u D C D C B C D D D t D D C C D D C C D D B D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D B B C q r P D q D r B D D C D D D B C D D D D D D D D D D D D C D v _.D t C p q t t B u r q D p s u D p t P s D C D D B D D C D q D C D D q D D s D D C B C t D C C D C D B D u B D D B q D D D B g D D s D r O D D D q D D D t q D D C D D C D u D s O C q u C D C s p t C D D u C B B s C B C B S D C T D C q D r D C C D D C t B D D B D D C q D C D t D D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B B B D D D t s s D q p -.q D D C B D D D D C D D D D D D D D D D D B t q s u v O v.,.}.7.i P *.b e # 2+T D D C D C D D D B u D D D D D D D C D q D D s D B D D D D t B D D C C D D D D D D D D D D C D O O D u p t D t D D D C C D D D D D D t D v s P t w C D q j j t D q D D D D D D D D t P w u C p C B u j i D D q D D D q t D D t D t B D B D D D D D D u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D B q r D u Q D D O D s D D B D C B D D D D D D D D D D t D B v D P D v S.@.` { {. }+D q l {. .s D X P B D D C C D t B D D u D s D t D D D D D C D q B D D B D B D B D D s D t B D s D D u D C p D P u C r q D D B t D D q D B B D C D C C D C B B u D 2 H N i t t P D D t t D B D s B D p w B B v -.m.) l+q q t C D D D B C B D D D D D D D D B q D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D B B B t s u C q 4 1 D D D B C D D q D D q B B D D D D D D D B B D q v C '+- }.D D ~.} [.u+D X U J w D q u C D t D D C D D q D B D D t D r D D C D q B D D C D D D C B D q D D D D D D D D D D D t r u D S ~.}.C D B t D C D C D D B D B u D Q h+i s q r u >+9 o+w u D B D C D B C D u D v ~.d B B C r *.p+| '.D D D D D C D D D D t D D t C D q D t D B t B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D C D D B D D B t s D k.{.7+D u D B s B D D B D B C C B D D D D D D t q s s D k+z+C+q C B B W e+8.B T ..N P D O D C D D t t B u t D s D q D C t D D r D C t D u q D P D t B D q B O C D D D C C q O D t D D s C R. O.D t C C u D t D P s D C D D D Q.+ c.D q T D u D B u Q B t C C B p D Q D D w.3.A D C r D Q D D u B q O D C D C C D D C D D D D B D q C B B D C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D C C t r v u C 6.' 9+D D C u q s u t u t D q t C B D D D D D D D D q q r.; 9.w D B r u.++S s C ,+D+D q D B B C q q u O u D B D D D B q S B t D B B t D u D D B t w D t D D D q C w p D q t D D D B B D D 0. ++t D B P t q D C D D B s r D D p+~ 6.q D D t D C D C u B w D D D B D C u D 5 ! I.D D D r D C t D t s r q B t B B D q D r q D D u D t C u P C t C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D D D D C O p b+` * { |.0+b+u+t D P C D r p q q C B D D D D D B B u D D 3 E+d.8.D s p D C D C T [ <+B A.2+m p.v C t C D D 2.n+0+N.y+B D p /.m F+< 6+*.u D s.x +D T 2.] M.( 7 D -.p C B B 2.N.0+t+x q._.L 3++ l._ t+c+D D D j.2+t+< @+C D a 1+3.&+N 2+< >.6 j+E I.Q B s D a+:.|.( x+/+P {+ .$ #.2+B.C+a+}+9 :+8.D O u D B W 0+: ( | g.B D e.( m |.9 }+_.u O t C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D B D D t t C 4 s.* |.G+n.3 S s D C q D D O C u q B D D B D t D D q s B p !+ 5+*+B B q O -.B r m.z 2+b.G+N > V.p r D -.p+3.h.2.p.! m ].D 8.!+ .S.O q s N $.P s 6.< W ^.r r T t v m+..h.G+w+. x+X ~.R + 9+L.q.a -.F.y A+G+$.} $ T.B l 4+^ > `.c.>.o.k j.~ [+g D v .+#.W.G.]+' n 7.l+m+* M a.>.l+;.V. .# R.q C B v.U n c.G+n ! ]+D *+i.A *+d+K - T D P P t D D B D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D B D C u s p D &. q+t t D D D t C D t C D q D B C D B D D D B B r D s D X y++ % C.R.D u s q h F $ d+P B c } 9 *.B D x.~ j.B D B w+ W.r D k.;+N p C D h+[+ s+q D q '+r+v B v D C s a+& <+r D D /+L D C H. >.D D r S (+5+l D D q.I )+C B t }+~ 4 D t u D i r+U h q ;.F D+;.u D Z.E s D 6 * b.D D q s B %.K l+D r v D+i.j D B 3 & Z.q <+$ u+C q J.1+a+s C O C D D B D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D D D C s r q P c K %+D D u s s q C B T }.T _.i v D C B D D B q B D C t v q t o.N ! * f+P D C p @.:.h r D }.B+y r D h n X. +B D u j {.i.].B t 1+&+l+D B W.v+n+ .*.w _.x+g+D P D O q D }._+<.2 v O u p v D a. T.P u C B g S D s B >+ ~+B D B 9+! 5 t D D s i F 2+*.D k i.! 0.s t u _.B B h+ y+O s D t q )+I g.D B R.= M q t s u X q S Z ) a.O B P X u O u O t D D B D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D C D B D D D t q u D *+ C+u D C D D C D D K. ~ h.D D D D B B D D r k p B t C D C |+<. (.q q T U e r D u P U j+}.D o.G C.,.D r C *.f+$ 0 B B A.* o+s 6._ J.b+&+6 D ~.=.>+u s C t O S B j.# j+8 O D D D z. U.D D i P B D h o.b Y 3.Z C u D s+. 7 *.r C q v.U F S r B n.E+ N k+S B t D |+! c+C B D C X v+} 8 B O 1.& `.D D s B s q D Y ;+ F c *.D D O C P u B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D B B D D C B r B '.~ F+D D D D D D B C $.$+] =.~+#+D D D C D B C t u D C D C C B q D c , V i D -.5+n Q q B k 5+=.u D c . _ w B t D S t+I *+D D }.<.#.C 0.|.O 3 @ v+s 9+M.D t D u q D t t D Y |.# + o+T q D U. Q.D O O D ;.*+9.5+i+J F D B D f. g.s D p D ,.y y i u O C 6.|.3+~ 2+l B D S.+ 9+D _.D D Q W.# S.D B F+> G+u r t O D v u B _.^ { . =.l s t t P u B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D B B D D C C s C 4 ~ W.D p C s P t B D D D C D D D q B D t D D D C C u B o.S.P q t t v : 3.w.C w F n P D D S #.).T C 8.d...o.D r u w |.G 2 C u D 4.& 4+p+b+D t n+r+}.V a B P O D w u r C C B D G.n++ c+D D E.! E.B t u S L E+A.D C C I t+B t C p+~ b D u s r ^.{ n+,.D D B C D k+m ~ A+B D |++ Y.C D u B r C+I k+B q p+' d+q r r C q D s D C B 8+(+) ^ w w B s t D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D B D B t t O D a A+B B B u D C P P u D D D u t D C u D D B D C t r B j._+,.C D s X C.$+k D p z+D+B P q ;.i+n+*.D h N.+ G.D t t }.% t+S D D w &.> [+C+'.B C B.,+y+).v B t C s s D D S.V.D D D ].# M B C E. 0.s -.D G. =+C q D +' j+D s B 9. 3 Q q D r h [+y -.C ,.d+D q D T i...Q D J.. 6+D r B D -.6+;+l+B D *+* M C D B O D t w U.t q D D V 5+8+D t u C D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D t t r P >+i.5+u+D z.'.-.D u t D B D D B D D D D D B D D C ;.D D O.+ `.D D B K. t.B D O ` N k D B 8+[ m.D q D $.* r+_.D D L r.D B B w B .. E r r B a.~ B+T.B C t D u C q q q.I 7 D C g.; y+u D c.> |.B B I.L. o D D ^.M., n+q t D @++ L D p s.D ,.{ n X D g. /.D D o.; !+P t 3 3.[ h D (.8+D E 3.6 D q _.N.$ ~.B C D W /.j O.D t ,.` ~+v p p s t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D C q B O q 5. d.m.F.h O S T B D B D D D D D D D D D D C C r D t w.G ! l.=.y N >.;.D 8+[++ 9 i v ] + Z i D C |+z+d.C. ._+3 C D B P D -.q+' /+D q B 8+= z w D u t D B D B B |++ ; V y K b.k u C Q 9+ r+$+Y T :+H J U -++++.&+M *.s T ^ J B.|+k+y . $+7.k.+ + m.C.;+q+ +O T P (.; 3.e+]+7.%++ [ V.t D ]._ H C.y ^ D. +j ~ . N N ;+_ 1 t r C C D D B B D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D C t u B Q r 6.g.|+B r B q O B D B B D D D D D D D D C D C u T C D +4+5 g.r.a t D C v k+1 ^+d _.v c u.'.l+p P u D 6.5 ~.&.8.D r D P O D u T 0 ;.Q B r r 6.6.q t D D t D D P O s u.0 l+7 a _.C C O u X c 7 6 Q D q 1 4 5 k.C ,.2 d C B C ;.0 7 ^+D _.k+d c ^+P T 6.c 2 5 V.w q D P u w 1 5 k+P D 3 2 c a T D B D i b ^+c.6 D B C ^.u.l+3 ^+}.r C D D s C D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D B t D q O u C u D s q p q s u D D D D D D D D D D D C D D B q B s D D C D B C D r v t D D s r C t D r O D B O D v t D D s q q B D O D v O r C D C u q D D t s D u C r u u D t p D t D q D D r D P D D B D B t C D t t C B B D D t p C s B r t D q r D B D D C s C u T u D C C r D w u D B O r t D B u D -.g C P u D C D u u D X D v D C B D r v D q r t D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D B C O u D q D B s u D s C C t D D B D D D D D D D D D t t p D D D t O D D s D r X D Q q t t t D B C D t p u q C D B j r D q r D t B t D D C u D q B P t u t D C C C D D s C C t C t D _.q C Q q D q s C D P D C -.D D B D D P C B O D O D D t B B t D D r B t B X B C D p D u u w C w D q u D D t B p s B D D q t p s q D u D C B u t D t B D B t q t B D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D B B B D D D C B D C D D C D D B D B D D D D D D D D D D D D C B D B D q D D t D D C B D B C D B D D D t D t D D u C D r D C D D C C B D D D D D u D D s D D B t D B D C D D C D D t B D B D D t B B D t D D B B D C D D D u C D D C D D q C D C B D q D D C D D B q D t D u D D D C D C D D D t C D C D D t B D u D D B t D B C B D D D B B D B B D D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D t t D D D D D q D q D D C D D D D D D D D D D B t B D C D C D B D D D D D B D C D D B B C D B B D D C D B D D D D B C B B D D D s D t D B D t C D D B D D t D D u B D D C B D D t C D C D D B D D B B D D t D C D D D D D C D u D D B D D B D D t D D D u D D D q D D D C D D B D D C C D D D D D B D C D B D D D D D q D D s q B t D D D C B D D B B D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D D D C B D C D D D D D D B B B D D D D D D D D D D D t D D B D D C C B B C D q D r B D D C D C D C t B D C D C D B t D u C D q B D t D B D u D B D q B D D D C D D D u D D D B t D D B D D q D s D q D t u D C D B q D C B D D D D D C B D C B D D s D B C D C D B q C D B C D C D B D D C B B D D B D B B D t C t D D D D D D B D D D D D u D D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D B D D D D D s D D t D D D t D D t D D D D D D D D D D D B D t D D C D D C D D q D C D D B B D D B D C D D D D B D D q D C D D C D D s D D D B D C B D B D q D C D B C D D C D B B D D D D B B D C D D D D D B t D B B D B D D t D B D C D D C D t D B D D B D B C D D B D D D C D B D C D D B B D D C D D D D C D t D D D B D D D C D B D C C D t D D D B B D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D D D C D B D C D D B D B C D D C D D D D D D D D D D B D t t C D C B B D B t D C D D t D D D B D C B D D B D D q D B D B D D C D B D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D D B D D D C D D D D D B B B C B D D D D D D D D D D B D t D D D t C D D D t D D D C D B D C D B D D D D D B D D D u B D D t D D D D B D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D B B D C t D D B C D D C D D t B D B D D D D D D D D B D C B D s D D D D q D B D t D C B D B D D B t D D u D D u D D D D u D C B B B D B q C D D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D B C B D C D C D t t C t B D B D D C D D D D D D D D D B D q t D t t u D D B D B w D D D C O q s q B s B t D t D D t s P B S D u D B q B D D t u C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D B C O B t u P C s w u t u u D D B D D D D D D D D D D q s *.P 5 k+>+4 S.~.r.J.k+g w s C B q B r O r D C B O _.o.'.O v B t -.C D p q D t u q C B C C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D B C t B B B D B q s q t D q r B D B D D D D D D D D D D B D O }.9 l.N D+C.i++ {+T B C t r u r t B P C B D }.<.. u.B q s D B P q p u t B C u r t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D B C t C P r C C w p B C D B q t B D D D D D D D D D D D D C P D D ~+~ k.C D D D ] A O t q B C D t B q q D D s Q O.s+^.t r S 4 /.v D q D q s q C C C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D B t q t t D u t s D D O r C B u B D C D D D D D D D D B D C B O t N. 6.D p t D c J.O D q C t C t D q D p q D t t D C P D q D+J P s s D q u q C C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D D B D D P B t Q q C D D D D q C t D D t D D C D D t D B D B D u u D v m ; 2 B s t B D t t B D D t D B B D D B D C q D D Q P D X 3+2+D t D B C s D C r D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D B D D D D v D B u u V.=.e U Z.C q D q D D B u D D C D D D B D D D t u s ( > 6.C D &.9._.D D G.~+D+N F+S ;.f N U U.,.V F M.8+D b.X.~ I e ..9 c C D P C B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D B D D D C p t C g s+#.2.a+A.E+-+r t t u t u D u D D B D s D C D q C B P ~+> 7 C r h.D+X C u T g+. {.7 O B p.~ Y.*.P V.J E+6.C 7.6 @. .>+d 6.-.D t t D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D B D D D C r D u 4+ }+D B P x _+R.u D P C D r D D D D D D P q D D D q r ^ r+,+3.# V *.D r s D %.* 1.D s m I.u D C r m } o.D D T d.n+B t D D D D D B C D q D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D B B D C B t X )+G 2 D D B G+= x.D X D Q t q a+6.d >+}.v B O B P s D _.[.. &.D D c+r+S t t C B -.f &+!.%+E P D Q r v 9 3+e.C D T B+[+B C C u D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D B D B t D u i d. .O.++>.c.F+ | D B C D C u ;+ = k+B q t D u q s _ &.C q 4 }+D -.O t D u *.~++ 7+t q C D D 7.x+E+a+D D h #.$+t D D D D q t D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D B D D u D P ;.#.& ] Z [.m t+-+O.P u B B u t y+o A R c+k.C u t t u D O [.! o.D C D B q D w r X D s @+ _ -.D q P t v 9 3.a+C D _.@.=.D B t C C D D B D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D D r C P j U C.B D D B D D D D q q u B q B D t D D B t O D s B C O ( w.O r C B a+!.g u _.s I.~+w+ L Q D p D P B.E+a+D D i X.[+C D D D C B D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D B B D D t t D C O 9.I 4 D B u t D q C C s D s C C C C C C C C t C B D u q ^ w.O D O q y.d. +D D F.i.o.C 4.~ }+t D D *.: ,+e.D D j z [+D u D D D B D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D B B D D C q q w D +3.n T D D D < 2.D C u u D B B B B B B B B D t q q C B e++ l B C B }.J 5+u+D $.@.h+D B w r+' 0.D B *.~+} 2 B C w _ - J.D x.L.D v.C D P D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D B B D D B q O B q r c <+_+[ ,+i.n.h C D D D B D D D D D D D D s D D D +< * + 3.` ` .@. (+p :+I n+i D W.) H # C+6.( > + d.4 D C e.l.@ { m+*.T r t w C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D B B D D t O C D O D *.k.l k i D q D r C C D D D D D D D D D D C C Q O u+v.g l h l +i Q S D ^.*.v.T v P *.i ;.j P s v.i h i u t D q -.i o.Q p r C -.D r D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D B D D B q s -.D D r q D g t ;.q B D B D C D D D D D D D D C D D C v t C s D O D t C C D P D q t t O u D q D u O v s C D B u v q q p t O C D C D s q u t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D B D D D D D D C D s C t Q P q D B D P O u D D D D D D D D D D D D D B s D D B D s D t u D v r t v B u *.C t O O r D S r D r u w r C O q D D T X r P v t D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D D D D B C t D C s p s u *.D O D D p B D t q D D D D D D D D t D s p u q r B P t t s p q s S C t P O t u r u -.p D X p t C s r q C ;.u r p q O B D p O t D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = o t u D D D D B D D C q u B r D u Q O D t C q s O C D B D D D D D D D D D D B B s B t P t u C C s P -.s s C D D k C D s O D w r D r s s p s s q D s D r -.s D B q D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - y ", +"$ = L t s B D D D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D B C C B D D t t t t t t t t D D D D D D B B B C C B B B B B B B B B B B B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - F ", +"@ - o t u B D D D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B D D D D D D D D D D D D D D D D B B B B B B B D D D D D D D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q u M - F ", +"@ - o t u B D D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D B B D D D D B B D D D D D D D D D D D D D D D B D D D D D D D D D D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D B t q u M - F ", +"$ = L t u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D D D D B B B D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D B t q s 1+ - F ", +"$ = L t u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B t u s 1++ = y ", +"$ - o t u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B t q u M + = y ", +"% - + A B q B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D D C t q f + - J ", +"& I + A+D q B C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D D D B C t f ) r+", +"@ $ M 7.d >+1 b 1 k+1 c b ^+^+8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 8 u.u.&.2 1 b &.u.u+< > * i+", +"G E++ |.c.p.H..+.+E.E.E.F.T.0.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.F.A.A.A.A.A.A.A.F..+F.F.A.0.Q.d+|.> $ N ", +"= = <+++F.0.>.$.0.!./.0./.$.0.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.q.q.$.$.$.$.$.$.!.++a./.!.a.]+H.e+~ @ U ", +"$ - . ~+q.Q.T.>.0.Q.a.>.$.$.q.>.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.a.$.$.$.$.$.$.$.$.$.$.a.0.0.A.A.d+<++ ; i+", +"G I + =.0.$.T.5.a.a.t.E.q.0.5.0.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.5.0.0.0.0.0.0.5.Q.a.0./.c.2.T.=. & D+", +"K ; + ~+T./.q.5.J.l+V.G.Y h+*+V.h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+h+P.L.R.*+H.U.5.5.=.. % n ", +"@ # &+|..+q.++P.Q D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B B B B B D q B O n.>.5..+<+. = r+", +"@ - . |.q.a.T.0.q q D D D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0.q.0..+n+ = N ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D H+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+D D D D D D D D D D D D H+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D H+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D H+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D I+I+I+I+D D D D D D D D I+I+I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D I+I+I+I+D D D D D D D D I+I+I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D I+I+I+I+D D D D D D D D I+I+I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D I+I+I+I+D D D D D H+D D I+I+J+J+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C B D D B B D D D D D D D D D D D D D B D D D C D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D I+I+I+D D D H+H+K+K+H+D D J+J+J+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+D D D D D D D B B D D D D D D D C D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D I+I+I+D D H+L+L+M+L+H+D D I+J+N+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+D D D D D D D B B B D D H+H+K+K+B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D I+I+D H+H+L+O+P+P+L+L+H+D D I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D H+H+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B B B B B D D D D D D D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D Q+B B B B D D D D D D H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D R+R+H+H+P+P+P+P+S+S+M+L+B B I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D Q+D D D Q+Q+B D D D H+H+H+H+H+H+B C C B D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B C C B B D D D D D D D D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C B B B D D D D Q+Q+T+U+t C B D D D D D H+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D V+W+W+X+Y+Y+Z+Z+`+Z+ @ @t t U+.@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@+@@@@@Q+T+U+T+C B H+H+H+K+#@#@#@t q q C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B C C B B D D D D D D D D B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B B C C C U+U+$@$@t C B D D D D D H+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D W+X+X+Y+Y+%@&@&@`+Z+ @*@=@u -@-@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@;@>@>@U+U+U+C C ,@,@,@'@X+X+X+t q t C B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B C C C B D D D D D D D D B B B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B C t q q $@-@-@-@q C D D D D D D H+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D #@#@#@P+)@!@!@!@~@{@]@ @=@-@-@-@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@^@/@(@/@_@U+T+Q+C q :@:@:@<@<@<@[@B B B D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D I+I+I+B C C B D }@}@D D D D B B I+|@1@2@3@4@B 5@6@7@8@9@C 0@a@b@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@6@c@c@d@d@e@0@f@t I+J+9@g@g@h@i@j@k@k@l@m@N+N+N+N+I+I+H+H+H+L+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D n@d@o@]@#@p@q@r@s@[@t@u@v@w@x@y@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@z@r@A@B@C@D@E@F@G@H@G@,@I@J@K@L@M@N@O@P@P@P@Q@R@S@H+H+H+T@U@U@V@V@D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D I+I+I+B C C B D 4@W@B D D B B B X@N+e@Y@Z@H+B `@V@ #8@9@C .#.#S++#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+#+# #+#+#0@0@0@.# @K+V+@#J+@#9@##g@H@l@$#%#_@>@I+D I+I+I+I+I+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D &#*#=#U@}@-#;#>#,#,#'#.@)#!#3@3@~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#~#U@ #+@{#%#]#^#/#(#_#:#<#[#}#|#1#9@2#D@ @O+3#O+P+H+H+H+L+}@}@f@f@D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D I+D D B B B B W@4@B B D D D D B 4#5###R+V+<@Z+6#7# @8#,@.#P@Y+9# @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @ @C C @ @ @S+S+'@X+0#V+R+8#B B u #a#b#b#c#d#U@f@}@D I+I+I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D e#f#g#h#i#j#8@9@k#k#k@5#5#g@T+ #l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#l#5@+#@@@@>@m#n#i@j@H@H@o#p#p#q#s@j@r#H@5#@#E@Y+O+L+}@D I+I+H+p@p@D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B B B W@W@B B D D D D J+8#9@s#t#u#v#w#x#y#z#A#A#B#!@C#D#E#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#D#A#A#A#A#z#z#z#D#F#D#G#p@H#{@3#I#6#a@J#K#L#L#a@Z@f@}@D I+I+I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D M#N#O#O#3@P#Q#R#S#T#U#V#W#X#Y#Z#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`#`# $.$+$S#@$#$$$%$&$*$=$-$;$>$,$'$9@m@)$m@##I+K+L+T@}@I+N+N+!$w#~$D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B B W@W@W@B B B C C D@z@{$`+]$^$/$($_$:$<$[$}$|$1$2$2$3$[$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$3$4$4$1$3$5$5$5$5$6$7$8$9$0$a$b$c${@d$e$f$g$g$b@h$T@}@D I+I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D ~#j#i$j$k$l$m$n$o$p$q$r$s$t$u$v$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$w$x$x$y$z$A$B$C$D$E$F$G$H$I$J$K$L$M$N$O$t 2#@#V+H+}@I+N+9@9@N+p@~$D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D }@}@}@W@D D B C 8#D@{$P$Q$R$S$T$U$V$W$X$Y$Z$`$ %.%.%+%@%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%#%@%@%@%+%#%#%#%#%$%%%&%*%=%-%;%>%,%'%)%&@&@P@{@3#L+H+D D D D D }@D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D !%~%{%]%^%/%(%_%:%<%[%}%|%1%2%3%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%4%5%6%7%8%9%0%0%a%b%c%d%e%f%g%h%i%j%k%l%m%L+N+I+R+D I+N+##9@N+H+p@D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D }@}@}@}@}@W@D D B J+8#D@z@n%o%p%q%r%s%t%u%v%w%x%y%z%A%B%C%C%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%B%A%A%B%B%B%D%D%D%E%F%G%H%I%J%K%L%M%N%O%s@P%X+S@H+H+H+I+I+D }@}@}@D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D Q%R%S%T%U%V%W%X%Y%Z%`% &.&+&@&#&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&$&%&&&*&=&-&;&>&,&'&)&!&~&{&]&^&/&(&_&:&<&[&##N+D@L+}@I+N+##N+D L+D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D }@}@}@}@}@}@}@W@B C C 8#8#D@z@}&|&1&2&3&4&5&6&7&8&9&0&a&b&b&c&d&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&e&f&e&g&h&i&j&k&l&m&n&o&p&q&r&s&t&u&H+H+I+I+I+D }@f@f@D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D v&w&x&y&z&A&B&C&D&E&F&G&H&I&J&K&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&L&M&N&L&O&P&Q&R&S&T&U&V&W&X&Y&Z&`& *.*+*@*D 9@m@D 3#I#f@I+N+I+D O+D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D }@}@}@}@}@}@W@W@B t D J+n%8#I+#*$*%*&***=*-*;*>*,*'*)*-*!*~*-*{*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*!*]*]*]*^*^*/*(*_*:*<*[*}*|*1*2*3*4*5*@#I+J+I+I+I+I+D }@f@f@D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D 6*7*8*9*0*a*b*c*d*e*e*f*g*h*i*j*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*k*l*l*m*n*o*p*q*r*s*t*u*v*w*x*y*z*A*B*C*3#5#H@##L+Q@Q@3#D I+I+S@#@D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D }@}@}@}@W@W@D C D D@D*P$P$E*F*G*H*I*J*K*L*M*N*O*P*Q*R*S*R*Q*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*S*T*T*T*T*T*U*V*W*X*Y*S*Z*`* =.=+=@=#=$=%=&=-@Q+D D I+I+I+D }@L+L+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D *==#Z+o%==-=;=>=,='=)=!=~={=]=^=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=/=(=_=:=<=[=}=|=1=2=3=4=5=6=7=8=9=0=a=b=m@k@m@N+c=S#y#d=H+I+e=p@f=D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D }@}@}@W@D B B t g=n%n%h=i=j=k=l=m=n=o=p=q=r=s=t=u=v=w=x=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=y=x=x=z=z=z=A=A=B=C=D=v=E=F=G=H=I=J=(@j#K=L=c#+#f@}@D D D D H+H+L+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D M=N=O=P=Q=R=S=T=U=V=W=X=Y=Z=`= -.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-.-+-@-&.b #-$-%-&-*-=---;->-,-'-)-!-~-{-r#H@##f@P@S#]-H+N+##I+L+I#D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D }@}@}@B B D B t J+I+z@j@^-/-(-_-:-<-[-}-|-1-2-3-4-1-5-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-6-7-7-7-7-7-8-9-0-a-5-b-c-d-e-f-g-h-i-6@j-c@3@6@U@f@}@D I+I+H+H+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D j-V@ #%#h@k-k-l-m-n-o-p-q-r-s-t-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-u-v-w-x-y-z-A-B-C-D-t-E-F-G-H-I-J-K-L-M-5#9@D I#Q@]-O+N+9@9@I+U@j-D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D D D D }@}@D D D B C D I+D@N-O-P-Q-R-S-T-D*U-V-W-X-P=Y-Z-`- ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ; ;Y-Y-Y-.;+;+;@;p O D*#;&=$;%;&;*;=;-;j-j-j-c@6@U@f@}@D I+I+I+I+H+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D V+R+R+2#n%;;#;>;W-,;';);';,;!;~;Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-Y-.;Y-Z-v {;];^;/;(;_;:;{;<;[;};|;1;m@9@N+D {@~@C#O+I+N+9@##Q+U@j-D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D I+D D D D D D }@}@D B C C B B C X@2;Q+D 8#I+I+3;9@H@k@H@8@U+.@g@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@.@9@8@8@U+T+C C 8#@#J+######8@8@+@4@4@4;f@Z@0@0@f@}@D I+I+I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D 5;p@p@S@#@,@*@:@B R+R+K+M+{@6;7;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;8;9;8;G#0;a;a;b;K+C Z+O@S#I#I+H@f@}@~#}@H+S@S@#@D I+N+N+I+}@}@f@D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D I+I+I+D D D D D W@}@B C D D D D V@0@ @c;d;@#H+e;V@Q+9@N+}@U@}@I+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+H+N+I+I+D }@}@L+H+H+H+J+J+I+I+D D f;g;g;h;K+K+B D I+I+I+I+I+I+D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D ,@W+K+ @L+D D B D }@}@f@f@U@U@U@I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+I+c;N+N+H+O+{@{@}@I+I+W@i;j;!@9@H@7#c={@'@!$c;N+N+I+}@f@f@}@D I+I+D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D I+I+I+D D D D D }@}@B C D D D D k;Q#3#l;m;l;.#n;e#j-Q+D V@j-6#H+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+O+I+I+D }@T@T@T@3#P+H+,@,@D B 4@}@u#t&o;f;e=e=H+H+I+I+I+I+I+D D }@D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D U@U@f@U@ #>@.@9@##N+N+@@@@####9@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@f@}@}@}@f@f@}@##5#m@N+L+~@S+9@5#p;q;f=p@2#g@9@9@I+f@0@7#d=p@v#o;D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D B B D D C D D t D B C D B D D C D D B D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D q D C C D D B D t D B D C D D D C B D D C B D D D D D D D D D D B B D D D D B D D q D B B B D C t t D D B D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B C C C t D D D D D D D D D D D D D D D D D D D D D B D D D D D D D B D D D D t D D D C B D D B D t D C D B D D D C B D D D D B B D D B D B D D D D s D D D B D D C D D D D D D D D D D D D D D D D D D D B B D D D D D D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D B C D D C D D B u D t D D C B t D B D D D s D D B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B D t D D D t t t D B D O D u C B B B D B C B B B B B B B B B B B B B B B B B B B C D B B D D D D D D C C t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B C B B B B B B B B B B B B B B B B D C C D D D B C B t C B D t D C u D B D B D t D D C D u D C D B D s D t t D s D C D B B D D B D D t D C t D u B t B D C C B B D B B B B B B B B B B B B B B B B B D D D D D D D C C B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D t D D D D D p C D s D t P O D t u D u D D D t B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B D B q u q r u B q O q D D u v B t B B B B B B C B B B B B B B B B D D B C C B D D C D D t t X D C w t D B B D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B B B B B B B B B B B B B D D B C q u t D D t q O u t B q D Q B t r u D P -.D C D Q O v C C t C q D u s D q B B B D B C D q B u C B O D D t t u t D D t B B B B B B B B B B B B B B B B B D D D D D D D D C C B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D B D q X -.q D t s B X B C t s C q D D C D q D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D t D D q B B B t t q D r D s B s C D B B D D B D D D D D D D D B D D D D D D D t w t _.r D u P C D D r D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C B D D D D B w t D B w t v D C C B u t r s q D C s t u C C w Q s P C _.p D t u B D B D B C D D u C O q D D q P D D t u B D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D B D D t u t r p t t D D C D t P q D D C D u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C D t D u B B D u D D D S P q D r C D D B D D D D D D D D D D D D D D D D D D B t D D q D v.D C B B C D C r D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D t s s u w C r t q D v s q q -.t u D C D t q C p D O t u P r D s r D w r s B D D D D B D D q P D u -.u D C u s D B t D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D C D B q u P P C t D r D D q u t D C D u D C t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D t D t l -.*.r q s q D B D P s t D D B B B D D D D D D D D D D D D D D B t q w t t v u v _.j T D Q B B B D q D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C B D D D D D D D D O t D p D D t B D D w w D _.D D D B O O v C P *.l _.r P u D u D D D D D D D ;.D D _.Q S X l q O p D D q D B D D D D D D D D D D D D D D D D D D D D D D D D B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D C C B q p u D w 2 w.8 w.0 T X C D C D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D u D D D h M.- E+5 t u D w t O p u q C D D B B D D D D D D D D D D D D D D B t t t X s t O $.K . {+B D P B t u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C q D D C X h s k.>+w.d 4 ^+8 '.D t w D t D q i >+X v D s q T f.<.$ e k.B D g u D D B D D D D D w T D 6 y &+[.v.D D u r q D D D D D D D D D D D D D D D D D D D D D D D D D D B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D u -.s D t q 4 R [ U ..; + 7+u B C D t B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C D D T %.~ r.B u B D B u B u s u B D D B D D D D D D D D D B D D D D D D D C D s q D t 6 + %+D B r q C D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C D D D u r q D p )+& + z J U X.&+F.8.D q r -.D x U.D D B O t+A+D 6 < o.q C r q D D B D D D B v D C D C *.$+<.l t r s D C t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D t D C D B q t t D.K ( v D D 5 ; @.X D D B D D B D D C D D C D D C B D C D B C D C D t B D B D D C D D D D B D B C D D D D D t D D D B t D B b+. J.D q C b *+r u P s B D C D D t D D B C D C D B B D D D D t D p #+&.s t B w 0 H A D D t D u B D C D D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D t s s D B w+. !.D D B q+G <.c D s u t 0.E r.B q t >.I U.D t B C u u D r C D D t D B D r B p B D _.m. .*.D u s s q B D C D D D D C t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D B t D u u D 8 @ C.D D C D u q+C.j C D C t v B s D B D s D P s D D C D q D D r D D s D O D u B D u D u D D s t D C q D t t D u t B P D t O %+' k+u D O 0+#._.D -.q u D D D q D D q t D q C C D C q D B t D D 0 & 4.B q C D u. F+B q D q D D u D D B B u B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C C C B '+ >.D D D D 4+ l.v.D w S B u D t q D v+H 5 P B t s B D u P D p D C B D s B B w t B P m. ._.t u D q P D C D D u t D t D q D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B s D s 9+ T.t B D r u g a.v B q C D C P D q D D r v P D C D D B D s w B B C D q q B D C u D O D D B D s q D D v t u s C t B D q D D f.. R.C t D G V D D u r D s D r D D B D C q D D O u D D t D D P D P. y.D D q D u.; A+C D B D C t B B C q C u D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D '++ 0.B C D C _.n+. `.u r D D D D t C D /+> 2 D D u O C q D D C B w O r P D D C D t D u e+@.k D t C q t D D C D q q r s D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D C D D t r D k.,+K ].q t q C C D B D u 8 [+).j.r 3 m t+G.D B D t.$+ .).C+s D C s 7+e+:.7.r i 1+).C+a+B g.n |.=+D j.U e+y.D D u D D j A [+N ~+=.G 2.D Y. .; ) y J E >+%+0+x+,.O 9+0+:+o.x n+v+r D a+M.n+y+D T (+<.> d.D+$+v+B ~.> W r q+r+j+!.t D C t t D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B D D D D '+. 5.D B D D D p.+ :.O s R e+x+P.C i -+3.H #.y w+t D D x.F J D+s+t B D t s P l =.~+J B.{ ` g D s v D Y C.r+n+R Q D t D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D B B D D q t a z r+D q q u p v C B u D T p.. W @+} . g+B v.E d.0.7 (.> 0+}.q O b } E+o.r g l+z+$ 6.D S K.' U j+Y.7 n+, Q.D r D 2 D+i.4+7 ]++ $ R.D ^.4 K e 4 g.g.w '.F & d+_ . n 8.#+ [ X t Q 5.G n ;.p 8 h. -+3 ~.'.C u.E+` e+a.a _+;+5 t C C C D t B B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B B D :++ 5.D B t B s |+ < T u a+o F.q Q 1 |. @+5 +D k :.d.2.l+q.. N.u+D q D a.` t+g.6 < ~ ~+8.D D v W.;+K.6 >.+ J 8 C p B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D D D B t D |+{.=.g q O q D C B t D D D u+y } b+c >+E+O.u x.> Z.t D D z.+ (+D C D )., l B t D N.} ^.C C k.d._+V.P D ^+> y+q D ;.V = k+C D g ).z+a B t g #.V D B C D B '+z -+x.j / C.8+D ).y p s D ;. .X.g D B r.' Y.C D C D a+! [+>+D u Q.~ f.D C t q C s C B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D D D D B D B :+ Q.B t p D D 4++ r+k.q t Y.& /.D p D -+ 2 D D C 1.+ !.C D u '+. A t B d E+U q C B '.#.n j w u /.* W.C D D h+~ =.D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D C B B s s D J.# ~+w D C w P e. +i >+w D >+F [ 3 B C t q ,.i.5+v.q D q }.X.J ^.t C ] _+g q _.D ~+[ }.q D ]., j+p B j h K V D D a z+V Q D s D 9. V.D D -.3+<+s u C v D =+&+h.D s u u s u B+` D t D -.J n+P q B c. j.D w u B '.&+L B C t 8 , A+t t u s C u B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D D D D D B D B b+ 5.C C w C D n.* r+o.D C (.' Z.D s B !+! 6 B D ^.@.l.i t Q D 6._+Z u+B .+% o+q t C S n i.8.D ;.[.#.b D r D T e+@.5 B D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D C D D t D ~.z l.r O q D 4 .. 2+_.B w.3+).g t B P u 8 - : j q v B -.:.) R.B B [.3+ +C D S : } 0 D D w.{.( s D D g $ n+D D @+. /+O C B u f+' 3 t O Q E+=.D *.r B C y+K 5.B q C T s s i.J X D C v { U Q D D >. Y.C D B D 5 &+F+D t D '.&+v+D B t u D C D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B B B C D t w+ T.B D P B D ++ Z *.t t H.z H.s C D E . 4+u D 4+! M }.D D B g $+# l+B o &+h+D u p C |._+h B v...{ 7.B r B O W > q.B q D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D C B D C s D ^.@.= i D r D D 0 d.G O D C ^.F [.v.C s D B 2 ; |.Q D i D l Z } &.C D :., p _.t D Z _+l D C 8+, ^ X q D v.! _ C D p. I.-.D C q )+# g.D t k 5+r+r D p D t }+@ h+D u D B O g n [+P D D i e n+X B B n.+ 1.D P t B 1 %+D D t 8 * 9+D s u t s u B D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D t D s C D q w+ q.D t C s B H.! 4.D v C x.I /.D C D M.~ J.D D r.) ^ X u C D i [.E+8 D / ) l+C B D p n .8+D +% e+*.B k C T A+& L.t D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D t B t q B _.y - l+u u -.D 8+z+[+w O D ].X.).j q t r D a+} F k.D D B h C.B+0 t r : 3+i D s -.m K ^.B D }.$ : p D q e.;+e+D t D. :+p v C D 4.! S.D D *.#.n B O r t q g+{.*+r s O D v q l.i+Q t C s .J S q D +++ h.s O D C 1 ~ !+u u r a+' {+D q r P s D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B D D D q u s u C w++ T.D r C D ;.( > #+C v D H.- 5.D t B A+. g.q t 4 , n k.D C t }.m.` u.D 9 + #+q P D ;.V i+X u ;.J 3.8 B t C P | K 4 D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D B B B D r B U. f D D u B l #.#.p O D ^.J j+-.t u D u v / > L.t t v ]. _ P D r |.{.d D r ^.F B+}.B D ^+@.<+_.t q T & D+u D k+% ).T r u S A+I l+q r ;.z e+v s D C D b.{.n.s t D B D w ,+,+v C D +d.$+-.r t c.> p+s t B B a+H A+r D C 7 & :+D u s C D q D D t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C C D q D D D t o+. 0.B v r q L. N.*.B D v z.# 5.B P D R . S.u D ;.( ^+u w D c x P C ]+~ b+B C q v.5+d.l q O o+! ]+C D X p I U X D u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D C D D t q v p v B.. f+q D C W V h B D +} [+g D q s X D T.{. .,.D D ^ , S.D q B }+ g+D 7.c+3+# v.D C h & 0+B D C w.) ).D s v E ~ P.D D $.;+ h+D u S e+# *+t 2.r.D v+# #+C w _.t D Q :.z 0.D ,.)+_+5+D w D 6 {.r+O B '+t 1 ~ 1+D S r o.+ 9 D ;.r r O t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C B D D D s s v D u W.+ G+D B D f.I =.k.C X ;.D (.! H.D C B q++ /.D C D q.. y P C s e+_+8 t q w #.d.>+q D w+, B+w D r k+{.z+>+C D !+! $.D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D C D q v C p D i :+ ... .o+f+2+h C 8+i+ B+>+D D B q u 5 ` } #.{ #.1 C B -.u }.j+~ 5+: Y t+! ,+R.v.+.~ &+/ u+a C.+ + o X C ;.).= .y Y.:++ {.D.D B u._+z 5+f.*.F+} {.@+s C C D B 1 i.&+5+7+V.l. N ].B P s.) <.{ 6 n.} H F+w &.#. . 6+C P O D s C C q D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C B B D C D i o+$ ! _+l.#.#.} 2.h B q s P f.% . $ y.D y+> . <.$.C B t a _+3.l.z+r+6.D -.t s 0 , <.e N.d+V i.|+D t ].D+% i.l.d.J.D u u D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D t D B q D C q D s k.0 +6 -.v o.O u -.d d 8+8.q w C q P B B 7.d 6.6.g D t P q r u Q 0 e.,.Q g ^.d _.C 1 k.}.].u v k+l ^.'.q D B g ^.c 8+-._.'.e.g w s C l u+c Q q ,.8.i w.l D w B -.-.D T 8.c u+D j 6.w.u s t r k.e.6.k P u.v.v.l P v 8.8+^.o.O t P u t D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C D D C B Q w C k k.^.,. +6.6.d B D P p r D k 6.8+6.i s w.8.8+,.u+C _.r D *.e.d '.i D u r _.q q j k.d >+v S 8.8.p k D D T 8+6.a+v.D D w D u D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D B D D B D P s O t r D t C C D D v D B q D B P B g u O _.D C -.C D D k.D q P s q D u C D p S q C B D B w D D v D p D q D O B s u q s D C O B D B D B D r D D s D D v C D q C u B C D D q B s D D D r D q D q D r q v B B C D D q C D q q D C D C O q u q Q C B t D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B B C C t B D D D D B B D q s D p P D D p C D C u u O D B D D u r s r k C O D u C q X D B ;.p D u O D C t D D t D t p q D t j q B P B O D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.T.u t B D D D D D D D D D D D D D D D D D D D D D D B B B B B B w C s C D B D C C D B u t t D s t D q t B P v D C r C D s q s u C C s B t B u D C C q q D s s D D p u B q D B C t t D k B B t t D r u B D D r B C q D B B q D q P D u B D P D t s t q q D B B s D -.r s C C Q t D u u D D D D O O t q v t u D C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B D D B D O C q s D C D u q t D B p D D s v D B B O D C D O q D X D t r D B D u B D r C D C *.u D -.C D _.O D C D D C u D u v D C u t C v D D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D r 0./.5.Q.e+> ) n ", +"$ - . |.T.q.q.0.u t B B B B D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C s 5.!.5.Q.e+> ' n ", +"$ - . |.0.T.q.T.q C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D q D D O 0.a.Q.T.e+> ) n ", +"$ - . |.0.T.q.T.s t B B B B D B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C q .+d+5.F.e+~ ' n ", +"$ - . |.T.q.$.T.u t B B D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D B C B u Q./.0.5.=.~ ' n ", +", - + <+T.$.$.0.u t B D D D D D B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B B D D D w >.$.Q.5.e+> ) D+", +"$ - + |.T.$.$.T.q C D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D D C D q 5.>.T.Q.=.~ ' n ", +"@ - ! |.0.T.$.q.p O s s r s s r s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s s r O r w 5.>.5.5.V ! ' n ", +"% - ~ [.0.0.$.$.5.T.$.$.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.$.$..+q./.5.$.V ~ ; m.", +"% ; ! <+Q.0.d+/.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.a.a.a.a.a.a.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.q.q.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.q.$.$.$.$.q.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$./.0.a.a.q.a.$.a.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.a.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.0.T.$.q.$.$..+Q.n . H N ", +"z # + n+$.E.0.T.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.q.$.$.$.$.$.q.q.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.a.a.q.q.q.q.$.a.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.q.$.$.$.$.$.$.$.a.a.q.q.q.q.$.a.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.q.$.$.$.$.a.a.>.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.q.a.q.$.a.0.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.T.q.q.q.q.q.$.$.a.$.q.q.q.q.a.a.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.$.T.T.5.q.a.T.$.[+~ = ..", +"! ~ [.#+0.>.d+q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.0.T.q.$.a.a.$.$.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.$.$.$.$.0.T.q.$.a.a.$.$.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.$.$.$.q.T.T.T.T.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.0.$.$.0.$.a.0.$.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.$.$.$.$.q.q.q.q.$.$.a.a.$.q.T.0.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.q.T.q.q.q.q.T.T.T.q.T.T.0.q.$.Q.5.V + @ n ", +" + ~ ( P.*+V.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.n.n.n.n.n.n.n.n.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.V.V.V.L.n.P.G.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.V.V.V.L.n.P.G.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.n.L.L.L.L.V.V.V.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.n.P.n.L.n.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.n.n.n.G.P.n.L.V.V.V.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.L.n.n.P.G.P.P.L.n.c.G.[.! > l.", +"+ {.V V F J y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y N N y F y N n D+y y y y y y y y y y y y y y y y y y y y y y y y N y y y y y y y N N y F y N n D+y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y N y y y F F J J y y y y y y y y y y y y y y y y D+J F n y F N J y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y y F F y y N N N y D+n N y F y N N y y y y y y y y y y y y y y y y y y y y y y y F F J F U F y y m._+) {.[+", +" + . ! + ! > * * * * * * * * * * * * * * * * * * * * * * * * * * * H H H H H * * * * * * * * * * * * * * * * * * * * * * * * > &+* H H * * &+* * * * * * * * * * * * * * * * * * * * * * * * * * * * * H H ' > &+* H H * * &+* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * H H H H * * * * * * * * * * * * * * * * &+~ ~ H H * ' &+* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * &+> &+* * H H * &+> * * * * * * * * * * * * * * * * * * * * * * &+&+* &+* > ~ ! > - ' ~ & ", +". ~ + + + + + + + + + + + + + + + + + + + + + + + + + ; ; I I I I I I = = = = = = = = = = = = = = = = = = = = = = = = - = # # I H ! + + + + + + + + + + + + + + + + + + + + + + + + + + . ! ! - = # # I H ! + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ~ * ) I - = = = = = = = = = = = = = = = = ; , - ) - I I I = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = = - - I I ; ) ' * ! H I # # = - = = = = = = = = = = = = = = = = = = = = = = - - ; ; - I ) > ! + + ~ ", +" + + + + + + + + + + + + + ' _+I ! + . + + + + + + "}; diff --git a/apps/ReactiveNav3D-Demo/ReactiveNav3D_demo_main.cpp b/apps/ReactiveNav3D-Demo/ReactiveNav3D_demo_main.cpp index 4c5a6902be..9d371e24ef 100644 --- a/apps/ReactiveNav3D-Demo/ReactiveNav3D_demo_main.cpp +++ b/apps/ReactiveNav3D-Demo/ReactiveNav3D_demo_main.cpp @@ -259,7 +259,7 @@ int main(int num_arg, char *argv[]) else if ( string(argv[1]) == "--create-config") { filename = argv[2]; - cout << endl << "Nombre del archivo: " << filename; + cout << endl << "Config_file name: " << filename; ofstream new_file(filename.c_str()); new_file << string(default_cfg_txt); new_file.close(); diff --git a/cmakemodules/DefineExamples.cmake b/cmakemodules/DefineExamples.cmake index d4d8119e22..a1cd035a52 100644 --- a/cmakemodules/DefineExamples.cmake +++ b/cmakemodules/DefineExamples.cmake @@ -295,7 +295,18 @@ IF(BUILD_EXAMPLES) ENDIF(BUILD_HWDRIVERS) - + + # === OPENNI2 examples === + IF (MRPT_HAS_OPENNI2) + SET(LIST_EXAMPLES_IN_THIS_DIR + openNI2_RGBD_demo + openNI2_proximity_demo) + + SET(CMAKE_EXAMPLE_DEPS mrpt-base mrpt-gui mrpt-opengl mrpt-maps) + SET(CMAKE_EXAMPLE_LINK_LIBS ${MRPT_LINKER_LIBS} ${OPENNI2_LIBRARIES}) + GENERATE_CMAKE_FILES_SAMPLES_DIRECTORY() + ENDIF(MRPT_HAS_OPENNI2) + # === SRBA examples === ADD_SAMPLES_DIRECTORY(srba-examples) diff --git a/cmakemodules/script_openni2.cmake b/cmakemodules/script_openni2.cmake new file mode 100644 index 0000000000..ed2b8208f0 --- /dev/null +++ b/cmakemodules/script_openni2.cmake @@ -0,0 +1,74 @@ +# Check for the OpenNI2 library: +# pkg-config if available (Linux), otherwise via +# Originally based on: https://github.com/rgbdemo/nestk/blob/master/cmake/FindOpenNI2.cmake +# ========================================================= +SET(CMAKE_MRPT_HAS_OPENNI2 0) + +OPTION(DISABLE_OPENNI2 "Disable the OpenNI2 library, even if automatically found" "OFF") +MARK_AS_ADVANCED(DISABLE_OPENNI2) + +IF (NOT DISABLE_OPENNI2) # Allow the user to force not using this lib + +IF (PKG_CONFIG_FOUND) + if(${CMAKE_VERSION} VERSION_LESS 2.8.2) + pkg_check_modules(PC_OPENNI libopenni2) + else(${CMAKE_VERSION} VERSION_LESS 2.8.2) + pkg_check_modules(PC_OPENNI QUIET libopenni2) + endif(${CMAKE_VERSION} VERSION_LESS 2.8.2) +ENDIF (PKG_CONFIG_FOUND) + +# Build the expected names of the environment variables (Windows only) where OpenNI2 can be found: +IF (CMAKE_MRPT_WORD_SIZE EQUAL 64) + SET(ENV_OPNI2_INCLUDE "OPENNI2_INCLUDE64") + SET(ENV_OPNI2_LIB "OPENNI2_LIB64") + SET(ENV_OPNI2_REDIST "OPENNI2_REDIST64") +ELSE (CMAKE_MRPT_WORD_SIZE EQUAL 64) + SET(ENV_OPNI2_INCLUDE "OPENNI2_INCLUDE") + SET(ENV_OPNI2_LIB "OPENNI2_LIB") + SET(ENV_OPNI2_REDIST "OPENNI2_REDIST") +ENDIF (CMAKE_MRPT_WORD_SIZE EQUAL 64) + +# Create option for OpenNI2 and guess its default value: +SET(DEFAULT_MRPT_HAS_OPENNI2 0) +IF(PC_OPENNI_FOUND OR NOT "$ENV{${ENV_OPNI2_INCLUDE}}" STREQUAL "") + SET(DEFAULT_MRPT_HAS_OPENNI2 1) +ENDIF(PC_OPENNI_FOUND OR NOT "$ENV{${ENV_OPNI2_INCLUDE}}" STREQUAL "") + +OPTION(MRPT_HAS_OPENNI2 "Support for the OpenNI2 library" ${DEFAULT_MRPT_HAS_OPENNI2}) + +IF(MRPT_HAS_OPENNI2) + #set(OPENNI2_DEFINITIONS ${PC_OPENNI_CFLAGS_OTHER}) #JL: Remove? + + #add a hint so that it can find it without the pkg-config + find_path(OPENNI2_INCLUDE_DIR OpenNI.h + HINTS ${PC_OPENNI_INCLUDEDIR} ${PC_OPENNI_INCLUDE_DIRS} /usr/include/openni2 /usr/include/ni2 + PATHS "$ENV{PROGRAMFILES}/OpenNI2/Include" "$ENV{PROGRAMW6432}/OpenNI2/Include" "$ENV{${ENV_OPNI2_INCLUDE}}" + PATH_SUFFIXES openni ni + DOC "Path to the include directory containing OpenNI.h,etc.") + #add a hint so that it can find it without the pkg-config + find_library(OPENNI2_LIBRARY + NAMES OpenNI2 + HINTS ${PC_OPENNI_LIBDIR} ${PC_OPENNI_LIBRARY_DIRS} /usr/lib + PATHS "$ENV{PROGRAMFILES}/OpenNI2/Redist" "$ENV{PROGRAMW6432}/OpenNI2/Redist" "$ENV{PROGRAMW6432}/OpenNI2" "$ENV{${ENV_OPNI2_LIB}}" + PATH_SUFFIXES lib lib64 + DOC "The OpenNI2.lib file path") + + set(OPENNI2_INCLUDE_DIRS ${OPENNI2_INCLUDE_DIR}) + set(OPENNI2_LIBRARIES ${OPENNI2_LIBRARY}) + + IF (OPENNI2_INCLUDE_DIRS AND OPENNI2_LIBRARIES) + SET(CMAKE_MRPT_HAS_OPENNI2 1) + SET(CMAKE_MRPT_HAS_OPENNI2_SYSTEM 1) + include_directories(${OPENNI2_INCLUDE_DIRS}) + APPEND_MRPT_LIBS(${OPENNI2_LIBRARIES}) + + # Add include directories as "-isystem" to avoid warnings : + ADD_DIRECTORIES_AS_ISYSTEM(OPENNI2_INCLUDE_DIRS) + + message(STATUS "OpenNI2 found (include: ${OPENNI2_INCLUDE_DIR}, lib: ${OPENNI2_LIBRARY})") + ELSE (OPENNI2_INCLUDE_DIRS AND OPENNI2_LIBRARIES) + message(FATAL_ERROR "OpenNI2 not found: Either correctly set OPENNI2_INCLUDE_DIR and OPENNI2_LIBRARY or uncheck MRPT_HAS_OPENNI2") + ENDIF (OPENNI2_INCLUDE_DIRS AND OPENNI2_LIBRARIES) +ENDIF(MRPT_HAS_OPENNI2) + +ENDIF (NOT DISABLE_OPENNI2) diff --git a/cmakemodules/script_show_final_summary.cmake b/cmakemodules/script_show_final_summary.cmake index 7f92a3f375..6daf587278 100644 --- a/cmakemodules/script_show_final_summary.cmake +++ b/cmakemodules/script_show_final_summary.cmake @@ -124,6 +124,7 @@ SHOW_CONFIG_LINE_SYSTEM("Has OpenCV (Image manipulation) " CMAKE_MRPT_HA SHOW_CONFIG_LINE_SYSTEM("Has OpenGL " CMAKE_MRPT_HAS_OPENGL_GLUT) SHOW_CONFIG_LINE_SYSTEM("Has GLUT " CMAKE_MRPT_HAS_GLUT) SHOW_CONFIG_LINE_SYSTEM("Has OpenKinect libfreenect " CMAKE_MRPT_HAS_FREENECT) +SHOW_CONFIG_LINE_SYSTEM("Has OpenNI2 " CMAKE_MRPT_HAS_OPENNI2) SHOW_CONFIG_LINE_SYSTEM("Has PCL (Pointscloud library) " CMAKE_MRPT_HAS_PCL "[Version: ${PCL_VERSION}]") IF(NOT UNIX) # In fact, it's not "support for Bumblebee" but for it thru PGR vendor libraries. SHOW_CONFIG_LINE("Has PGR Digiclops/Triclops " CMAKE_MRPT_HAS_BUMBLEBEE) diff --git a/doc/doxygen-pages/changeLog_doc.h b/doc/doxygen-pages/changeLog_doc.h index b38addc868..98ebee777c 100644 --- a/doc/doxygen-pages/changeLog_doc.h +++ b/doc/doxygen-pages/changeLog_doc.h @@ -34,6 +34,8 @@ - mrpt::reactivenav::CAbstractPTGBasedReactive, as part of a large code refactoring of these classes: [(commit)](https://github.com/jlblancoc/mrpt/pull/4) - mrpt::reactivenav::CReactiveNavigationSystem - mrpt::reactivenav::CReactiveNavigationSystem3D + - [mrpt-vision] + - mrpt::vision::CDifodo, a class which implements visual odometry based on depth images and the "range flow constraint equation". (by Mariano Jaimez Tarifa) - [(commit)]() - Changes in classes: - Clean up and slight optimization of metric map matching API: - [(commit)](http://code.google.com/p/mrpt/source/detail?r=3446) - Methods marked as deprecated: @@ -52,9 +54,14 @@ - Deleted classes: - mrpt::utils::CEvent, which was actually unimplemented (!) - mrpt::hwdrivers::CInterfaceNI845x has been deleted. It didn't offer features enough to justify a class. + - New apps: + - DifOdometry-Camera (By Mariano Jaimez Tarifa) + - DifOdometry-Datasets (By Mariano Jaimez Tarifa) - New examples: - [MRPT]/samples/threadsPipe - [MRPT]/samples/NIDAQ_test + - [MRPT]/openNI2_RGBD_demo (by Mariano Jaimez Tarifa) + - [MRPT]/openNI2_proximity_demo (by Mariano Jaimez Tarifa) - Build system: - Fixed compilation with clang. - Fixed building against OpenCV 3.0.0 (GIT head) diff --git a/doc/doxygen-pages/lib_mrpt_vision.h b/doc/doxygen-pages/lib_mrpt_vision.h index 5d4f02f9f4..997e66e868 100644 --- a/doc/doxygen-pages/lib_mrpt_vision.h +++ b/doc/doxygen-pages/lib_mrpt_vision.h @@ -69,6 +69,8 @@ patch, with or without a set of descriptors. - Notice that sets of parameters for monocular and stereo cameras are defined in [mrpt-base] for convenience, in the classes: - mrpt::utils::TCamera - mrpt::utils::TStereoCamera + +- mrpt::vision::CDifodo: A class which implements a Visual Odometry algorithm based on depth images and the "range flow constraint equation". See all the classes in mrpt::vision diff --git a/libs/vision/include/mrpt/vision.h b/libs/vision/include/mrpt/vision.h index 95161d0f54..d3f530013b 100644 --- a/libs/vision/include/mrpt/vision.h +++ b/libs/vision/include/mrpt/vision.h @@ -34,6 +34,7 @@ #include #include #include +#include // Maps: #include diff --git a/libs/vision/include/mrpt/vision/CDifodo.h b/libs/vision/include/mrpt/vision/CDifodo.h new file mode 100644 index 0000000000..90579e5389 --- /dev/null +++ b/libs/vision/include/mrpt/vision/CDifodo.h @@ -0,0 +1,236 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + +#ifndef CDifodo_H +#define CDifodo_H + +#include +#include +#include +#include + + +//class CDeflodo Acronim for "Depth Flow odometry" -> otra opción de nombre... +namespace mrpt +{ + namespace vision + { + using mrpt::poses::CPose3D; + using Eigen::MatrixXf; + using Eigen::MatrixXi; + + /** This abstract class implements a method called "Difodo" to perform Visual odometry with range cameras. + * It is based on the range flow equation and assumes that the scene is rigid. + * It can work with different image resolutions (640 x 480, 320 x 240 or 160 x 120). + * Independently of the initial resolution chosen, the method normally makes use of a smaller amount of points + * which can be adjusted with the member variables (rows,cols). + * + * How to use: + * - A derived class must be created which defines the method "loadFrame(...)" according to the user application. + * This method has to load the depth image into the variable "depth_wf". + * - Call loadFrame(); + * - Call OdometryCalculation(); + * - Call filterSpeedAndPoseUpdate(); + * + * For further information have a look at the apps: + * - [Difodometry-Camera](http://www.mrpt.org/list-of-mrpt-apps/application-difodometry-camera/) + * - [Difodometry-Datasets](http://www.mrpt.org/list-of-mrpt-apps/application-difodometry-datasets/) + * + * Please refer to the respective publication when using this method: ************************* + * + * - JUN/2013: First design. + * - JAN/2014: Integrated into MRPT library. + * + * \sa ********************* + * \ingroup mrpt_vision_grp + */ + + class VISION_IMPEXP CDifodo { + + protected: + + /** Matrices that store the original and filtered depth frames with the image resolution */ + MatrixXf depth_ft; + MatrixXf depth_wf; + + /** Matrices that store the point coordinates after downsampling. */ + MatrixXf depth; + MatrixXf depth_old; + MatrixXf depth_inter; + MatrixXf xx; + MatrixXf xx_inter; + MatrixXf xx_old; + MatrixXf yy; + MatrixXf yy_inter; + MatrixXf yy_old; + + /** Matrices that store the depth derivatives */ + MatrixXf du; + MatrixXf dv; + MatrixXf dt; + + /** Matrix which indicates wheter the depth of a pixel is zero (null = 1) or not (null = 00). and border and noisy points */ + MatrixXi null; + + /** Matrix which indicates wheter a point is in a border or has an inaccurate depth (border =1, border = 0 otherwise) */ + MatrixXi border; + + /** Least squares covariance matrix */ + math::CMatrixFloat66 est_cov; + + /** Camera properties: */ + float f_dist; //! // Precompiled headers +#include + +using namespace mrpt; +using namespace mrpt::vision; +using namespace std; +using namespace Eigen; + +CDifodo::CDifodo() +{ + rows = 60; + cols = 80; + fovh = M_PI*57.5/180.0; + fovv = M_PI*45.0/180.0; + lens_disp = 0.022; + cam_mode = 1; // (1 - 640 x 480, 2 - 320 x 240, 4 - 160 x 120) + downsample = 4; + gaussian_mask_size = 7; + const unsigned int resh = 640/(cam_mode*downsample); + const unsigned int resv = 480/(cam_mode*downsample); + + depth.setSize(rows,cols); + depth_old.setSize(rows,cols); + depth_inter.setSize(rows,cols); + depth_ft.setSize(resv,resh); + depth_wf.setSize(resv,resh); + + du.setSize(rows,cols); + dv.setSize(rows,cols); + dt.setSize(rows,cols); + xx.setSize(rows,cols); + xx_inter.setSize(rows,cols); + xx_old.setSize(rows,cols); + yy.setSize(rows,cols); + yy_inter.setSize(rows,cols); + yy_old.setSize(rows,cols); + + border.setSize(rows,cols); + border.assign(0); + null.setSize(rows,cols); + null.assign(0); + est_cov.assign(0); + + f_dist = 1.0/525.0; //In meters + x_incr = 2.0*f_dist*(floor(float(resh)/float(cols))*cols/float(resh))*tan(0.5*fovh)/(cols-1); //In meters + y_incr = 2.0*f_dist*(floor(float(resv)/float(rows))*rows/float(resv))*tan(0.5*fovv)/(rows-1); //In meters + fps = 30.0; //In Hz + + //Depth thresholds + const int dy = floor(float(resv)/float(rows)); + const int dx = floor(float(resh)/float(cols)); + + duv_threshold = 0.001*(dx + dy)*(cam_mode*downsample); + dt_threshold = 0.2*fps; + dif_threshold = 0.001*(dx + dy)*(cam_mode*downsample); + difuv_surroundings = 0.005*(dx + dy)*(cam_mode*downsample); + dift_surroundings = 0.01*fps*(dx + dy)*(cam_mode*downsample); + + previous_speed_const_weight = 0.2; + previous_speed_eig_weight = 400.0; + + num_valid_points = 0; +} + +void CDifodo::calculateCoord() +{ + for (unsigned int x = 0; x < cols; x++) + for (unsigned int y = 0; y < rows; y++) + { + if ((depth(y,x)) == 0 || (depth_old(y,x) == 0)) + { + depth_inter(y,x) = 0; + xx_inter(y,x) = 0; + yy_inter(y,x) = 0; + } + else + { + depth_inter(y,x) = 0.5*(depth(y,x) + depth_old(y,x)); + xx_inter(y,x) = 0.5*(xx(y,x) + xx_old(y,x)); + yy_inter(y,x) = 0.5*(yy(y,x) + yy_old(y,x)); + } + } +} + + +void CDifodo::calculateDepthDerivatives() +{ + for (unsigned int x = 1; x < cols-1; x++) + for (unsigned int y = 1; y < rows-1; y++) + { + du(y,x) = 0.5*(depth_inter(y,x+1) - depth_inter(y,x-1)); + dv(y,x) = 0.5*(depth_inter(y+1,x) - depth_inter(y-1,x)); + dt(y,x) = fps*(depth(y,x) - depth_old(y,x)); + } +} + + +void CDifodo::filterAndDownsample() +{ + //CTicTac clock; + //clock.Tic(); + + //Push the frames back + depth_old = depth; + xx_old = xx; + yy_old = yy; + + // Create the kernel + //========================================================== + Eigen::MatrixXf kernel(gaussian_mask_size,1); + + const float sigma = 0.2f*gaussian_mask_size; + float r, s = 2.0f * sigma * sigma; + float ksum = 0.0f; + + // Generate kernel + if ((gaussian_mask_size%2 == 0)||(gaussian_mask_size<3)) + { + cout << endl << "Mask size must be odd and bigger than 2"; + depth_ft = depth_wf; + return; + } + + const int lim_mask = (gaussian_mask_size-1)/2; + for (int x = -lim_mask; x <= lim_mask; x++) + { + r = math::sqrt(float(x*x)); + kernel(x + lim_mask, 0) = (exp(-(r*r)/s))/(M_PI * s); + ksum += kernel(x + lim_mask, 0); + } + + // normalize the Kernel + for (int x = -lim_mask; x <= lim_mask; x++) + { + kernel(x + lim_mask, 0)/=ksum; + //cout << kernel(x + lim_mask, 1) << " "; + } + + const int width = depth_wf.getColCount(); + const int height = depth_wf.getRowCount(); + MatrixXf depth_if; + depth_if.setSize(height, width); + + //Apply gaussian filter (separately) + //rows + for ( int i=0; i=lim_mask)&&(j 0.0001f) + depth_if(i,j) = sum/ponder; + else + depth_if(i,j) = 0; + } + else + depth_if(i,j) = depth_wf(i,j); + + } + + //cols + for ( int i=0; i=lim_mask)&&(i 0.0001f) + depth_wf(i,j) = sum/ponder; + else + depth_wf(i,j) = 0; + } + else + depth_wf(i,j) = depth_if(i,j); + + } + + //Downsample the pointcloud + const float inv_f = float(640/width)/525.0f; + const float disp_x = 0.5*(width-1); + const float disp_y = 0.5*(height-1); + + const int dy = floor(float(height)/float(rows)); + const int dx = floor(float(width)/float(cols)); + const unsigned int iniy = (height-dy*rows)/2; + const unsigned int inix = (width-dx*cols)/2; + + for (unsigned int y = 0; y < rows; y++) + for (unsigned int x = 0; x < cols; x++) + { + depth(y,x) = depth_wf(iniy+y*dy,inix+x*dx); + xx(y,x) = (inix+x*dx - disp_x)*depth_wf(iniy+y*dy,inix+x*dx)*inv_f + lens_disp; + yy(y,x) = (iniy+y*dy - disp_y)*depth_wf(iniy+y*dy,inix+x*dx)*inv_f; + } + + //cout << endl << "Execution time - filter + downsample (ms): " << 1000*clock.Tac(); +} + +void CDifodo::findBorders() +{ + border.assign(0); + + //Detect borders + for (unsigned int x = 1; x < cols-1; x++) + for (unsigned int y = 1; y < rows-1; y++) + { + if (null(y,x) == 0) + { + const float aver_duv = du(y,x)*du(y,x) + dv(y,x)*dv(y,x); + const float ini_dx = 0.5*(depth_old(y,x+1) - depth_old(y,x-1)); + const float ini_dy = 0.5*(depth_old(y+1,x) - depth_old(y-1,x)); + const float final_dx = 0.5*(depth(y,x+1) - depth(y,x-1)); + const float final_dy = 0.5*(depth(y+1,x) - depth(y-1,x)); + + + //Derivative too high (the average derivative) + if (aver_duv > duv_threshold) + border(y,x) = 1; + + else if (abs(dt(y,x)) > dt_threshold) + border(y,x) = 1; + + //Big difference between initial and final derivatives + else if (abs(final_dx-ini_dx) + abs(final_dy-ini_dy) > dif_threshold) + border(y,x) = 1; + + //Difference between derivatives in the surroundings + else + { + float sum_duv = 0; + float sum_dift = 0; + float sum_difdepth = 0; + for (int k = -1; k<2; k++) + for (int l = -1; l<2; l++) + { + sum_duv += abs(du(y,x)-du(y+k,x+l)) + abs(dv(y,x)-dv(y+k,x+l)); + sum_dift += abs(dt(y,x) - dt(y+k,x+l)); + sum_difdepth += abs(depth_inter(y,x) - depth_inter(y+k,x+l)); + } + + if (sum_dift > depth_inter(y,x)*dift_surroundings) + border(y,x) = 1; + + else if (sum_duv > (4.0*sum_difdepth + depth_inter(y,x))*difuv_surroundings) + border(y,x) = 1; + + } + } + } + + //Delete sparse points + for (unsigned int x = 1; x < cols-1; x++) + for (unsigned int y = 1; y < rows-1; y++) + { + if ((null(y,x) == 0)&&(border(y,x) == 0)) + { + float sum_alone = 0; + for (int k = -1; k<2; k++) + for (int l = -1; l<2; l++) + { + sum_alone += (border(y+k,x+l)||null(y+k,x+l)); + } + + if (sum_alone > 6) + border(y,x) = 1; + + } + } +} + + +void CDifodo::findNullPoints() +{ + null.assign(0); + for (unsigned int x = 0; x < cols; x++) + for (unsigned int y = 0; y < rows; y++) + if (depth_inter(y,x) == 0) + null(y,x) = 1; + +} + + +void CDifodo::findValidPoints() +{ + num_valid_points = 0; + + for (unsigned int y = 1; y < rows-1; y++) + for (unsigned int x = 1; x < cols-1; x++) + if ((border(y,x) == 0)&&(null(y,x) == 0)) + num_valid_points++; +} + + +void CDifodo::solveDepthSystem() +{ + utils::CTicTac clock; + unsigned int cont = 0; + vector > coord; + SparseMatrix A; + MatrixXf Var; + MatrixXf B; + A.resize(num_valid_points,6); + B.setSize(num_valid_points,1); + Var.setSize(6,1); + + //clock.Tic(); + + //Fill the matrix A and the vector B + //The order of the variables will be (vx, vy, vz, wx, wy, wz) + //The points order will be (1,1), (1,2)...(1,cols-1), (2,1), (2,2)...(row-1,cols-1). Points at the borders are not included + + const float f_inv_x = f_dist/x_incr; + const float f_inv_y = f_dist/y_incr; + + for (unsigned int y = 1; y < rows-1; y++) + for (unsigned int x = 1; x < cols-1; x++) + if ((border(y,x) == 0)&&(null(y,x) == 0)) + { + const float inv_d = 1.0f/depth_inter(y,x); + const float dxcomp = du(y,x)*f_inv_x*inv_d; + const float dycomp = dv(y,x)*f_inv_y*inv_d; + + coord.push_back(Triplet(cont, 0, inv_d*(1.0f + dxcomp*xx_inter(y,x)*inv_d + dycomp*yy_inter(y,x)*inv_d))); + coord.push_back(Triplet(cont, 1, inv_d*(-dxcomp))); + coord.push_back(Triplet(cont, 2, inv_d*(-dycomp))); + coord.push_back(Triplet(cont, 3, inv_d*(dxcomp*yy_inter(y,x) - dycomp*xx_inter(y,x)))); + coord.push_back(Triplet(cont, 4, inv_d*(yy_inter(y,x) + dxcomp*inv_d*yy_inter(y,x)*xx_inter(y,x) + dycomp*(yy_inter(y,x)*yy_inter(y,x)*inv_d + depth_inter(y,x))))); + coord.push_back(Triplet(cont, 5, inv_d*(-xx_inter(y,x) - dxcomp*(xx_inter(y,x)*xx_inter(y,x)*inv_d + depth_inter(y,x)) - dycomp*inv_d*yy_inter(y,x)*xx_inter(y,x)))); + + B(cont,0) = inv_d*(-dt(y,x)); + + cont++; + } + + + A.setFromTriplets(coord.begin(), coord.end()); + + //Solve the linear system of equations using a minimum least squares method + const SparseMatrix atrans = A.transpose(); + const SparseMatrix aux = atrans*A; + SimplicialLDLT> SparseCholesky; + SparseCholesky.compute(aux); + + if(SparseCholesky.info()!= Eigen::Success ) { cout << endl << "Cholesky decomposition failed "; } + + Var = SparseCholesky.solve(atrans*B); + kai_solver = Var; + + if(SparseCholesky.info()!= Eigen::Success ) { cout << endl << "Cholesty solver failed"; } + + + //Covariance matrix calculation + MatrixXf aux_normal; + MatrixXf residuals(num_valid_points,1); + aux_normal = aux.toDense(); + residuals = A*Var - B; + est_cov = (1.0f/float(num_valid_points-6))*aux_normal.inverse()*residuals.squaredNorm(); + //cout << endl << "Covariance matrix: " << endl << 50*est_cov; + +} + + +void CDifodo::OdometryCalculation() +{ + utils::CTicTac clock; + clock.Tic(); + filterAndDownsample(); + calculateCoord(); + calculateDepthDerivatives(); + findNullPoints(); + findBorders(); + findValidPoints(); + + if (num_valid_points > 6) {solveDepthSystem();} + else {kai_solver.assign(0);} + + execution_time = 1000*clock.Tac(); +} + + +void CDifodo::filterSpeedAndPoseUpdate() +{ + //------------------------------------------------------------------------- + // Filter speed + //------------------------------------------------------------------------- + + utils::CTicTac clock; + clock.Tic(); + + // Calculate Eigenvalues and Eigenvectors + //---------------------------------------------------------------------------- + SelfAdjointEigenSolver eigensolver(est_cov); + if (eigensolver.info() != Success) + { + printf("Eigensolver couldn't find a solution. Pose is not updated"); + return; + } + + //First, we have to describe both the new linear and angular speeds in the "eigenvector" basis + //------------------------------------------------------------------------------------------------- + MatrixXf Bii, kai_b; + Bii.setSize(6,6); kai_b.setSize(6,1); + Bii = eigensolver.eigenvectors(); + + kai_b = Bii.colPivHouseholderQr().solve(kai_solver); + + //Second, we have to describe both the old linear and angular speeds in the "eigenvector" basis too + //------------------------------------------------------------------------------------------------- + math::CMatrixDouble33 inv_trans; + math::CMatrixFloat31 v_loc_old, w_loc_old; + + //Express them in the local reference frame first + cam_pose.getRotationMatrix(inv_trans); + v_loc_old = inv_trans.inverse().cast()*kai_abs.topRows(3); + w_loc_old = inv_trans.inverse().cast()*kai_abs.bottomRows(3); + + //Then transform that local representation to the "eigenvector" basis + MatrixXf kai_b_old; + kai_b_old.setSize(6,1); + math::CMatrixFloat61 kai_loc_old; + kai_loc_old.topRows<3>() = v_loc_old; + kai_loc_old.bottomRows<3>() = w_loc_old; + + kai_b_old = Bii.colPivHouseholderQr().solve(kai_loc_old); + + //Filter speed + MatrixXf kai_b_fil; + kai_b_fil.setSize(6,1); + for (unsigned int i=0; i<6; i++) + { + kai_b_fil(i,0) = (kai_b(i,0) + (previous_speed_eig_weight*eigensolver.eigenvalues()(i,0) + previous_speed_const_weight)*kai_b_old(i,0))/(1.0 + previous_speed_eig_weight*eigensolver.eigenvalues()(i,0) + previous_speed_const_weight); + } + + //Transform filtered speed to local and then absolute reference systems + MatrixXf kai_loc_fil; + math::CMatrixFloat31 v_abs_fil, w_abs_fil; + kai_loc_fil.setSize(6,1); + kai_loc_fil = Bii.inverse().colPivHouseholderQr().solve(kai_b_fil); + + cam_pose.getRotationMatrix(inv_trans); + v_abs_fil = inv_trans.cast()*kai_loc_fil.topRows(3); + w_abs_fil = inv_trans.cast()*kai_loc_fil.bottomRows(3); + + kai_abs.topRows<3>() = v_abs_fil; + kai_abs.bottomRows<3>() = w_abs_fil; + + + //------------------------------------------------------------------------- + // Update pose (DIFODO) + //------------------------------------------------------------------------- + + cam_oldpose = cam_pose; + + double yaw,pitch,roll; + math::CMatrixDouble31 w_euler_d; + + cam_pose.getYawPitchRoll(yaw,pitch,roll); + w_euler_d(0,0) = kai_loc_fil(4,0)*sin(roll)/cos(pitch) + kai_loc_fil(5,0)*cos(roll)/cos(pitch); + w_euler_d(1,0) = kai_loc_fil(4,0)*cos(roll) - kai_loc_fil(5,0)*sin(roll); + w_euler_d(2,0) = kai_loc_fil(3,0) + kai_loc_fil(4,0)*sin(roll)*tan(pitch) + kai_loc_fil(5,0)*cos(roll)*tan(pitch); + + //Update pose + cam_pose.x_incr(v_abs_fil(0,0)/fps); + cam_pose.y_incr(v_abs_fil(1,0)/fps); + cam_pose.y_incr(v_abs_fil(2,0)/fps); + cam_pose.setYawPitchRoll(yaw + w_euler_d(0,0)/fps, pitch + w_euler_d(1,0)/fps, roll + w_euler_d(2,0)/fps); + + execution_time += 1000*clock.Tac(); +} + + +void CDifodo::setCameraFocalLenght(float new_f) +{ + const unsigned int resh = 640/(cam_mode*downsample); + const unsigned int resv = 480/(cam_mode*downsample); + + f_dist = new_f; + x_incr = 2.0*f_dist*(floor(float(resh)/float(cols))*cols/float(resh))*tan(0.5*fovh)/(cols-1); + y_incr = 2.0*f_dist*(floor(float(resv)/float(rows))*rows/float(resv))*tan(0.5*fovv)/(rows-1); +} + + +void CDifodo::setRowsAndCols(unsigned int num_rows, unsigned int num_cols) +{ + rows = num_rows; + cols = num_cols; + + const unsigned int resh = 640/(cam_mode*downsample); + const unsigned int resv = 480/(cam_mode*downsample); + + depth.setSize(rows,cols); + depth_old.setSize(rows,cols); + depth_inter.setSize(rows,cols); + + du.setSize(rows,cols); + dv.setSize(rows,cols); + dt.setSize(rows,cols); + xx.setSize(rows,cols); + xx_inter.setSize(rows,cols); + xx_old.setSize(rows,cols); + yy.setSize(rows,cols); + yy_inter.setSize(rows,cols); + yy_old.setSize(rows,cols); + + border.setSize(rows,cols); + border.assign(0); + null.setSize(rows,cols); + null.assign(0); + + x_incr = 2.0*f_dist*(floor(float(resh)/float(cols))*cols/float(resh))*tan(0.5*fovh)/(cols-1); //In meters + y_incr = 2.0*f_dist*(floor(float(resv)/float(rows))*rows/float(resv))*tan(0.5*fovv)/(rows-1); //In meters //In Hz + + //Depth thresholds + const int dy = floor(float(resv)/float(rows)); + const int dx = floor(float(resh)/float(cols)); + + duv_threshold = 0.001*(dx + dy)*(cam_mode*downsample); + dt_threshold = 0.2*fps; + dif_threshold = 0.001*(dx + dy)*(cam_mode*downsample); + difuv_surroundings = 0.005*(dx + dy)*(cam_mode*downsample); + dift_surroundings = 0.01*fps*(dx + dy)*(cam_mode*downsample); +} + + +void CDifodo::setFOV(float new_fovh, float new_fovv) +{ + fovh = M_PI*new_fovh/180.0; + fovv = M_PI*new_fovv/180.0; + const unsigned int resh = 640/(cam_mode*downsample); + const unsigned int resv = 480/(cam_mode*downsample); + + x_incr = 2.0*f_dist*(floor(float(resh)/float(cols))*cols/float(resh))*tan(0.5*fovh)/(cols-1); //In meters + y_incr = 2.0*f_dist*(floor(float(resv)/float(rows))*rows/float(resv))*tan(0.5*fovv)/(rows-1); //In meters +} + + +void CDifodo::getPointsCoord(MatrixXf &x, MatrixXf &y, MatrixXf &z) +{ + x.resize(rows,cols); + y.resize(rows,cols); + z.resize(rows,cols); + + z = depth_inter; + x = xx_inter; + y = yy_inter; +} + + +void CDifodo::getDepthDerivatives(MatrixXf &cur_du, MatrixXf &cur_dv, MatrixXf &cur_dt) +{ + cur_du.resize(rows,cols); + cur_dv.resize(rows,cols); + cur_dt.resize(rows,cols); + + cur_du = du; + cur_dv = dv; + cur_dt = dt; +} + + +void CDifodo::bordersThresholdToDefault() +{ + const int dy = floor(float(480/(cam_mode*downsample))/float(rows)); + const int dx = floor(float(640/(cam_mode*downsample))/float(cols)); + + duv_threshold = 0.001*(dx + dy)*(cam_mode*downsample); + dt_threshold = 0.2*fps; + dif_threshold = 0.001*(dx + dy)*(cam_mode*downsample); + difuv_surroundings = 0.005*(dx + dy)*(cam_mode*downsample); + dift_surroundings = 0.01*fps*(dx + dy)*(cam_mode*downsample); +} + diff --git a/parse-files/config.h.in b/parse-files/config.h.in index 8b8e64e55d..a9785f24e6 100644 --- a/parse-files/config.h.in +++ b/parse-files/config.h.in @@ -104,6 +104,9 @@ ${CMAKE_MRPT_BUILD_SHARED_LIB} #define MRPT_HAS_KINECT_FREENECT ${CMAKE_MRPT_HAS_FREENECT} #define MRPT_HAS_KINECT_FREENECT_SYSTEM ${CMAKE_MRPT_HAS_FREENECT_SYSTEM} +/* OpenNI2 lib: */ +#define MRPT_HAS_KINECT_CL_NUI ${CMAKE_MRPT_HAS_CL_NUI} +#define MRPT_HAS_OPENNI2 ${CMAKE_MRPT_HAS_OPENNI2} /* PCL (The pointclouds library): */ #define MRPT_HAS_PCL ${CMAKE_MRPT_HAS_PCL} diff --git a/samples/CMakeLists.txt b/samples/CMakeLists.txt index bf85f38973..ed0c83e6bd 100644 --- a/samples/CMakeLists.txt +++ b/samples/CMakeLists.txt @@ -122,5 +122,9 @@ add_subdirectory(MOXmodel-rawlog) add_subdirectory(captureVideoAndBuildPyr) add_subdirectory(stereoRectify) add_subdirectory(face_detection) +add_subdirectory(openNI2_RGBD_demo) +add_subdirectory(openNI2_proximity_demo) add_subdirectory(srba-examples) +add_subdirectory(pbmap_example) +add_subdirectory(pbmap_visualizer) diff --git a/samples/openNI2_RGBD_demo/CMakeLists.txt b/samples/openNI2_RGBD_demo/CMakeLists.txt new file mode 100644 index 0000000000..617f49855e --- /dev/null +++ b/samples/openNI2_RGBD_demo/CMakeLists.txt @@ -0,0 +1,73 @@ +#----------------------------------------------------------------------------------------------- +# CMake file for the MRPT example: /openNI2_RGBD_demo +# +# Run with "ccmake ." at the root directory, or use it as a template for +# starting your own programs +#----------------------------------------------------------------------------------------------- +SET(sampleName openNI2_RGBD_demo) +SET(PRJ_NAME "EXAMPLE_${sampleName}") + +# --------------------------------------- +# Declare a new CMake Project: +# --------------------------------------- +PROJECT(${PRJ_NAME}) + +# These commands are needed by modern versions of CMake: +CMAKE_MINIMUM_REQUIRED(VERSION 2.4) +if(COMMAND cmake_policy) + cmake_policy(SET CMP0003 NEW) # Required by CMake 2.7+ +endif(COMMAND cmake_policy) + +# --------------------------------------------------------------------------- +# Set the output directory of each example to its corresponding subdirectory +# in the binary tree: +# --------------------------------------------------------------------------- +SET(EXECUTABLE_OUTPUT_PATH ".") + +# -------------------------------------------------------------------------- +# The list of "libs" which can be included can be found in: +# http://www.mrpt.org/Libraries +# +# The dependencies of a library are automatically added, so you only +# need to specify the top-most libraries your code depend on. +# -------------------------------------------------------------------------- +FIND_PACKAGE(MRPT REQUIRED base;gui;opengl;maps) + +# --------------------------------------------- +# TARGET: +# --------------------------------------------- +# Define the executable target: +ADD_EXECUTABLE(${sampleName} test.cpp ) + +SET_TARGET_PROPERTIES( + ${sampleName} + PROPERTIES + PROJECT_LABEL "(EXAMPLE) ${sampleName}") + +# Add special defines needed by this example, if any: +SET(MY_DEFS ) +IF(MY_DEFS) # If not empty + ADD_DEFINITIONS("-D${MY_DEFS}") +ENDIF(MY_DEFS) + +# Add the required libraries for linking: +TARGET_LINK_LIBRARIES(${sampleName} + ${MRPT_LIBS} # This is filled by FIND_PACKAGE(MRPT ...) + "C:/Users/Mariano/Programas/OpenNI2_32/Lib/OpenNI2.lib" # Optional extra libs... + ) + +# Set optimized building: +IF(CMAKE_COMPILER_IS_GNUCXX AND NOT CMAKE_BUILD_TYPE MATCHES "Debug") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -mtune=native") +ENDIF(CMAKE_COMPILER_IS_GNUCXX AND NOT CMAKE_BUILD_TYPE MATCHES "Debug") + + +# ------------------------------------------------------------------------- +# This part can be removed if you are compiling this program outside of +# the MRPT tree: +# ------------------------------------------------------------------------- +IF("${CMAKE_PROJECT_NAME}" STREQUAL "MRPT") # Fails if build outside of MRPT project. + DeclareAppDependencies(${sampleName} mrpt-base;mrpt-gui;mrpt-opengl;mrpt-maps) # Dependencies +ENDIF("${CMAKE_PROJECT_NAME}" STREQUAL "MRPT") +# ------------------------------------------------------------------------- + diff --git a/samples/openNI2_RGBD_demo/test.cpp b/samples/openNI2_RGBD_demo/test.cpp new file mode 100644 index 0000000000..cf68d3af0b --- /dev/null +++ b/samples/openNI2_RGBD_demo/test.cpp @@ -0,0 +1,211 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + +#include +#include + +#include +#include +#include +#include + +using namespace mrpt; +using namespace std; + + +int main ( int argc, char** argv ) +{ + openni::Status rc = openni::STATUS_OK; + + openni::Device device; + openni::VideoMode options; + openni::VideoStream depth, rgb; + + // Device is openned + //======================================================================================= + const char* deviceURI = openni::ANY_DEVICE; + if (argc > 1) + deviceURI = argv[1]; + + rc = openni::OpenNI::initialize(); + + if (rc != openni::STATUS_OK) { printf("After initialization:\n %s\n", openni::OpenNI::getExtendedError()); } + + rc = device.open(deviceURI); + + //cout << endl << "Do we have IR sensor? " << device.hasSensor(openni::SENSOR_IR); + //cout << endl << "Do we have RGB sensor? " << device.hasSensor(openni::SENSOR_COLOR); + //cout << endl << "Do we have Depth sensor? " << device.hasSensor(openni::SENSOR_DEPTH); + + if (rc != openni::STATUS_OK) + { + printf("SimpleViewer: Device open failed:\n%s\n", openni::OpenNI::getExtendedError()); + openni::OpenNI::shutdown(); + return 1; + } + + // Create RGB and Depth channels + //======================================================================================== + rc = depth.create(device, openni::SENSOR_DEPTH); + if (rc == openni::STATUS_OK) + { + rc = depth.start(); + if (rc != openni::STATUS_OK) + { + printf("SimpleViewer: Couldn't start depth stream:\n%s\n", openni::OpenNI::getExtendedError()); + depth.destroy(); + } + } + else + { + printf("SimpleViewer: Couldn't find depth stream:\n%s\n", openni::OpenNI::getExtendedError()); + } + + + rc = rgb.create(device, openni::SENSOR_COLOR); + if (rc == openni::STATUS_OK) + { + rc = rgb.start(); + if (rc != openni::STATUS_OK) + { + printf("SimpleViewer: Couldn't start infrared stream:\n%s\n", openni::OpenNI::getExtendedError()); + rgb.destroy(); + } + } + else + { + printf("SimpleViewer: Couldn't find infrared stream:\n%s\n", openni::OpenNI::getExtendedError()); + } + + if (!depth.isValid() || !rgb.isValid()) + { + printf("SimpleViewer: No valid streams. Exiting\n"); + openni::OpenNI::shutdown(); + return 2; + } + + if (rc != openni::STATUS_OK) + { + openni::OpenNI::shutdown(); + return 3; + } + + // Configure some properties (resolution) + //======================================================================================== + + unsigned width = 320, height = 240; + + rc = device.setImageRegistrationMode(openni::IMAGE_REGISTRATION_DEPTH_TO_COLOR); + //rc = device.setImageRegistrationMode(openni::IMAGE_REGISTRATION_OFF); + + options = rgb.getVideoMode(); + printf("\nInitial resolution RGB (%d, %d)", options.getResolutionX(), options.getResolutionY()); + options.setResolution(width,height); + rc = rgb.setVideoMode(options); + rc = rgb.setMirroringEnabled(false); + + options = depth.getVideoMode(); + printf("\nInitial resolution Depth(%d, %d)", options.getResolutionX(), options.getResolutionY()); + options.setResolution(width,height); + rc = depth.setVideoMode(options); + rc = depth.setMirroringEnabled(false); + + options = depth.getVideoMode(); + printf("\nNew resolution (%d, %d) \n", options.getResolutionX(), options.getResolutionY()); + + //Allow detection of closer points (although they will flicker) + //bool CloseRange; + //depth.setProperty(XN_STREAM_PROPERTY_CLOSE_RANGE, 1); + //depth.getProperty(XN_STREAM_PROPERTY_CLOSE_RANGE, &CloseRange); + //printf("\nClose range: %s", CloseRange?"On":"Off"); + + + // Create scene + //======================================================================================== + + gui::CDisplayWindow3D window; + opengl::COpenGLScenePtr scene; + gui::global_settings::OCTREE_RENDER_MAX_POINTS_PER_NODE = 1000000; + window.setWindowTitle("Kinect frame"); + window.resize(800,600); + window.setPos(500,50); + window.setCameraZoom(5); + window.setCameraAzimuthDeg(180); + window.setCameraElevationDeg(5); + scene = window.get3DSceneAndLock(); + + opengl::CPointCloudColouredPtr kinectp = opengl::CPointCloudColoured::Create(); + kinectp->enablePointSmooth(true); + kinectp->setPointSize(2); + scene->insert( kinectp ); + + opengl::CSetOfObjectsPtr reference = opengl::stock_objects::CornerXYZ(); + reference->setScale(0.4); + scene->insert( reference ); + + window.unlockAccess3DScene(); + window.addTextMessage(5,5, format("Push any key to exit")); + window.repaint(); + + // Grab frames continuously and show + //======================================================================================== + + slam::CColouredPointsMap points; + openni::VideoFrameRef framed, framergb; + + while (!window.keyHit()) //Push any key to exit + { + points.clear(); + depth.readFrame(&framed); + rgb.readFrame(&framergb); + + if ((framed.getWidth() != framergb.getWidth()) || (framed.getHeight() != framergb.getHeight())) + { + cout << endl << "Both frames don't have the same size."; + } + else + { + //Read one frame + const openni::DepthPixel* pDepthRow = (const openni::DepthPixel*)framed.getData(); + const openni::RGB888Pixel* pRgbRow = (const openni::RGB888Pixel*)framergb.getData(); + int rowSize = framed.getStrideInBytes() / sizeof(openni::DepthPixel); + + float x, y, z, inv_f = float(640/width)/525.0f; + + for (int yc = 0; yc < framed.getHeight(); ++yc) + { + const openni::DepthPixel* pDepth = pDepthRow; + const openni::RGB888Pixel* pRgb = pRgbRow; + for (int xc = 0; xc < framed.getWidth(); ++xc, ++pDepth, ++pRgb) + { + z = 0.001*(*pDepth); + x = -(xc - 0.5*(width-1))*z*inv_f; + y = -(yc - 0.5*(height-1))*z*inv_f; + points.insertPoint(z, x, y, 0.0039*pRgb->r, 0.0039*pRgb->g, 0.0039*pRgb->b); + } + pDepthRow += rowSize; + pRgbRow += rowSize; + } + } + + scene = window.get3DSceneAndLock(); + kinectp->loadFromPointsMap (&points); + system::sleep(10); + window.unlockAccess3DScene(); + window.repaint(); + } + + depth.destroy(); + rgb.destroy(); + openni::OpenNI::shutdown(); + + return 0; +} + + diff --git a/samples/openNI2_proximity_demo/CMakeLists.txt b/samples/openNI2_proximity_demo/CMakeLists.txt new file mode 100644 index 0000000000..ea16fafe5f --- /dev/null +++ b/samples/openNI2_proximity_demo/CMakeLists.txt @@ -0,0 +1,73 @@ +#----------------------------------------------------------------------------------------------- +# CMake file for the MRPT example: /openNI2_proximity_demo +# +# Run with "ccmake ." at the root directory, or use it as a template for +# starting your own programs +#----------------------------------------------------------------------------------------------- +SET(sampleName openNI2_proximity_demo) +SET(PRJ_NAME "EXAMPLE_${sampleName}") + +# --------------------------------------- +# Declare a new CMake Project: +# --------------------------------------- +PROJECT(${PRJ_NAME}) + +# These commands are needed by modern versions of CMake: +CMAKE_MINIMUM_REQUIRED(VERSION 2.4) +if(COMMAND cmake_policy) + cmake_policy(SET CMP0003 NEW) # Required by CMake 2.7+ +endif(COMMAND cmake_policy) + +# --------------------------------------------------------------------------- +# Set the output directory of each example to its corresponding subdirectory +# in the binary tree: +# --------------------------------------------------------------------------- +SET(EXECUTABLE_OUTPUT_PATH ".") + +# -------------------------------------------------------------------------- +# The list of "libs" which can be included can be found in: +# http://www.mrpt.org/Libraries +# +# The dependencies of a library are automatically added, so you only +# need to specify the top-most libraries your code depend on. +# -------------------------------------------------------------------------- +FIND_PACKAGE(MRPT REQUIRED base;gui;opengl;maps) + +# --------------------------------------------- +# TARGET: +# --------------------------------------------- +# Define the executable target: +ADD_EXECUTABLE(${sampleName} test.cpp ) + +SET_TARGET_PROPERTIES( + ${sampleName} + PROPERTIES + PROJECT_LABEL "(EXAMPLE) ${sampleName}") + +# Add special defines needed by this example, if any: +SET(MY_DEFS ) +IF(MY_DEFS) # If not empty + ADD_DEFINITIONS("-D${MY_DEFS}") +ENDIF(MY_DEFS) + +# Add the required libraries for linking: +TARGET_LINK_LIBRARIES(${sampleName} + ${MRPT_LIBS} # This is filled by FIND_PACKAGE(MRPT ...) + "C:/Users/Mariano/Programas/OpenNI2_32/Lib/OpenNI2.lib" # Optional extra libs... + ) + +# Set optimized building: +IF(CMAKE_COMPILER_IS_GNUCXX AND NOT CMAKE_BUILD_TYPE MATCHES "Debug") + SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -mtune=native") +ENDIF(CMAKE_COMPILER_IS_GNUCXX AND NOT CMAKE_BUILD_TYPE MATCHES "Debug") + + +# ------------------------------------------------------------------------- +# This part can be removed if you are compiling this program outside of +# the MRPT tree: +# ------------------------------------------------------------------------- +IF("${CMAKE_PROJECT_NAME}" STREQUAL "MRPT") # Fails if build outside of MRPT project. + DeclareAppDependencies(${sampleName} mrpt-base;mrpt-gui;mrpt-opengl;mrpt-maps) # Dependencies +ENDIF("${CMAKE_PROJECT_NAME}" STREQUAL "MRPT") +# ------------------------------------------------------------------------- + diff --git a/samples/openNI2_proximity_demo/test.cpp b/samples/openNI2_proximity_demo/test.cpp new file mode 100644 index 0000000000..f0905e865b --- /dev/null +++ b/samples/openNI2_proximity_demo/test.cpp @@ -0,0 +1,211 @@ +/* +---------------------------------------------------------------------------+ + | Mobile Robot Programming Toolkit (MRPT) | + | http://www.mrpt.org/ | + | | + | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file | + | See: http://www.mrpt.org/Authors - All rights reserved. | + | Released under BSD License. See details in http://www.mrpt.org/License | + +---------------------------------------------------------------------------+ */ + +#include +#include +#include +#include +#include + +using namespace mrpt; +using namespace std; + +//================================================================================================= +// +// This example illustrates how points closer than a RGBD camera threshold (0.3 - 0.5 m typically) +// can be detected with these cameras. This method finds pixels with a very high value in the +// infrared image and, therefore, it will fail if an external source of infrared light (sun) affects +// the camera... +// +// ================================================================================================= + + +int main ( int argc, char** argv ) +{ + openni::Status rc = openni::STATUS_OK; + + openni::Device device; + openni::VideoMode options; + openni::VideoStream depth, infrared; + + // Device is openned + //======================================================================================= + const char* deviceURI = openni::ANY_DEVICE; + if (argc > 1) + deviceURI = argv[1]; + + rc = openni::OpenNI::initialize(); + + if (rc != openni::STATUS_OK) { printf("After initialization:\n %s\n", openni::OpenNI::getExtendedError()); } + + rc = device.open(deviceURI); + + if (rc != openni::STATUS_OK) + { + printf("SimpleViewer: Device open failed:\n%s\n", openni::OpenNI::getExtendedError()); + openni::OpenNI::shutdown(); + return 1; + } + + // Create IR and Depth channels + //======================================================================================== + + rc = depth.create(device, openni::SENSOR_DEPTH); + if (rc == openni::STATUS_OK) + { + rc = depth.start(); + if (rc != openni::STATUS_OK) + { + printf("SimpleViewer: Couldn't start depth stream:\n%s\n", openni::OpenNI::getExtendedError()); + depth.destroy(); + } + } + else + { + printf("SimpleViewer: Couldn't find depth stream:\n%s\n", openni::OpenNI::getExtendedError()); + } + + + rc = infrared.create(device, openni::SENSOR_IR); + if (rc == openni::STATUS_OK) + { + rc = infrared.start(); + if (rc != openni::STATUS_OK) + { + printf("SimpleViewer: Couldn't start infrared stream:\n%s\n", openni::OpenNI::getExtendedError()); + infrared.destroy(); + } + } + else + { + printf("SimpleViewer: Couldn't find infrared stream:\n%s\n", openni::OpenNI::getExtendedError()); + } + + if (!depth.isValid() || !infrared.isValid()) + { + printf("SimpleViewer: No valid streams. Exiting\n"); + openni::OpenNI::shutdown(); + return 2; + } + + if (rc != openni::STATUS_OK) + { + openni::OpenNI::shutdown(); + return 3; + } + + + // Read resolution + //======================================================================================== + + options = infrared.getVideoMode(); + printf("\nInitial resolution IR (%d, %d)", options.getResolutionX(), options.getResolutionY()); + + options = depth.getVideoMode(); + printf("\nInitial resolution Depth (%d, %d) \n", options.getResolutionX(), options.getResolutionY()); + + + // Create scene + //======================================================================================== + + gui::CDisplayWindow3D window; + opengl::COpenGLScenePtr scene; + gui::global_settings::OCTREE_RENDER_MAX_POINTS_PER_NODE = 1000000; + window.setWindowTitle("Kinect frame"); + window.resize(800,600); + window.setPos(500,50); + window.setCameraZoom(5); + window.setCameraAzimuthDeg(-90); + window.setCameraElevationDeg(90); + scene = window.get3DSceneAndLock(); + + opengl::CSetOfLinesPtr lines = opengl::CSetOfLines::Create(); + lines->setLocation(0,0,0); + lines->setColor(0,0,1); + lines->setLineWidth(10); + lines->appendLine(-1,1,0,1,1,0); + lines->appendLine(1,1,0,1,-1,0); + lines->appendLine(1,-1,0,-1,-1,0); + lines->appendLine(-1,-1,0,-1,1,0); + scene->insert( lines ); + + opengl::CPointCloudPtr too_close = opengl::CPointCloud::Create(); + too_close->setPointSize(5); + too_close->enablePointSmooth(true); + too_close->setColor(1,0,0); + scene->insert( too_close ); + + opengl::CGridPlaneXYPtr grid = opengl::CGridPlaneXY::Create(-4,4,-4,4,0); + scene->insert( grid ); + + window.unlockAccess3DScene(); + window.addTextMessage(5,5, format("Push any key to exit")); + window.repaint(); + + + // Grab frames continuously and show saturated pixels + //======================================================================================== + + openni::VideoFrameRef framed, frameir; + const int ir_threshold = 500; + float x,y; + + while (!window.keyHit()) //Push any key to exit + { + infrared.readFrame(&frameir); + depth.readFrame(&framed); + + scene = window.get3DSceneAndLock(); + too_close->clear(); + + //Read one frame + if ((framed.getWidth() != frameir.getWidth()) || (framed.getHeight() != frameir.getHeight())) + { + cout << endl << "Both frames don't have the same size."; + } + else + { + const openni::DepthPixel* pDepthRow = (const openni::DepthPixel*)framed.getData(); + const openni::Grayscale16Pixel* pInfraredRow = (const openni::Grayscale16Pixel*)frameir.getData(); + int rowSize = frameir.getStrideInBytes() / sizeof(openni::Grayscale16Pixel); + + for (int yc = 0; yc < frameir.getHeight(); ++yc) + { + const openni::DepthPixel* pDepth = pDepthRow; + const openni::Grayscale16Pixel* pInfrared = pInfraredRow; + for (int xc = 0; xc < frameir.getWidth(); ++xc, ++pInfrared, ++pDepth) + { + + if ((*pInfrared > ir_threshold)&&(*pDepth == 0)) + { + x = -1.0f + float(2*xc)/float(frameir.getWidth()); + y = -1.0f + float(2*yc)/float(frameir.getHeight()); + too_close->insertPoint( x, -y, 0); + } + } + + pDepthRow += rowSize; + pInfraredRow += rowSize; + } + } + + system::sleep(10); + window.unlockAccess3DScene(); + window.repaint(); + + } + + infrared.destroy(); + depth.destroy(); + openni::OpenNI::shutdown(); + + return 0; +} + +