From 3c69946db486a12db53d564718f94abc1af5a5ec Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Sun, 11 Feb 2024 20:54:46 +0100 Subject: [PATCH 1/9] patch version bump --- appveyor.yml | 2 +- doc/source/doxygen-docs/changelog.md | 3 +++ package.xml | 2 +- version_prefix.txt | 2 +- 4 files changed, 6 insertions(+), 3 deletions(-) diff --git a/appveyor.yml b/appveyor.yml index bb4d632eca..1cc91b4ecf 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -1,5 +1,5 @@ # version format -version: 2.11.9-{branch}-build{build} +version: 2.11.10-{branch}-build{build} os: Visual Studio 2019 diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 4b75bdbab4..789f8ea28f 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,5 +1,8 @@ \page changelog Change Log +# Version 2.11.10: UNRELEASED +(none) + # Version 2.11.9: Released Feb 11th, 2024 - Changes in libraries: - \ref mrpt_vision_grp: diff --git a/package.xml b/package.xml index 36f540d862..0d8d57440c 100644 --- a/package.xml +++ b/package.xml @@ -7,7 +7,7 @@ mrpt2 - 2.11.9 + 2.11.10 Mobile Robot Programming Toolkit (MRPT) version 2.x Jose-Luis Blanco-Claraco diff --git a/version_prefix.txt b/version_prefix.txt index 442f347259..b0b0d26e12 100644 --- a/version_prefix.txt +++ b/version_prefix.txt @@ -1,4 +1,4 @@ -2.11.9 +2.11.10 # IMPORTANT: This file is parsed by CMake, don't add any comment to # the first line. # This file is used in both Windows and Linux scripts to automatically From 80d109060dbf7125d8988d2e28c4e9f369ae0f9c Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sun, 11 Feb 2024 21:20:10 +0100 Subject: [PATCH 2/9] CHeightGridMap2D: support any pointcloud insertion --- doc/source/doxygen-docs/changelog.md | 4 ++- libs/maps/src/maps/CHeightGridMap2D_Base.cpp | 27 +------------------- 2 files changed, 4 insertions(+), 27 deletions(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 789f8ea28f..598a5e1bed 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,7 +1,9 @@ \page changelog Change Log # Version 2.11.10: UNRELEASED -(none) +- Changes in libraries: + - \ref mrpt_maps_grp: + - mrpt::maps::CHeightGridMap2D: now supports integrating any point-cloud observation. # Version 2.11.9: Released Feb 11th, 2024 - Changes in libraries: diff --git a/libs/maps/src/maps/CHeightGridMap2D_Base.cpp b/libs/maps/src/maps/CHeightGridMap2D_Base.cpp index 4845bf8591..b060ab8633 100644 --- a/libs/maps/src/maps/CHeightGridMap2D_Base.cpp +++ b/libs/maps/src/maps/CHeightGridMap2D_Base.cpp @@ -140,32 +140,7 @@ bool CHeightGridMap2D_Base::dem_internal_insertObservation( // Points to insert: CSimplePointsMap thePointsMoved; - - if (IS_CLASS(obs, CObservation2DRangeScan)) - { - /******************************************************************** - OBSERVATION TYPE: CObservation2DRangeScan - ********************************************************************/ - const auto& o = static_cast(obs); - - // Create points map, if not created yet: - CPointsMap::TInsertionOptions opts; - const auto* thePoints = - o.buildAuxPointsMap(&opts); - - // And rotate to the robot pose: - thePointsMoved.changeCoordinatesReference(*thePoints, robotPose3D); - } - else if (IS_CLASS(obs, CObservationVelodyneScan)) - { - /******************************************************************** - OBSERVATION TYPE: CObservationVelodyneScan - ********************************************************************/ - const auto& o = static_cast(obs); - - // Create points map, if not created yet: - thePointsMoved.loadFromVelodyneScan(o, robotPose3D); - } + thePointsMoved.insertObservation(obs, robotPose); // Factorized insertion of points, for different observation classes: if (!thePointsMoved.empty()) From 969d59e80d54354dc6df77cb48fa44c02b63bde1 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Fri, 16 Feb 2024 10:41:15 +0100 Subject: [PATCH 3/9] Fix appstream debian warnings --- doc/source/doxygen-docs/changelog.md | 2 ++ ...gui.desktop => kinect_stereo_camera_calib_gui.desktop} | 2 +- .../{navlog-viewer.desktop => navlog_viewer.desktop} | 0 ...-kinematics.desktop => robotic_arm_kinematics.desktop} | 0 ...fo.xml => kinect_stereo_camera_calib_gui.metainfo.xml} | 4 ++-- ...log-viewer.metainfo.xml => navlog_viewer.metainfo.xml} | 4 ++-- ...s.metainfo.xml => robotic_arm_kinematics.metainfo.xml} | 8 ++++---- 7 files changed, 11 insertions(+), 9 deletions(-) rename share/applications/{kinect-stereo-camera-calib-gui.desktop => kinect_stereo_camera_calib_gui.desktop} (87%) rename share/applications/{navlog-viewer.desktop => navlog_viewer.desktop} (100%) rename share/applications/{robotic-arm-kinematics.desktop => robotic_arm_kinematics.desktop} (100%) rename share/metainfo/{kinect-stereo-camera-calib-gui.metainfo.xml => kinect_stereo_camera_calib_gui.metainfo.xml} (84%) rename share/metainfo/{navlog-viewer.metainfo.xml => navlog_viewer.metainfo.xml} (84%) rename share/metainfo/{robotic-arm-kinematics.metainfo.xml => robotic_arm_kinematics.metainfo.xml} (76%) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 598a5e1bed..3b323c49f0 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -4,6 +4,8 @@ - Changes in libraries: - \ref mrpt_maps_grp: - mrpt::maps::CHeightGridMap2D: now supports integrating any point-cloud observation. +- Others: + - Fix Debian appstream warnings on mrpt-apps. # Version 2.11.9: Released Feb 11th, 2024 - Changes in libraries: diff --git a/share/applications/kinect-stereo-camera-calib-gui.desktop b/share/applications/kinect_stereo_camera_calib_gui.desktop similarity index 87% rename from share/applications/kinect-stereo-camera-calib-gui.desktop rename to share/applications/kinect_stereo_camera_calib_gui.desktop index c3b493bc16..c71cfdc3c9 100644 --- a/share/applications/kinect-stereo-camera-calib-gui.desktop +++ b/share/applications/kinect_stereo_camera_calib_gui.desktop @@ -11,4 +11,4 @@ Categories=Science;Robotics;ArtificialIntelligence; StartupNotify=true Keywords=mrpt;camera;vision;computer vision;calibration; -Name[en_US]=kinect-stereo-camera-calib-gui.desktop +Name[en_US]=kinect_stereo_camera_calib_gui.desktop diff --git a/share/applications/navlog-viewer.desktop b/share/applications/navlog_viewer.desktop similarity index 100% rename from share/applications/navlog-viewer.desktop rename to share/applications/navlog_viewer.desktop diff --git a/share/applications/robotic-arm-kinematics.desktop b/share/applications/robotic_arm_kinematics.desktop similarity index 100% rename from share/applications/robotic-arm-kinematics.desktop rename to share/applications/robotic_arm_kinematics.desktop diff --git a/share/metainfo/kinect-stereo-camera-calib-gui.metainfo.xml b/share/metainfo/kinect_stereo_camera_calib_gui.metainfo.xml similarity index 84% rename from share/metainfo/kinect-stereo-camera-calib-gui.metainfo.xml rename to share/metainfo/kinect_stereo_camera_calib_gui.metainfo.xml index 3eb3638ceb..4a14618fb5 100644 --- a/share/metainfo/kinect-stereo-camera-calib-gui.metainfo.xml +++ b/share/metainfo/kinect_stereo_camera_calib_gui.metainfo.xml @@ -1,13 +1,13 @@ - org.mrpt.kinect-stereo-camera-calib-gui.desktop + org.mrpt.kinect_stereo_camera_calib_gui.desktop MIT kinect-stereo-calib Stereo Camera and Kinect Calibration GUI

Stereo Camera and Kinect Calibration GUI.

- kinect-stereo-camera-calib-gui.desktop + kinect_stereo_camera_calib_gui.desktop Application screenshot diff --git a/share/metainfo/navlog-viewer.metainfo.xml b/share/metainfo/navlog_viewer.metainfo.xml similarity index 84% rename from share/metainfo/navlog-viewer.metainfo.xml rename to share/metainfo/navlog_viewer.metainfo.xml index 2f8905200b..e8631f7977 100644 --- a/share/metainfo/navlog-viewer.metainfo.xml +++ b/share/metainfo/navlog_viewer.metainfo.xml @@ -1,13 +1,13 @@ - org.mrpt.navlog-viewer.desktop + org.mrpt.navlog_viewer.desktop MIT navlog-viewer Navigation log viewer

Navigation log viewer.

- navlog-viewer.desktop + navlog_viewer.desktop Application screenshot diff --git a/share/metainfo/robotic-arm-kinematics.metainfo.xml b/share/metainfo/robotic_arm_kinematics.metainfo.xml similarity index 76% rename from share/metainfo/robotic-arm-kinematics.metainfo.xml rename to share/metainfo/robotic_arm_kinematics.metainfo.xml index b3a034dc8b..44649497d1 100644 --- a/share/metainfo/robotic-arm-kinematics.metainfo.xml +++ b/share/metainfo/robotic_arm_kinematics.metainfo.xml @@ -1,13 +1,13 @@ - org.mrpt.robotic-arm-kinematics.desktop + org.mrpt.robotic_arm_kinematics.desktop MIT robotic-arm-kinematics - GUI to practice and learn the Denavit-Hartenberg (DH) parameters or robotic arm manipulators + GUI to practice and learn the Denavit-Hartenberg (DH) parameters -

GUI to practice and learn the Denavit-Hartenberg (DH) parameters or robotic arm manipulators.

+

GUI to practice and learn the Denavit-Hartenberg (DH) parameters for robotic arm manipulators.

- robotic-arm-kinematics.desktop + robotic_arm_kinematics.desktop Application screenshot From 031d1f0f6697d5c8293d8d506161b70c44f80ff7 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Tue, 16 Jan 2024 11:35:22 +0100 Subject: [PATCH 4/9] progress update to cv5 API --- .../mrpt/3rdparty/do_opencv_includes.h | 7 +- libs/img/src/CImage.cpp | 2 +- libs/opengl/src/Shader.cpp | 2 - libs/vision/src/checkerboard_find_corners.cpp | 26 +-- .../src/checkerboard_multiple_detector.cpp | 53 +++-- .../src/checkerboard_ocamcalib_detector.cpp | 196 ++++++++---------- .../src/checkerboard_ocamcalib_detector.h | 14 +- 7 files changed, 141 insertions(+), 159 deletions(-) diff --git a/libs/img/include/mrpt/3rdparty/do_opencv_includes.h b/libs/img/include/mrpt/3rdparty/do_opencv_includes.h index 6138a067ee..b93a35dd80 100644 --- a/libs/img/include/mrpt/3rdparty/do_opencv_includes.h +++ b/libs/img/include/mrpt/3rdparty/do_opencv_includes.h @@ -49,10 +49,11 @@ // C API: #include -#include -#include +// CPP +#include +#include #ifdef HAVE_OPENCV_VIDEOIO -#include +#include #endif /// start added by Raghavender Sahdev diff --git a/libs/img/src/CImage.cpp b/libs/img/src/CImage.cpp index c996fc7d4b..da0032d1b2 100644 --- a/libs/img/src/CImage.cpp +++ b/libs/img/src/CImage.cpp @@ -1007,7 +1007,7 @@ bool my_img_to_grayscale(const cv::Mat& src, cv::Mat& dest) #endif // OpenCV Method: - cv::cvtColor(src, dest, CV_BGR2GRAY); + cv::cvtColor(src, dest, cv::COLOR_BGR2GRAY); return false; } } // namespace diff --git a/libs/opengl/src/Shader.cpp b/libs/opengl/src/Shader.cpp index c4aff5c7c3..b0168b96c6 100644 --- a/libs/opengl/src/Shader.cpp +++ b/libs/opengl/src/Shader.cpp @@ -189,8 +189,6 @@ void Program::clear() { if (!m_data || !m_data->program) return; - MRPT_TODO("Remove this??"); - // If we are in the same thread that created us, ok, clean up. // Otherwise, postpone it for later on: if (m_data->linkedThread == std::this_thread::get_id()) diff --git a/libs/vision/src/checkerboard_find_corners.cpp b/libs/vision/src/checkerboard_find_corners.cpp index dded2dcd76..7fa74396b1 100644 --- a/libs/vision/src/checkerboard_find_corners.cpp +++ b/libs/vision/src/checkerboard_find_corners.cpp @@ -55,7 +55,7 @@ bool mrpt::vision::findChessboardCorners( const int CORNERS_COUNT = check_size_x * check_size_y; - vector corners_list; + vector corners_list; corners_count = CORNERS_COUNT; corners_list.resize(CORNERS_COUNT); @@ -93,12 +93,12 @@ bool mrpt::vision::findChessboardCorners( if (corners_found) { - IplImage iplImg = cvIplImage(cvImg); // Refine corners: - cvFindCornerSubPix( - &iplImg, &corners_list[0], corners_count, cvSize(5, 5), // window - cvSize(-1, -1), - cvTermCriteria(CV_TERMCRIT_ITER | CV_TERMCRIT_EPS, 10, 0.01f)); + cv::cornerSubPix( + cvImg, corners_list, cv::Size(5, 5), // window + cv::Size(-1, -1), + cv::TermCriteria( + cv::TermCriteria::MAX_ITER | cv::TermCriteria::EPS, 10, 0.01f)); // save the corners in the data structure: int y; @@ -141,9 +141,8 @@ void mrpt::vision::findMultipleChessboardsCorners( // Grayscale version: const CImage img(in_img, FAST_REF_OR_CONVERT_TO_GRAY); const cv::Mat img_m = img.asCvMat(SHALLOW_COPY); - const IplImage img_ipl = cvIplImage(img_m); - std::vector> corners_list; + std::vector> corners_list; // Return: -1: errors, 0: not found, 1: found OK bool corners_found = find_chessboard_corners_multiple( @@ -159,11 +158,12 @@ void mrpt::vision::findMultipleChessboardsCorners( { ASSERT_(corners_list[i].size() == check_size_x * check_size_y); - cvFindCornerSubPix( - &img_ipl, &corners_list[i][0], check_size_x * check_size_y, - cvSize(5, 5), // window - cvSize(-1, -1), - cvTermCriteria(CV_TERMCRIT_ITER | CV_TERMCRIT_EPS, 10, 0.01f)); + cv::cornerSubPix( + img_m, corners_list, cv::Size(5, 5), // window + cv::Size(-1, -1), + cv::TermCriteria( + cv::TermCriteria::MAX_ITER | cv::TermCriteria::EPS, 10, + 0.01f)); // save the corners in the data structure: for (unsigned int y = 0, k = 0; y < check_size_y; y++) diff --git a/libs/vision/src/checkerboard_multiple_detector.cpp b/libs/vision/src/checkerboard_multiple_detector.cpp index bb40514772..e8d1f32451 100644 --- a/libs/vision/src/checkerboard_multiple_detector.cpp +++ b/libs/vision/src/checkerboard_multiple_detector.cpp @@ -36,7 +36,7 @@ using namespace std; // Return: true: found OK bool find_chessboard_corners_multiple( const CImage& img_, CvSize pattern_size, - std::vector>& out_corners) + std::vector>& out_corners) { // Assure it's a grayscale image: const CImage img(img_, FAST_REF_OR_CONVERT_TO_GRAY); @@ -73,23 +73,28 @@ bool find_chessboard_corners_multiple( } // JL: Move these constructors out of the loops: - IplConvKernel* kernel_cross = - cvCreateStructuringElementEx(3, 3, 1, 1, CV_SHAPE_CROSS, nullptr); - IplConvKernel* kernel_rect = - cvCreateStructuringElementEx(3, 3, 1, 1, CV_SHAPE_RECT, nullptr); - - static int kernel_diag1_vals[9] = {1, 0, 0, 0, 1, 0, 0, 0, 1}; - IplConvKernel* kernel_diag1 = cvCreateStructuringElementEx( - 3, 3, 1, 1, CV_SHAPE_CUSTOM, kernel_diag1_vals); - static int kernel_diag2_vals[9] = {0, 0, 1, 0, 1, 0, 1, 0, 0}; - IplConvKernel* kernel_diag2 = cvCreateStructuringElementEx( - 3, 3, 1, 1, CV_SHAPE_CUSTOM, kernel_diag2_vals); - static int kernel_horz_vals[9] = {0, 0, 0, 1, 1, 1, 0, 0, 0}; - IplConvKernel* kernel_horz = cvCreateStructuringElementEx( - 3, 3, 1, 1, CV_SHAPE_CUSTOM, kernel_horz_vals); - static int kernel_vert_vals[9] = {0, 1, 0, 0, 1, 0, 0, 1, 0}; - IplConvKernel* kernel_vert = cvCreateStructuringElementEx( - 3, 3, 1, 1, CV_SHAPE_CUSTOM, kernel_vert_vals); + const auto kernel_cross = + cv::getStructuringElement(cv::MORPH_CROSS, {3, 3}); + const auto kernel_rect = cv::getStructuringElement(cv::MORPH_RECT, {3, 3}); + + // clang-format off + const cv::Mat kernel_diag1 = (cv::Mat_(3,3) << + 1, 0, 0, + 0, 1, 0, + 0, 0, 1 ); + const cv::Mat kernel_diag2 = (cv::Mat_(3,3) << + 0, 0, 1, + 0, 1, 0, + 1, 0, 0 ); + const cv::Mat kernel_horz = (cv::Mat_(3,3) << + 0, 0, 0, + 1, 1, 1, + 0, 0, 0 ); + const cv::Mat kernel_vert = (cv::Mat_(3,3) << + 0, 1, 0, + 0, 1, 0, + 0, 1, 0 ); + // clang-format on // For image binarization (thresholding) // we use an adaptive threshold with a gaussian mask @@ -100,7 +105,7 @@ bool find_chessboard_corners_multiple( cv::adaptiveThreshold( img.asCvMat(SHALLOW_COPY), thresh_img.asCvMat(SHALLOW_COPY), 255, - CV_ADAPTIVE_THRESH_GAUSSIAN_C, CV_THRESH_BINARY, block_size, 0); + cv::ADAPTIVE_THRESH_GAUSSIAN_C, cv::THRESH_BINARY, block_size, 0); thresh_img_save = thresh_img.makeDeepCopy(); @@ -269,7 +274,7 @@ bool find_chessboard_corners_multiple( if (out_corners.empty() || min_dist > 80) { - vector pts; + vector pts; if (1 == myQuads2Points(*it, pattern_size, pts)) // and populate it now. { @@ -281,14 +286,6 @@ bool find_chessboard_corners_multiple( } } - // Free mem: - cvReleaseStructuringElement(&kernel_cross); - cvReleaseStructuringElement(&kernel_rect); - cvReleaseStructuringElement(&kernel_diag1); - cvReleaseStructuringElement(&kernel_diag2); - cvReleaseStructuringElement(&kernel_horz); - cvReleaseStructuringElement(&kernel_vert); - return !out_corners.empty(); } diff --git a/libs/vision/src/checkerboard_ocamcalib_detector.cpp b/libs/vision/src/checkerboard_ocamcalib_detector.cpp index 28c0caa0d9..9a8f6dfeb7 100644 --- a/libs/vision/src/checkerboard_ocamcalib_detector.cpp +++ b/libs/vision/src/checkerboard_ocamcalib_detector.cpp @@ -80,67 +80,65 @@ using namespace std; // JL: Refactored code from within cvFindChessboardCorners3() and alternative // algorithm: bool do_special_dilation( - CImage& thresh_img, const int dilations, IplConvKernel* kernel_cross, - IplConvKernel* kernel_rect, IplConvKernel* kernel_diag1, - IplConvKernel* kernel_diag2, IplConvKernel* kernel_horz, - IplConvKernel* kernel_vert) + CImage& thresh_img, const int dilations, const cv::Mat& kernel_cross, + const cv::Mat& kernel_rect, const cv::Mat& kernel_diag1, + const cv::Mat& kernel_diag2, const cv::Mat& kernel_horz, + const cv::Mat& kernel_vert) { - cv::Mat m = thresh_img.asCvMat(SHALLOW_COPY); - IplImage i = cvIplImage(m); - IplImage* ipl = &i; + cv::Mat im = thresh_img.asCvMat(SHALLOW_COPY); bool isLast = false; switch (dilations) { case 37: - cvDilate(ipl, ipl, kernel_cross, 1); + cv::dilate(im, im, kernel_cross); isLast = true; [[fallthrough]]; - case 36: cvErode(ipl, ipl, kernel_rect, 1); [[fallthrough]]; - case 35: cvDilate(ipl, ipl, kernel_vert, 1); [[fallthrough]]; - case 34: cvDilate(ipl, ipl, kernel_vert, 1); [[fallthrough]]; - case 33: cvDilate(ipl, ipl, kernel_vert, 1); [[fallthrough]]; - case 32: cvDilate(ipl, ipl, kernel_vert, 1); [[fallthrough]]; - case 31: cvDilate(ipl, ipl, kernel_vert, 1); break; - - case 30: cvDilate(ipl, ipl, kernel_cross, 1); [[fallthrough]]; - case 29: cvErode(ipl, ipl, kernel_rect, 1); [[fallthrough]]; - case 28: cvDilate(ipl, ipl, kernel_horz, 1); [[fallthrough]]; - case 27: cvDilate(ipl, ipl, kernel_horz, 1); [[fallthrough]]; - case 26: cvDilate(ipl, ipl, kernel_horz, 1); [[fallthrough]]; - case 25: cvDilate(ipl, ipl, kernel_horz, 1); [[fallthrough]]; - case 24: cvDilate(ipl, ipl, kernel_horz, 1); break; - - case 23: cvDilate(ipl, ipl, kernel_diag2, 1); [[fallthrough]]; - case 22: cvDilate(ipl, ipl, kernel_diag1, 1); [[fallthrough]]; - case 21: cvDilate(ipl, ipl, kernel_diag2, 1); [[fallthrough]]; - case 20: cvDilate(ipl, ipl, kernel_diag1, 1); [[fallthrough]]; - case 19: cvDilate(ipl, ipl, kernel_diag2, 1); [[fallthrough]]; - case 18: cvDilate(ipl, ipl, kernel_diag1, 1); break; - - case 17: cvDilate(ipl, ipl, kernel_diag2, 1); [[fallthrough]]; - case 16: cvDilate(ipl, ipl, kernel_diag2, 1); [[fallthrough]]; - case 15: cvDilate(ipl, ipl, kernel_diag2, 1); [[fallthrough]]; - case 14: cvDilate(ipl, ipl, kernel_diag2, 1); break; - - case 13: cvDilate(ipl, ipl, kernel_diag1, 1); [[fallthrough]]; - case 12: cvDilate(ipl, ipl, kernel_diag1, 1); [[fallthrough]]; - case 11: cvDilate(ipl, ipl, kernel_diag1, 1); [[fallthrough]]; - case 10: cvDilate(ipl, ipl, kernel_diag1, 1); break; - - case 9: cvDilate(ipl, ipl, kernel_cross, 1); [[fallthrough]]; - case 8: cvErode(ipl, ipl, kernel_rect, 1); [[fallthrough]]; - case 7: cvDilate(ipl, ipl, kernel_cross, 1); [[fallthrough]]; + case 36: cv::erode(im, im, kernel_rect); [[fallthrough]]; + case 35: cv::dilate(im, im, kernel_vert); [[fallthrough]]; + case 34: cv::dilate(im, im, kernel_vert); [[fallthrough]]; + case 33: cv::dilate(im, im, kernel_vert); [[fallthrough]]; + case 32: cv::dilate(im, im, kernel_vert); [[fallthrough]]; + case 31: cv::dilate(im, im, kernel_vert); break; + + case 30: cv::dilate(im, im, kernel_cross); [[fallthrough]]; + case 29: cv::erode(im, im, kernel_rect); [[fallthrough]]; + case 28: cv::dilate(im, im, kernel_horz); [[fallthrough]]; + case 27: cv::dilate(im, im, kernel_horz); [[fallthrough]]; + case 26: cv::dilate(im, im, kernel_horz); [[fallthrough]]; + case 25: cv::dilate(im, im, kernel_horz); [[fallthrough]]; + case 24: cv::dilate(im, im, kernel_horz); break; + + case 23: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; + case 22: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; + case 21: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; + case 20: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; + case 19: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; + case 18: cv::dilate(im, im, kernel_diag1); break; + + case 17: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; + case 16: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; + case 15: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; + case 14: cv::dilate(im, im, kernel_diag2); break; + + case 13: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; + case 12: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; + case 11: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; + case 10: cv::dilate(im, im, kernel_diag1); break; + + case 9: cv::dilate(im, im, kernel_cross); [[fallthrough]]; + case 8: cv::erode(im, im, kernel_rect); [[fallthrough]]; + case 7: cv::dilate(im, im, kernel_cross); [[fallthrough]]; case 6: - cvDilate(ipl, ipl, kernel_diag2, 1); + cv::dilate(im, im, kernel_diag2); isLast = true; [[fallthrough]]; - case 5: cvDilate(ipl, ipl, kernel_diag1, 1); [[fallthrough]]; - case 4: cvDilate(ipl, ipl, kernel_rect, 1); [[fallthrough]]; - case 3: cvErode(ipl, ipl, kernel_cross, 1); [[fallthrough]]; - case 2: cvDilate(ipl, ipl, kernel_rect, 1); [[fallthrough]]; - case 1: cvDilate(ipl, ipl, kernel_cross, 1); [[fallthrough]]; + case 5: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; + case 4: cv::dilate(im, im, kernel_rect); [[fallthrough]]; + case 3: cv::erode(im, im, kernel_cross); [[fallthrough]]; + case 2: cv::dilate(im, im, kernel_rect); [[fallthrough]]; + case 1: cv::dilate(im, im, kernel_cross); [[fallthrough]]; case 0: /* first try: do nothing to the image */ break; }; @@ -153,7 +151,7 @@ bool do_special_dilation( // Return: -1: errors, 0: not found, 1: found OK int cvFindChessboardCorners3( const CImage& img_, CvSize pattern_size, - std::vector& out_corners) + std::vector& out_corners) { // PART 0: INITIALIZATION //----------------------------------------------------------------------- @@ -200,23 +198,28 @@ int cvFindChessboardCorners3( CH_GRAY); // = cvCreateMat( img->rows, img->cols, CV_8UC1 ); // JL: Move these constructors out of the loops: - IplConvKernel* kernel_cross = - cvCreateStructuringElementEx(3, 3, 1, 1, CV_SHAPE_CROSS, nullptr); - IplConvKernel* kernel_rect = - cvCreateStructuringElementEx(3, 3, 1, 1, CV_SHAPE_RECT, nullptr); - - static int kernel_diag1_vals[9] = {1, 0, 0, 0, 1, 0, 0, 0, 1}; - IplConvKernel* kernel_diag1 = cvCreateStructuringElementEx( - 3, 3, 1, 1, CV_SHAPE_CUSTOM, kernel_diag1_vals); - static int kernel_diag2_vals[9] = {0, 0, 1, 0, 1, 0, 1, 0, 0}; - IplConvKernel* kernel_diag2 = cvCreateStructuringElementEx( - 3, 3, 1, 1, CV_SHAPE_CUSTOM, kernel_diag2_vals); - static int kernel_horz_vals[9] = {0, 0, 0, 1, 1, 1, 0, 0, 0}; - IplConvKernel* kernel_horz = cvCreateStructuringElementEx( - 3, 3, 1, 1, CV_SHAPE_CUSTOM, kernel_horz_vals); - static int kernel_vert_vals[9] = {0, 1, 0, 0, 1, 0, 0, 1, 0}; - IplConvKernel* kernel_vert = cvCreateStructuringElementEx( - 3, 3, 1, 1, CV_SHAPE_CUSTOM, kernel_vert_vals); + const auto kernel_cross = + cv::getStructuringElement(cv::MORPH_CROSS, {3, 3}); + const auto kernel_rect = cv::getStructuringElement(cv::MORPH_RECT, {3, 3}); + + // clang-format off + const cv::Mat kernel_diag1 = (cv::Mat_(3,3) << + 1, 0, 0, + 0, 1, 0, + 0, 0, 1 ); + const cv::Mat kernel_diag2 = (cv::Mat_(3,3) << + 0, 0, 1, + 0, 1, 0, + 1, 0, 0 ); + const cv::Mat kernel_horz = (cv::Mat_(3,3) << + 0, 0, 0, + 1, 1, 1, + 0, 0, 0 ); + const cv::Mat kernel_vert = (cv::Mat_(3,3) << + 0, 1, 0, + 0, 1, 0, + 0, 1, 0 ); + // clang-format on // For image binarization (thresholding) // we use an adaptive threshold with a gaussian mask @@ -227,7 +230,7 @@ int cvFindChessboardCorners3( cv::adaptiveThreshold( img.asCvMat(SHALLOW_COPY), thresh_img.asCvMat(SHALLOW_COPY), 255, - CV_ADAPTIVE_THRESH_GAUSSIAN_C, CV_THRESH_BINARY, block_size, 0); + cv::ADAPTIVE_THRESH_GAUSSIAN_C, cv::THRESH_BINARY, block_size, 0); thresh_img_save = thresh_img.makeDeepCopy(); @@ -334,7 +337,7 @@ int cvFindChessboardCorners3( // If enough corners have been found already, then there is no need for PART // 2 ->EXIT // JLBC for MRPT: Don't save to Matlab files (mrWriteCorners), but to - // "CvPoint2D32f *out_corners": + // "cv::Point2f *out_corners": // Return true on success in finding all the quads. found = myQuads2Points(output_quad_group, pattern_size, out_corners); @@ -421,14 +424,6 @@ int cvFindChessboardCorners3( } // JL: Was label "exit:", but again, http://xkcd.com/292/ ;-) - // Free mem: - cvReleaseStructuringElement(&kernel_cross); - cvReleaseStructuringElement(&kernel_rect); - cvReleaseStructuringElement(&kernel_diag1); - cvReleaseStructuringElement(&kernel_diag2); - cvReleaseStructuringElement(&kernel_horz); - cvReleaseStructuringElement(&kernel_vert); - /* // MARTIN: found = mrWriteCorners( output_quad_group, max_count, pattern_size, @@ -476,7 +471,7 @@ void icvCleanFoundConnectedQuads( { cv::MemStorage temp_storage; // JL: "Modernized" to use C++ STL stuff. - CvPoint2D32f center = cvPoint2D32f(0, 0); + cv::Point2f center = cv::Point2f(0, 0); // Number of quads this pattern should contain const size_t expected_quads_count = @@ -489,7 +484,7 @@ void icvCleanFoundConnectedQuads( if (nQuads <= expected_quads_count) return; // Nothing to be done. // Create an array of quadrangle centers - vector centers(nQuads); + vector centers(nQuads); temp_storage = cv::MemStorage(cvCreateMemStorage(0)); // make also the list of squares areas, so we can discriminate by @@ -500,12 +495,12 @@ void icvCleanFoundConnectedQuads( for (size_t i = 0; i < nQuads; i++) { - CvPoint2D32f ci = cvPoint2D32f(0, 0); + cv::Point2f ci = cv::Point2f(0, 0); CvCBQuad::Ptr& q = quad_group[i]; for (size_t j = 0; j < 4; j++) { - CvPoint2D32f pt = q->corners[j]->pt; + cv::Point2f pt = q->corners[j]->pt; ci.x += pt.x; ci.y += pt.y; } @@ -585,7 +580,7 @@ void icvCleanFoundConnectedQuads( for (size_t skip = 0; skip < quad_group.size(); skip++) { // get bounding rectangle - CvPoint2D32f temp = centers[skip]; + cv::Point2f temp = centers[skip]; centers[skip] = center; CvMat pointMat = cvMat(1, quad_group.size(), CV_32FC2, ¢ers[0]); @@ -1173,7 +1168,7 @@ void mrFindQuadNeighbors2(std::vector& quads, int dilation) // For each corner of this quadrangle for (size_t i = 0; i < 4; i++) { - CvPoint2D32f pt; + cv::Point2f pt; float min_dist = FLT_MAX; int closest_corner_idx = -1; CvCBQuad::Ptr closest_quad; @@ -1434,7 +1429,7 @@ int mrAugmentBestRun( // For each corner of this quadrangle for (int i = 0; i < 4; i++) { - CvPoint2D32f pt; + cv::Point2f pt; float min_dist = FLT_MAX; int closest_corner_idx = -1; CvCBQuad::Ptr closest_quad; @@ -1805,34 +1800,25 @@ int icvGenerateQuads( // Initializations int quad_count = 0; - // Create temporary storage for contours and the sequence of pointers to - // found quadrangles - cv::MemStorage temp_storage = cv::MemStorage(cvCreateMemStorage(0)); - - CvSeq* src_contour = nullptr; - CvSeq* root; // cv::Seq<> root; // - CvContourEx* board = nullptr; - CvContourScanner scanner; - // Empiric sower bound for the size of allowable quadrangles. // MARTIN, modified: Added "*0.1" in order to find smaller quads. const int min_size = cvRound(image.getWidth() * image.getHeight() * .03 * 0.01 * 0.92 * 0.1); - root = cvCreateSeq(0, sizeof(CvSeq), sizeof(CvSeq*), temp_storage); - // Initialize contour retrieving routine cv::Mat im_mat = image.asCvMat(SHALLOW_COPY); - IplImage im_ipl = cvIplImage(im_mat); - scanner = cvStartFindContours( - &im_ipl, temp_storage, sizeof(CvContourEx), CV_RETR_CCOMP, - CV_CHAIN_APPROX_SIMPLE); + std::vector> contours; + std::vector hierarchy; + + cv::findContours( + im_mat, contours, hierarchy, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE); // Get all the contours one by one - while ((src_contour = cvFindNextContour(scanner)) != nullptr) + for (const auto& contour : contours) { - CvSeq* dst_contour = nullptr; - CvRect rect = ((CvContour*)src_contour)->rect; + contour. + + CvRect rect = ((CvContour*)src_contour)->rect; // Reject contours with a too small perimeter and contours which are // completely surrounded by another contour @@ -1913,7 +1899,7 @@ int icvGenerateQuads( } // Finish contour retrieving - cvEndFindContours(&scanner); + // cvEndFindContours(&scanner); // Allocate quad & corner buffers out_quads.clear(); @@ -1939,7 +1925,7 @@ int icvGenerateQuads( assert(src_contour->total == 4); for (int i = 0; i < 4; i++) { - CvPoint2D32f pt = + cv::Point2f pt = cvPointTo32f(*(CvPoint*)cvGetSeqElem(src_contour, i)); CvCBCorner::Ptr& corner = out_corners [quad_count * 4 + i]; // &(*out_corners)[quad_count*4 @@ -1976,7 +1962,7 @@ int icvGenerateQuads( // Return 1 on success in finding all the quads, 0 on didn't, -1 on error. int myQuads2Points( const std::vector& output_quads, const CvSize& pattern_size, - std::vector& out_corners) + std::vector& out_corners) { // Initialize out_corners.clear(); diff --git a/libs/vision/src/checkerboard_ocamcalib_detector.h b/libs/vision/src/checkerboard_ocamcalib_detector.h index a61c64f65f..536af47b07 100644 --- a/libs/vision/src/checkerboard_ocamcalib_detector.h +++ b/libs/vision/src/checkerboard_ocamcalib_detector.h @@ -37,7 +37,7 @@ struct CvCBCorner { using Ptr = std::shared_ptr; CvCBCorner() = default; - CvPoint2D32f pt; // X and y coordinates + cv::Point2f pt; // X and y coordinates int row{-1000}; // Row and column of the corner int column{-1000}; // in the found pattern bool needsNeighbor; // Does the corner require a neighbor? @@ -70,12 +70,12 @@ struct CvCBQuad // Return: -1: errors, 0: not found, 1: found OK int cvFindChessboardCorners3( const mrpt::img::CImage& img_, CvSize pattern_size, - std::vector& out_corners); + std::vector& out_corners); // Return: true: found OK bool find_chessboard_corners_multiple( const mrpt::img::CImage& img_, CvSize pattern_size, - std::vector>& out_corners); + std::vector>& out_corners); //=========================================================================== // INTERNAL FUNCTION PROTOTYPES @@ -106,7 +106,7 @@ void icvCleanFoundConnectedQuads( // JL: Return 1 on success in finding all the quads, 0 on didn't, -1 on error. int myQuads2Points( const std::vector& output_quads, const CvSize& pattern_size, - std::vector& out_corners); + std::vector& out_corners); // JL: Make unique all the (smart pointers-pointed) objects in the list and // neighbors lists. @@ -116,8 +116,8 @@ void quadListMakeUnique(std::vector& quads); // algorithm: bool do_special_dilation( mrpt::img::CImage& thresh_img, const int dilations, - IplConvKernel* kernel_cross, IplConvKernel* kernel_rect, - IplConvKernel* kernel_diag1, IplConvKernel* kernel_diag2, - IplConvKernel* kernel_horz, IplConvKernel* kernel_vert); + const cv::Mat& kernel_cross, const cv::Mat& kernel_rect, + const cv::Mat& kernel_diag1, const cv::Mat& kernel_diag2, + const cv::Mat& kernel_horz, const cv::Mat& kernel_vert); #endif // MRPT_HAS_OPENCV From acd3f9fdb820f0055c77a816696ffd65cb226442 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco-Claraco Date: Fri, 16 Feb 2024 14:19:12 +0100 Subject: [PATCH 5/9] Simplify and fixes for opencv5 --- .../src/visual_odometry.cpp | 23 +- apps/camera-calib/CDlgCalibWizardOnline.cpp | 12 +- apps/camera-calib/CDlgCalibWizardOnline.h | 2 - apps/camera-calib/CDlgPoseEst.cpp | 12 +- apps/camera-calib/CDlgPoseEst.h | 2 - apps/camera-calib/camera_calib_guiMain.cpp | 12 +- apps/camera-calib/camera_calib_guiMain.h | 1 - doc/source/doxygen-docs/changelog.md | 3 + .../example-vision_multiple_checkerboards.md | 5 - doc/source/examples.rst | 1 - .../mrpt/hwdrivers/CImageGrabber_OpenCV.h | 12 +- libs/hwdrivers/src/CImageGrabber_OpenCV.cpp | 22 +- .../mrpt/vision/chessboard_camera_calib.h | 8 +- .../mrpt/vision/chessboard_find_corners.h | 45 +- libs/vision/src/CVideoFileWriter.cpp | 2 +- libs/vision/src/checkerboard_cam_calib.cpp | 11 +- libs/vision/src/checkerboard_find_corners.cpp | 126 +- .../src/checkerboard_multiple_detector.cpp | 292 --- .../src/checkerboard_ocamcalib_detector.cpp | 2171 ----------------- .../src/checkerboard_ocamcalib_detector.h | 123 - libs/vision/src/vision_utils.cpp | 2 +- samples/CMakeLists.txt | 1 - .../vision_checkerboard_detectors/test.cpp | 32 +- .../CMakeLists.txt | 62 - .../vision_multiple_checkerboards/test.cpp | 105 - .../test_3_checkerboards_5x4.jpg | Bin 111376 -> 0 bytes 26 files changed, 59 insertions(+), 3028 deletions(-) delete mode 100644 doc/source/doxygen-docs/example-vision_multiple_checkerboards.md delete mode 100644 libs/vision/src/checkerboard_multiple_detector.cpp delete mode 100644 libs/vision/src/checkerboard_ocamcalib_detector.cpp delete mode 100644 libs/vision/src/checkerboard_ocamcalib_detector.h delete mode 100644 samples/vision_multiple_checkerboards/CMakeLists.txt delete mode 100644 samples/vision_multiple_checkerboards/test.cpp delete mode 100644 samples/vision_multiple_checkerboards/test_3_checkerboards_5x4.jpg diff --git a/apps/benchmarking-image-features/src/visual_odometry.cpp b/apps/benchmarking-image-features/src/visual_odometry.cpp index 94931dd566..f0bfd578f3 100644 --- a/apps/benchmarking-image-features/src/visual_odometry.cpp +++ b/apps/benchmarking-image-features/src/visual_odometry.cpp @@ -240,7 +240,7 @@ VisualOdometry::VisualOdometry() * Generate VO main funciton * ************************************************************************************************/ Mat VisualOdometry::generateVO( - CFeatureExtraction fext, int numFeats, + CFeatureExtraction fExt, int NumFeats, std::array file_paths, int feat_type) { string dataset = file_paths[0]; @@ -248,8 +248,8 @@ Mat VisualOdometry::generateVO( string calibration_file = file_paths[2]; cnt.setValue(0); // this->detector_selected = detector_selected; - this->fext = fext; - this->numFeats = numFeats; + this->fext = fExt; + this->numFeats = NumFeats; Mat img_1, img_2; Mat R_f, t_f; // the final rotation and tranlation vectors containing the // transform @@ -318,9 +318,9 @@ Mat VisualOdometry::generateVO( // double focal = 718.8560; // cv::Point2d pp(607.1928, 185.2157); // recovering the pose and the essential matrix - Mat E, R, t, mask; - E = findEssentialMat(points2, points1, focal, pp, RANSAC, 0.999, 1.0, mask); - recoverPose(E, points2, points1, R, t, focal, pp, mask); + Mat E, R, t; + E = findEssentialMat(points2, points1, focal, pp); + cv::recoverPose(E, points2, points1, R, t, focal, pp); Mat prevImage = img_2; Mat currImage; @@ -354,13 +354,12 @@ Mat VisualOdometry::generateVO( img3.loadFromFile(filename); cvtColor(currImage_c, currImage, COLOR_BGR2GRAY); - vector status; + vector Status; featureTracking( - prevImage, currImage, prevFeatures, currFeatures, status); + prevImage, currImage, prevFeatures, currFeatures, Status); - E = findEssentialMat( - currFeatures, prevFeatures, focal, pp, RANSAC, 0.999, 1.0, mask); - recoverPose(E, currFeatures, prevFeatures, R, t, focal, pp, mask); + E = findEssentialMat(currFeatures, prevFeatures, focal, pp, RANSAC); + recoverPose(E, currFeatures, prevFeatures, R, t, focal, pp); Mat prevPts(2, prevFeatures.size(), CV_64F), currPts(2, currFeatures.size(), CV_64F); @@ -394,7 +393,7 @@ Mat VisualOdometry::generateVO( { featureDetection(img3, prevFeatures, feat_type); featureTracking( - prevImage, currImage, prevFeatures, currFeatures, status); + prevImage, currImage, prevFeatures, currFeatures, Status); } prevImage = currImage.clone(); diff --git a/apps/camera-calib/CDlgCalibWizardOnline.cpp b/apps/camera-calib/CDlgCalibWizardOnline.cpp index d486b0606f..7baef73a19 100644 --- a/apps/camera-calib/CDlgCalibWizardOnline.cpp +++ b/apps/camera-calib/CDlgCalibWizardOnline.cpp @@ -135,13 +135,6 @@ CDlgCalibWizardOnline::CDlgCalibWizardOnline( StaticBoxSizer4->Add(FlexGridSizer17, 1, wxEXPAND, 0); FlexGridSizer6->Add( StaticBoxSizer4, 1, wxALL | wxALIGN_LEFT | wxALIGN_CENTER_VERTICAL, 2); - wxString __wxRadioBoxChoices_1[2] = { - _("OpenCV\'s default"), _("Scaramuzza et al.\'s")}; - rbMethod = new wxRadioBox( - this, ID_RADIOBOX1, _(" Detector method: "), wxDefaultPosition, - wxDefaultSize, 2, __wxRadioBoxChoices_1, 1, 0, wxDefaultValidator, - _T("ID_RADIOBOX1")); - FlexGridSizer6->Add(rbMethod, 1, wxEXPAND, 2); StaticBoxSizer5 = new wxStaticBoxSizer(wxHORIZONTAL, this, _(" Size of quads (in mm): ")); FlexGridSizer18 = new wxFlexGridSizer(1, 4, 0, 0); @@ -352,8 +345,6 @@ void CDlgCalibWizardOnline::OntimCaptureTrigger(wxTimerEvent& event) m_check_size_x = this->edSizeX->GetValue(); m_check_size_y = this->edSizeY->GetValue(); m_normalize_image = this->cbNormalize->GetValue(); - m_useScaramuzzaAlternativeDetector = - this->rbMethod->GetSelection() == 1; CObservation::Ptr obs = m_video->getNextFrame(); ASSERT_(obs); @@ -524,8 +515,7 @@ void CDlgCalibWizardOnline::threadProcessCorners() bool foundCorners = mrpt::vision::findChessboardCorners( obj->m_threadImgToProcess->image, obj->m_threadResults, obj->m_check_size_x, obj->m_check_size_y, - obj->m_normalize_image, - obj->m_useScaramuzzaAlternativeDetector); + obj->m_normalize_image); // cout << "corners: " << obj->m_threadResults.size() << // endl; diff --git a/apps/camera-calib/CDlgCalibWizardOnline.h b/apps/camera-calib/CDlgCalibWizardOnline.h index b82e096169..8848018634 100644 --- a/apps/camera-calib/CDlgCalibWizardOnline.h +++ b/apps/camera-calib/CDlgCalibWizardOnline.h @@ -45,7 +45,6 @@ class CDlgCalibWizardOnline : public wxDialog wxTextCtrl* edLengthY; wxButton* btnClose; wxCheckBox* cbNormalize; - wxRadioBox* rbMethod; mrpt::gui::wxMRPTImageControl* m_realtimeview; wxSpinCtrl* edSizeY; wxStaticText* StaticText1; @@ -118,7 +117,6 @@ class CDlgCalibWizardOnline : public wxDialog unsigned int m_check_size_x; unsigned int m_check_size_y; bool m_normalize_image; - bool m_useScaramuzzaAlternativeDetector; mrpt::hwdrivers::CCameraSensor::Ptr m_video; diff --git a/apps/camera-calib/CDlgPoseEst.cpp b/apps/camera-calib/CDlgPoseEst.cpp index 6db37c18a6..db700870fa 100644 --- a/apps/camera-calib/CDlgPoseEst.cpp +++ b/apps/camera-calib/CDlgPoseEst.cpp @@ -146,13 +146,6 @@ CDlgPoseEst::CDlgPoseEst( StaticBoxSizer4->Add(FlexGridSizer17, 1, wxEXPAND, 0); FlexGridSizer6->Add( StaticBoxSizer4, 1, wxALL | wxALIGN_LEFT | wxALIGN_CENTER_VERTICAL, 2); - wxString __wxRadioBoxChoices_1[2] = { - _("OpenCV\'s default"), _("Scaramuzza et al.\'s")}; - rbMethod = new wxRadioBox( - this, ID_RADIOBOX1, _(" Detector method: "), wxDefaultPosition, - wxDefaultSize, 2, __wxRadioBoxChoices_1, 1, 0, wxDefaultValidator, - _T("ID_RADIOBOX1")); - FlexGridSizer6->Add(rbMethod, 1, wxEXPAND, 2); StaticBoxSizer5 = new wxStaticBoxSizer(wxHORIZONTAL, this, _(" Size of quads (in mm): ")); FlexGridSizer18 = new wxFlexGridSizer(1, 4, 0, 0); @@ -411,8 +404,6 @@ void CDlgPoseEst::OntimCaptureTrigger(wxTimerEvent& event) m_check_size_y = this->edSizeY->GetValue(); m_normalize_image = this->cbNormalize->GetValue(); - m_useScaramuzzaAlternativeDetector = - this->rbMethod->GetSelection() == 1; CObservation::Ptr obs = m_video->getNextFrame(); ASSERT_(obs); @@ -531,8 +522,7 @@ void CDlgPoseEst::threadProcessCorners() bool foundCorners = mrpt::vision::findChessboardCorners( obj->m_threadImgToProcess->image, obj->m_threadResults, obj->m_check_size_x, obj->m_check_size_y, - obj->m_normalize_image, - obj->m_useScaramuzzaAlternativeDetector); + obj->m_normalize_image); if (!foundCorners) obj->m_threadResults.clear(); else diff --git a/apps/camera-calib/CDlgPoseEst.h b/apps/camera-calib/CDlgPoseEst.h index 0476786275..59fd1e1c99 100644 --- a/apps/camera-calib/CDlgPoseEst.h +++ b/apps/camera-calib/CDlgPoseEst.h @@ -56,7 +56,6 @@ class CDlgPoseEst : public wxDialog wxTextCtrl* edLengthY; wxButton* btnClose; wxCheckBox* cbNormalize; - wxRadioBox* rbMethod; mrpt::gui::wxMRPTImageControl* m_realtimeview; wxSpinCtrl* edSizeY; wxStaticText* StaticText1; @@ -132,7 +131,6 @@ class CDlgPoseEst : public wxDialog unsigned int m_check_size_x; unsigned int m_check_size_y; bool m_normalize_image; - bool m_useScaramuzzaAlternativeDetector; mrpt::hwdrivers::CCameraSensor::Ptr m_video; CMyGLCanvas* m_3Dview_cam; mrpt::vision::pnp::CPnP pnp_algos; diff --git a/apps/camera-calib/camera_calib_guiMain.cpp b/apps/camera-calib/camera_calib_guiMain.cpp index 1f0192f8d0..7a1cd22af7 100644 --- a/apps/camera-calib/camera_calib_guiMain.cpp +++ b/apps/camera-calib/camera_calib_guiMain.cpp @@ -268,13 +268,6 @@ camera_calib_guiDialog::camera_calib_guiDialog(wxWindow* parent, wxWindowID id) StaticBoxSizer4->Add(FlexGridSizer17, 1, wxEXPAND, 0); FlexGridSizer6->Add( StaticBoxSizer4, 1, wxALL | wxALIGN_LEFT | wxALIGN_CENTER_VERTICAL, 2); - wxString __wxRadioBoxChoices_1[2] = { - _("OpenCV\'s default"), _("Scaramuzza et al.\'s")}; - rbMethod = new wxRadioBox( - this, ID_RADIOBOX1, _(" Detector method: "), wxDefaultPosition, - wxDefaultSize, 2, __wxRadioBoxChoices_1, 0, 0, wxDefaultValidator, - _T("ID_RADIOBOX1")); - FlexGridSizer6->Add(rbMethod, 1, wxEXPAND, 2); StaticBoxSizer5 = new wxStaticBoxSizer(wxHORIZONTAL, this, _(" Size of quads (in mm): ")); FlexGridSizer18 = new wxFlexGridSizer(1, 4, 0, 0); @@ -604,16 +597,13 @@ void camera_calib_guiDialog::OnbtnRunCalibClick(wxCommandEvent& event) const bool normalize_image = cbNormalize->GetValue(); - const bool useScaramuzzaAlternativeDetector = - rbMethod->GetSelection() == 1; - wxBusyCursor waitcur; bool res = mrpt::vision::checkerBoardCameraCalibration( lst_images, check_size_x, check_size_y, check_squares_length_X_meters, check_squares_length_Y_meters, camera_params, normalize_image, nullptr /* MSE */, - false /* skip draw */, useScaramuzzaAlternativeDetector); + false /* skip draw */); refreshDisplayedImage(); diff --git a/apps/camera-calib/camera_calib_guiMain.h b/apps/camera-calib/camera_calib_guiMain.h index 74838accb5..684ab07d78 100644 --- a/apps/camera-calib/camera_calib_guiMain.h +++ b/apps/camera-calib/camera_calib_guiMain.h @@ -95,7 +95,6 @@ class camera_calib_guiDialog : public wxDialog wxTextCtrl* edLengthX; CMyGLCanvas* m_3Dview; wxNotebook* Notebook1; - wxRadioBox* rbMethod; wxButton* btnSave; wxButton* btnAbout; wxStaticText* StaticText2; diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index 3b323c49f0..ee2c33668e 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -4,8 +4,11 @@ - Changes in libraries: - \ref mrpt_maps_grp: - mrpt::maps::CHeightGridMap2D: now supports integrating any point-cloud observation. + - \ref mrpt_vision_grp: + - Remove functions that were problematic with opencv 5: mrpt::vision::findMultipleChessboardsCorners() - Others: - Fix Debian appstream warnings on mrpt-apps. + - Fix build against opencv 5. # Version 2.11.9: Released Feb 11th, 2024 - Changes in libraries: diff --git a/doc/source/doxygen-docs/example-vision_multiple_checkerboards.md b/doc/source/doxygen-docs/example-vision_multiple_checkerboards.md deleted file mode 100644 index 888164c0b3..0000000000 --- a/doc/source/doxygen-docs/example-vision_multiple_checkerboards.md +++ /dev/null @@ -1,5 +0,0 @@ -\page vision_multiple_checkerboards Example: vision_multiple_checkerboards - -![vision_multiple_checkerboards screenshot](doc/source/images/vision_multiple_checkerboards_screenshot.png) -C++ example source code: -\include vision_multiple_checkerboards/test.cpp diff --git a/doc/source/examples.rst b/doc/source/examples.rst index 052a2efd8f..5763a3ae8b 100644 --- a/doc/source/examples.rst +++ b/doc/source/examples.rst @@ -140,6 +140,5 @@ Python examples are `here `_. page_vision_create_video_file_example.rst page_vision_feature_extraction.rst page_vision_keypoint_matching_example.rst - page_vision_multiple_checkerboards.rst page_vision_stereo_calib_example.rst page_vision_stereo_rectify.rst diff --git a/libs/hwdrivers/include/mrpt/hwdrivers/CImageGrabber_OpenCV.h b/libs/hwdrivers/include/mrpt/hwdrivers/CImageGrabber_OpenCV.h index 29b29daf6e..a5c15f823e 100644 --- a/libs/hwdrivers/include/mrpt/hwdrivers/CImageGrabber_OpenCV.h +++ b/libs/hwdrivers/include/mrpt/hwdrivers/CImageGrabber_OpenCV.h @@ -20,11 +20,11 @@ namespace mrpt::hwdrivers enum TCameraType { CAMERA_CV_AUTODETECT = 0, - CAMERA_CV_DC1394, - CAMERA_CV_VFL, - CAMERA_CV_VFW, - CAMERA_CV_MIL, - CAMERA_CV_DSHOW + CAMERA_CV_DC1394 = 1, + CAMERA_CV_VFL = 2, + // CAMERA_CV_VFW = 3, // removed feb-2024 + // CAMERA_CV_MIL = 4, // removed feb-2024 + CAMERA_CV_DSHOW = 5 }; /** Options used when creating an OpenCV capture object @@ -109,7 +109,5 @@ MRPT_ENUM_TYPE_BEGIN(mrpt::hwdrivers::TCameraType) MRPT_FILL_ENUM_MEMBER(mrpt::hwdrivers, CAMERA_CV_AUTODETECT); MRPT_FILL_ENUM_MEMBER(mrpt::hwdrivers, CAMERA_CV_DC1394); MRPT_FILL_ENUM_MEMBER(mrpt::hwdrivers, CAMERA_CV_VFL); -MRPT_FILL_ENUM_MEMBER(mrpt::hwdrivers, CAMERA_CV_VFW); -MRPT_FILL_ENUM_MEMBER(mrpt::hwdrivers, CAMERA_CV_MIL); MRPT_FILL_ENUM_MEMBER(mrpt::hwdrivers, CAMERA_CV_DSHOW); MRPT_ENUM_TYPE_END() diff --git a/libs/hwdrivers/src/CImageGrabber_OpenCV.cpp b/libs/hwdrivers/src/CImageGrabber_OpenCV.cpp index cf95950aa6..ffd6c68c1a 100644 --- a/libs/hwdrivers/src/CImageGrabber_OpenCV.cpp +++ b/libs/hwdrivers/src/CImageGrabber_OpenCV.cpp @@ -45,12 +45,10 @@ CImageGrabber_OpenCV::CImageGrabber_OpenCV( int cv_cap_indx = 0; switch (cameraType) { - case CAMERA_CV_AUTODETECT: cv_cap_indx = CV_CAP_ANY; break; - case CAMERA_CV_DC1394: cv_cap_indx = CV_CAP_DC1394; break; - case CAMERA_CV_VFL: cv_cap_indx = CV_CAP_V4L; break; - case CAMERA_CV_VFW: cv_cap_indx = CV_CAP_VFW; break; - case CAMERA_CV_MIL: cv_cap_indx = CV_CAP_MIL; break; - case CAMERA_CV_DSHOW: cv_cap_indx = CV_CAP_DSHOW; break; + case CAMERA_CV_AUTODETECT: cv_cap_indx = cv::CAP_ANY; break; + case CAMERA_CV_DC1394: cv_cap_indx = cv::CAP_DC1394; break; + case CAMERA_CV_VFL: cv_cap_indx = cv::CAP_V4L; break; + case CAMERA_CV_DSHOW: cv_cap_indx = cv::CAP_DSHOW; break; default: THROW_EXCEPTION_FMT("Invalid camera type: %i", cameraType); } @@ -71,7 +69,7 @@ CImageGrabber_OpenCV::CImageGrabber_OpenCV( // Global settings if (options.gain != 0) { - if (!m_capture->cap.set(CV_CAP_PROP_GAIN, options.gain)) + if (!m_capture->cap.set(cv::CAP_PROP_GAIN, options.gain)) cerr << "[CImageGrabber_OpenCV] Warning: Could not set the " "capturing gain property!" << endl; @@ -109,7 +107,7 @@ CImageGrabber_OpenCV::CImageGrabber_OpenCV( if (cvMode1394 > 0) { - if (!m_capture->cap.set(CV_CAP_PROP_MODE, cvMode1394)) + if (!m_capture->cap.set(cv::CAP_PROP_MODE, cvMode1394)) cerr << "[CImageGrabber_OpenCV] Warning: Could not set the " "capturing mode " << cvMode1394 << " property!" << endl; @@ -126,7 +124,7 @@ CImageGrabber_OpenCV::CImageGrabber_OpenCV( // cerr << "[CImageGrabber_OpenCV] Warning: Could not set the RGB // conversion property!" << endl; - if (!m_capture->cap.set(CV_CAP_PROP_FPS, options.ieee1394_fps)) + if (!m_capture->cap.set(cv::CAP_PROP_FPS, options.ieee1394_fps)) cerr << "[CImageGrabber_OpenCV] Warning: Could not set the fps " "property!" << endl; @@ -134,15 +132,15 @@ CImageGrabber_OpenCV::CImageGrabber_OpenCV( // Settings only for V4L if (cameraType == CAMERA_CV_AUTODETECT || cameraType == CAMERA_CV_VFL || - cameraType == CAMERA_CV_VFW || cameraType == CAMERA_CV_DSHOW) + cameraType == CAMERA_CV_DSHOW) { if (options.frame_width != 0 && options.frame_height != 0) { // First set width then height. The first command always returns a // error! - m_capture->cap.set(CV_CAP_PROP_FRAME_WIDTH, options.frame_width); + m_capture->cap.set(cv::CAP_PROP_FRAME_WIDTH, options.frame_width); if (!m_capture->cap.set( - CV_CAP_PROP_FRAME_HEIGHT, options.frame_height)) + cv::CAP_PROP_FRAME_HEIGHT, options.frame_height)) cerr << "[CImageGrabber_OpenCV] Warning: Could not set the " "frame width & height property!" << endl; diff --git a/libs/vision/include/mrpt/vision/chessboard_camera_calib.h b/libs/vision/include/mrpt/vision/chessboard_camera_calib.h index 67a69330f9..2a51639e4d 100644 --- a/libs/vision/include/mrpt/vision/chessboard_camera_calib.h +++ b/libs/vision/include/mrpt/vision/chessboard_camera_calib.h @@ -78,8 +78,6 @@ using TCalibrationImageList = std::map; * reprojection will be stored here (in pixel units). * \param skipDrawDetectedImgs [IN] Whether to skip the generation of the * undistorted and detected images in each TImageCalibData - * \param useScaramuzzaAlternativeDetector [IN] Whether to use an alternative - * detector. See CImage::findChessboardCorners for more deatails and references. * \sa The camera-calib-gui application is a user-friendly GUI to this class. * \return false on any error (more info will be dumped to cout), or true on @@ -91,8 +89,7 @@ bool checkerBoardCameraCalibration( unsigned int check_size_y, double check_squares_length_X_meters, double check_squares_length_Y_meters, mrpt::img::TCamera& out_camera_params, bool normalize_image = true, double* out_MSE = nullptr, - bool skipDrawDetectedImgs = false, - bool useScaramuzzaAlternativeDetector = false); + bool skipDrawDetectedImgs = false); /** \overload with matrix of intrinsic params instead of mrpt::img::TCamera */ @@ -102,8 +99,7 @@ bool checkerBoardCameraCalibration( double check_squares_length_Y_meters, mrpt::math::CMatrixDouble33& intrinsicParams, std::vector& distortionParams, bool normalize_image = true, - double* out_MSE = nullptr, bool skipDrawDetectedImgs = false, - bool useScaramuzzaAlternativeDetector = false); + double* out_MSE = nullptr, bool skipDrawDetectedImgs = false); /** @} */ // end of grouping } // namespace mrpt::vision diff --git a/libs/vision/include/mrpt/vision/chessboard_find_corners.h b/libs/vision/include/mrpt/vision/chessboard_find_corners.h index 5762984d57..cc77409eb7 100644 --- a/libs/vision/include/mrpt/vision/chessboard_find_corners.h +++ b/libs/vision/include/mrpt/vision/chessboard_find_corners.h @@ -47,57 +47,16 @@ namespace mrpt::vision * \param check_size_x [IN] The number of squares, in the X direction * \param check_size_y [IN] The number of squares, in the Y direction * \param normalize_image [IN] Whether to normalize the image before detection - * \param useScaramuzzaMethod [IN] Whether to use the alternative, more robust - *method by M. Rufli, D. Scaramuzza, and R. Siegwart. * * \return true on success * - * \sa findMultipleChessboardsCorners, - *mrpt::vision::checkerBoardCameraCalibration, drawChessboardCorners + * \sa mrpt::vision::checkerBoardCameraCalibration, drawChessboardCorners */ bool findChessboardCorners( const mrpt::img::CImage& img, std::vector& cornerCoords, unsigned int check_size_x, unsigned int check_size_y, - bool normalize_image = true, bool useScaramuzzaMethod = false); - -/** Look for the corners of one or more chessboard/checkerboards in the image. - * This method uses an improved version of OpenCV's cvFindChessboardCorners - *published - * by M. Rufli, D. Scaramuzza, and R. Siegwart. See: - *http://robotics.ethz.ch/~scaramuzza/Davide_Scaramuzza_files/Research/OcamCalib_Tutorial.htm - * and the papers: - * - 1. Scaramuzza, D., Martinelli, A. and Siegwart, R. (2006), A Toolbox - *for - *Easily Calibrating Omnidirectional Cameras, Proceedings of the IEEE/RSJ - *International Conference on Intelligent Robots and Systems (IROS 2006), - *Beijing, China, October 2006. - * - 2. Scaramuzza, D., Martinelli, A. and Siegwart, R., (2006). "A - *Flexible - *Technique for Accurate Omnidirectional Camera Calibration and Structure from - *Motion", Proceedings of IEEE International Conference of Vision Systems - *(ICVS'06), New York, January 5-7, 2006. - * - 3. Rufli, M., Scaramuzza, D., and Siegwart, R. (2008), Automatic - *Detection of Checkerboards on Blurred and Distorted Images, Proceedings of - *the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS - *2008), Nice, France, September 2008. - * - * That method has been extended in this MRPT implementation to automatically - *detect a - * number of different checkerboards in the same image. - * - * \param cornerCoords [OUT] A vector of N vectors of pixel coordinates, for - *each of the N chessboards detected. - * \param check_size_x [IN] The number of squares, in the X direction - * \param check_size_y [IN] The number of squares, in the Y direction - * - * - * \sa mrpt::vision::checkerBoardCameraCalibration, drawChessboardCorners - */ -void findMultipleChessboardsCorners( - const mrpt::img::CImage& img, - std::vector>& cornerCoords, - unsigned int check_size_x, unsigned int check_size_y); + bool normalize_image = true); /** @} */ } // namespace mrpt::vision diff --git a/libs/vision/src/CVideoFileWriter.cpp b/libs/vision/src/CVideoFileWriter.cpp index 7a4f5abc7a..c4f3b830e3 100644 --- a/libs/vision/src/CVideoFileWriter.cpp +++ b/libs/vision/src/CVideoFileWriter.cpp @@ -49,7 +49,7 @@ bool CVideoFileWriter::open( if (fourcc.empty()) { - cc = CV_FOURCC_DEFAULT; // Default + cc = CV_FOURCC('I', 'Y', 'U', 'V'); // Default } else if (fourcc.size() == 4) { diff --git a/libs/vision/src/checkerboard_cam_calib.cpp b/libs/vision/src/checkerboard_cam_calib.cpp index df16471c29..10bb304192 100644 --- a/libs/vision/src/checkerboard_cam_calib.cpp +++ b/libs/vision/src/checkerboard_cam_calib.cpp @@ -38,15 +38,14 @@ bool mrpt::vision::checkerBoardCameraCalibration( unsigned int check_size_y, double check_squares_length_X_meters, double check_squares_length_Y_meters, CMatrixDouble33& intrinsicParams, std::vector& distortionParams, bool normalize_image, - double* out_MSE, bool skipDrawDetectedImgs, - bool useScaramuzzaAlternativeDetector) + double* out_MSE, bool skipDrawDetectedImgs) { // Just a wrapper for the newer version of the function which uses TCamera: TCamera cam; bool ret = checkerBoardCameraCalibration( images, check_size_x, check_size_y, check_squares_length_X_meters, check_squares_length_Y_meters, cam, normalize_image, out_MSE, - skipDrawDetectedImgs, useScaramuzzaAlternativeDetector); + skipDrawDetectedImgs); intrinsicParams = cam.intrinsicParams; distortionParams = cam.getDistortionParamsAsVector(); @@ -61,8 +60,7 @@ bool mrpt::vision::checkerBoardCameraCalibration( unsigned int check_size_y, double check_squares_length_X_meters, double check_squares_length_Y_meters, mrpt::img::TCamera& out_camera_params, bool normalize_image, double* out_MSE, - [[maybe_unused]] bool skipDrawDetectedImgs, - bool useScaramuzzaAlternativeDetector) + [[maybe_unused]] bool skipDrawDetectedImgs) { #if MRPT_HAS_OPENCV try @@ -176,8 +174,7 @@ bool mrpt::vision::checkerBoardCameraCalibration( vector detectedCoords; corners_found = mrpt::vision::findChessboardCorners( img_gray, detectedCoords, check_size_x, check_size_y, - normalize_image, // normalize_image - useScaramuzzaAlternativeDetector); + normalize_image); corners_count = detectedCoords.size(); diff --git a/libs/vision/src/checkerboard_find_corners.cpp b/libs/vision/src/checkerboard_find_corners.cpp index 7fa74396b1..90ae3f1edd 100644 --- a/libs/vision/src/checkerboard_find_corners.cpp +++ b/libs/vision/src/checkerboard_find_corners.cpp @@ -15,8 +15,6 @@ // Universal include for all versions of OpenCV #include -#include "checkerboard_ocamcalib_detector.h" - using namespace mrpt; using namespace mrpt::vision; using namespace mrpt::img; @@ -35,8 +33,7 @@ using namespace std; */ bool mrpt::vision::findChessboardCorners( const mrpt::img::CImage& in_img, std::vector& cornerCoords, - unsigned int check_size_x, unsigned int check_size_y, bool normalize_image, - bool useScaramuzzaMethod) + unsigned int check_size_x, unsigned int check_size_y, bool normalize_image) { #if MRPT_HAS_OPENCV MRPT_START @@ -65,27 +62,18 @@ bool mrpt::vision::findChessboardCorners( if (normalize_image) find_chess_flags |= cv::CALIB_CB_NORMALIZE_IMAGE; cv::Mat cvImg = img.asCvMat(SHALLOW_COPY); - if (!useScaramuzzaMethod) - { - vector pointbuf; - - // Standard OpenCV's function: - corners_found = 0 != - cv::findChessboardCorners( - cvImg, check_size, pointbuf, find_chess_flags); - - corners_list.resize(pointbuf.size()); - for (size_t i = 0; i < pointbuf.size(); i++) - { - corners_list[i].x = pointbuf[i].x; - corners_list[i].y = pointbuf[i].y; - } - } - else + vector pointbuf; + + // Standard OpenCV's function: + corners_found = 0 != + cv::findChessboardCorners( + cvImg, check_size, pointbuf, find_chess_flags); + + corners_list.resize(pointbuf.size()); + for (size_t i = 0; i < pointbuf.size(); i++) { - // Return: -1: errors, 0: not found, 1: found OK - corners_found = - 1 == cvFindChessboardCorners3(img, check_size, corners_list); + corners_list[i].x = pointbuf[i].x; + corners_list[i].y = pointbuf[i].y; } // Check # of corners: @@ -115,93 +103,3 @@ bool mrpt::vision::findChessboardCorners( return false; #endif } - -/** Look for the corners of one or more chessboard/checkerboards in the image. - * This method uses an improved version of OpenCV's cvFindChessboardCorners - * published - * by M. Rufli, D. Scaramuzza, and R. Siegwart. - * That method has been extended in this MRPT implementation to automatically - * detect a - * number of different checkerboards in the same image. - * - * \param cornerCoords [OUT] A vector of N vectors of pixel coordinates, for - * each of the N chessboards detected. - * \param check_size_x [IN] The number of squares, in the X direction - * \param check_size_y [IN] The number of squares, in the Y direction - * - * - * \sa mrpt::vision::checkerBoardCameraCalibration, drawChessboardCorners - */ -void mrpt::vision::findMultipleChessboardsCorners( - const mrpt::img::CImage& in_img, - std::vector>& cornerCoords, - unsigned int check_size_x, unsigned int check_size_y) -{ -#if MRPT_HAS_OPENCV - // Grayscale version: - const CImage img(in_img, FAST_REF_OR_CONVERT_TO_GRAY); - const cv::Mat img_m = img.asCvMat(SHALLOW_COPY); - - std::vector> corners_list; - - // Return: -1: errors, 0: not found, 1: found OK - bool corners_found = find_chessboard_corners_multiple( - img, cvSize(check_size_x, check_size_y), corners_list); - - if (corners_found && !corners_list.empty()) - { - // Alloc space for output points: - cornerCoords.resize(corners_list.size()); - - // Refine corners: - for (size_t i = 0; i < corners_list.size(); i++) - { - ASSERT_(corners_list[i].size() == check_size_x * check_size_y); - - cv::cornerSubPix( - img_m, corners_list, cv::Size(5, 5), // window - cv::Size(-1, -1), - cv::TermCriteria( - cv::TermCriteria::MAX_ITER | cv::TermCriteria::EPS, 10, - 0.01f)); - - // save the corners in the data structure: - for (unsigned int y = 0, k = 0; y < check_size_y; y++) - for (unsigned int x = 0; x < check_size_x; x++, k++) - cornerCoords[i].push_back(TPixelCoordf( - corners_list[i][k].x, corners_list[i][k].y)); - - // Consistency of the counter-clockwise XYZ reference system and - // corners ORDER. - - // Key idea: The cross product of X * Y must point outwards the - // screen: - - const mrpt::math::TPoint2D pt_0{ - cornerCoords[i][0].x, cornerCoords[i][0].y}, - pt_x1{cornerCoords[i][1].x, cornerCoords[i][1].y}, - pt_y1{ - cornerCoords[i][check_size_x].x, - cornerCoords[i][check_size_x].y}; - const mrpt::math::TPoint3D Ax = pt_x1 - pt_0; // z=0 - const mrpt::math::TPoint3D Ay = pt_y1 - pt_0; // z=0 - - const auto Az = mrpt::math::crossProduct3D(Ax, Ay); - if (Az[2] > 0) - { - // Invert all rows (X): - for (unsigned int y = 0; y < check_size_y; y++) - std::reverse( - cornerCoords[i].begin() + y * check_size_x, - cornerCoords[i].begin() + (y + 1) * check_size_x); - } - } - } - else - { // Not found. - cornerCoords.clear(); - return; - } - -#endif -} diff --git a/libs/vision/src/checkerboard_multiple_detector.cpp b/libs/vision/src/checkerboard_multiple_detector.cpp deleted file mode 100644 index e8d1f32451..0000000000 --- a/libs/vision/src/checkerboard_multiple_detector.cpp +++ /dev/null @@ -1,292 +0,0 @@ -/* +------------------------------------------------------------------------+ - | Mobile Robot Programming Toolkit (MRPT) | - | https://www.mrpt.org/ | - | | - | Copyright (c) 2005-2024, Individual contributors, see AUTHORS file | - | See: https://www.mrpt.org/Authors - All rights reserved. | - | Released under BSD License. See: https://www.mrpt.org/License | - +------------------------------------------------------------------------+ */ - -#include "vision-precomp.h" // Precompiled headers -// -#include -#include -#include -#include - -#include -#include - -// Universal include for all versions of OpenCV -#include - -#include "checkerboard_ocamcalib_detector.h" - -#if VIS -#include -#endif - -using namespace mrpt; -using namespace mrpt::img; -using namespace mrpt::math; -using namespace std; - -#if MRPT_HAS_OPENCV - -// Return: true: found OK -bool find_chessboard_corners_multiple( - const CImage& img_, CvSize pattern_size, - std::vector>& out_corners) -{ - // Assure it's a grayscale image: - const CImage img(img_, FAST_REF_OR_CONVERT_TO_GRAY); - - CImage thresh_img(img.getWidth(), img.getHeight(), CH_GRAY); - CImage thresh_img_save(img.getWidth(), img.getHeight(), CH_GRAY); - - out_corners.clear(); // for now, empty the output. - - const size_t expected_quads_count = - ((pattern_size.width + 1) * (pattern_size.height + 1) + 1) / 2; - - // PART 0: INITIALIZATION - //----------------------------------------------------------------------- - // Initialize variables - int flags = 1; // not part of the function call anymore! - // int found = 0; - - vector quads; - vector corners; - list> - good_quad_groups; // Storage of potential good quad groups found - - if (pattern_size.width < 2 || pattern_size.height < 2) - { - std::cerr << "Pattern should have at least 2x2 size" << endl; - return false; - } - if (pattern_size.width > 127 || pattern_size.height > 127) - { - std::cerr << "Pattern should not have a size larger than 127 x 127" - << endl; - return false; - } - - // JL: Move these constructors out of the loops: - const auto kernel_cross = - cv::getStructuringElement(cv::MORPH_CROSS, {3, 3}); - const auto kernel_rect = cv::getStructuringElement(cv::MORPH_RECT, {3, 3}); - - // clang-format off - const cv::Mat kernel_diag1 = (cv::Mat_(3,3) << - 1, 0, 0, - 0, 1, 0, - 0, 0, 1 ); - const cv::Mat kernel_diag2 = (cv::Mat_(3,3) << - 0, 0, 1, - 0, 1, 0, - 1, 0, 0 ); - const cv::Mat kernel_horz = (cv::Mat_(3,3) << - 0, 0, 0, - 1, 1, 1, - 0, 0, 0 ); - const cv::Mat kernel_vert = (cv::Mat_(3,3) << - 0, 1, 0, - 0, 1, 0, - 0, 1, 0 ); - // clang-format on - - // For image binarization (thresholding) - // we use an adaptive threshold with a gaussian mask - // ATTENTION: Gaussian thresholding takes MUCH more time than Mean - // thresholding! - int block_size = cvRound(MIN(img.getWidth(), img.getHeight()) * 0.2) | 1; - - cv::adaptiveThreshold( - img.asCvMat(SHALLOW_COPY), - thresh_img.asCvMat(SHALLOW_COPY), 255, - cv::ADAPTIVE_THRESH_GAUSSIAN_C, cv::THRESH_BINARY, block_size, 0); - - thresh_img_save = thresh_img.makeDeepCopy(); - - // PART 1: FIND LARGEST PATTERN - //----------------------------------------------------------------------- - // Checker patterns are tried to be found by dilating the background and - // then applying a canny edge finder on the closed contours (checkers). - // Try one dilation run, but if the pattern is not found, repeat until - // max_dilations is reached. - // for( int dilations = min_dilations; dilations <= max_dilations; - // dilations++ ) - - bool last_dilation = false; - - for (int dilations = 0; !last_dilation; dilations++) - { - // Calling "cvCopy" again is much faster than rerunning - // "cvAdaptiveThreshold" - thresh_img = thresh_img_save.makeDeepCopy(); - - // Dilate squares: - last_dilation = do_special_dilation( - thresh_img, dilations, kernel_cross, kernel_rect, kernel_diag1, - kernel_diag2, kernel_horz, kernel_vert); - - // In order to find rectangles that go to the edge, we draw a white - // line around the image edge. Otherwise FindContours will miss those - // clipped rectangle contours. The border color will be the image mean, - // because otherwise we risk screwing up filters like cvSmooth() - cv::rectangle( - thresh_img.asCvMatRef(), cv::Point(0, 0), - cv::Point(thresh_img.getWidth() - 1, thresh_img.getHeight() - 1), - CV_RGB(255, 255, 255), 3, 8); - - // Generate quadrangles in the following function - // "quad_count" is the number of cound quadrangles - int quad_count = icvGenerateQuads( - quads, corners, thresh_img, flags, dilations, true); - if (quad_count <= 0) continue; - - // The following function finds and assigns neighbor quads to every - // quadrangle in the immediate vicinity fulfilling certain - // prerequisites - mrFindQuadNeighbors2(quads, dilations); - - // JL: To achieve multiple-checkerboard, take all the raw detected quads - // and - // separate them in groups with k-means. - std::vector> quad_centers; - quad_centers.resize(quads.size()); - for (size_t i = 0; i < quads.size(); i++) - { - const CvCBQuad* q = quads[i].get(); - quad_centers[i][0] = 0.25 * - (q->corners[0]->pt.x + q->corners[1]->pt.x + - q->corners[2]->pt.x + q->corners[3]->pt.x); - quad_centers[i][1] = 0.25 * - (q->corners[0]->pt.y + q->corners[1]->pt.y + - q->corners[2]->pt.y + q->corners[3]->pt.y); - } - - // Try the k-means with a number of variable # of clusters: - static const size_t MAX_NUM_CLUSTERS = 4; - for (size_t nClusters = 1; nClusters < MAX_NUM_CLUSTERS; nClusters++) - { - vector num_quads_by_cluster(nClusters); - - vector assignments; - mrpt::math::kmeanspp(nClusters, quad_centers, assignments); - - // Count # of quads in each cluster: - for (size_t i = 0; i < nClusters; i++) - num_quads_by_cluster[i] = - std::count(assignments.begin(), assignments.end(), i); - - // Take a look at the promising clusters: - // ----------------------------------------- - for (size_t i = 0; i < nClusters; i++) - { - if (num_quads_by_cluster[i] < - size_t(pattern_size.height) * size_t(pattern_size.width)) - continue; // Can't be good... - - // Create a subset of the quads with those in the i'th cluster: - vector ith_quads; - for (size_t q = 0; q < quads.size(); q++) - if (size_t(assignments[q]) == i) - ith_quads.push_back(quads[q]); - - // Make sense out of smart pointers... - quadListMakeUnique(ith_quads); - - // The connected quads will be organized in groups. The - // following loop - // increases a "group_idx" identifier. - // The function "icvFindConnectedQuads assigns all connected - // quads - // a unique group ID. - // If more quadrangles were assigned to a given group (i.e. - // connected) - // than are expected by the input variable "pattern_size", the - // function "icvCleanFoundConnectedQuads" erases the surplus - // quadrangles by minimizing the convex hull of the remaining - // pattern. - for (int group_idx = 0;; group_idx++) - { - vector quad_group; - - icvFindConnectedQuads( - ith_quads, quad_group, group_idx, dilations); - if (quad_group.empty()) break; - - icvCleanFoundConnectedQuads(quad_group, pattern_size); - size_t count = quad_group.size(); - - if (count == expected_quads_count) - { - // The following function labels all corners of every - // quad - // with a row and column entry. - mrLabelQuadGroup(quad_group, pattern_size, true); - - // Add this set of quads as a good result to be returned - // to the user: - good_quad_groups.push_back(quad_group); - // And "make_unique()" it: - // quadListMakeUnique( good_quad_groups.back() ); - } - - } // end for each "group_idx" - - } // end of the loop "try with each promising cluster" - - } // end loop, for each "nClusters" size. - - } // end for dilation - - // Convert the set of good detected quad sets in "good_quad_groups" - // to the expected output data struct, doing a final check to - // remove duplicates: - vector - out_boards_centers; // the center (average) of each output board. - for (auto it = good_quad_groups.begin(); it != good_quad_groups.end(); ++it) - { - // Compute the center of this board: - TPoint2D boardCenter(0, 0); - for (size_t i = 0; i < it->size(); i++) - { // JL: Avoid the normalizations of all the averages, since it really - // doesn't matter for our purpose. - boardCenter += TPoint2D( - /*0.25* */ (*it)[i]->corners[0]->pt.x + - (*it)[i]->corners[1]->pt.x + (*it)[i]->corners[2]->pt.x + - (*it)[i]->corners[3]->pt.x, - /*0.25* */ (*it)[i]->corners[0]->pt.y + - (*it)[i]->corners[1]->pt.y + (*it)[i]->corners[2]->pt.y + - (*it)[i]->corners[3]->pt.y); - } - - // If it's too close to an already existing board, it's surely a - // duplicate: - double min_dist = std::numeric_limits::max(); - for (size_t b = 0; b < out_boards_centers.size(); b++) - keep_min( - min_dist, - mrpt::math::distance(boardCenter, out_boards_centers[b])); - - if (out_corners.empty() || min_dist > 80) - { - vector pts; - if (1 == - myQuads2Points(*it, pattern_size, pts)) // and populate it now. - { - // Ok with it: add to the output list: - out_corners.push_back(pts); - // Add center to list of known centers: - out_boards_centers.push_back(boardCenter); - } - } - } - - return !out_corners.empty(); -} - -#endif // MRPT_HAS_OPENCV diff --git a/libs/vision/src/checkerboard_ocamcalib_detector.cpp b/libs/vision/src/checkerboard_ocamcalib_detector.cpp deleted file mode 100644 index 9a8f6dfeb7..0000000000 --- a/libs/vision/src/checkerboard_ocamcalib_detector.cpp +++ /dev/null @@ -1,2171 +0,0 @@ -/* +------------------------------------------------------------------------+ - | Mobile Robot Programming Toolkit (MRPT) | - | https://www.mrpt.org/ | - | | - | Copyright (c) 2005-2024, Individual contributors, see AUTHORS file | - | See: https://www.mrpt.org/Authors - All rights reserved. | - | Released under BSD License. See: https://www.mrpt.org/License | - +------------------------------------------------------------------------+ */ - -#include "vision-precomp.h" // Precompiled headers -// -#include // Precompiled headers - -// Note for MRPT: what follows below is a modified part of the "OCamCalib -// Toolbox": -// See: -// http://robotics.ethz.ch/~scaramuzza/Davide_Scaramuzza_files/Research/OcamCalib_Tutorial.htm -// Modifications include: -// - Clean up of code and update to use STL containers, and smart pointers. -// - Addition of a new method to detect a number of checkerboards. -// - Modification of the dilation algorithm - see do_special_dilation(). -// -// Original copyright note: -/************************************************************************************\ - This is improved variant of chessboard corner detection algorithm that - uses a graph of connected quads. It is based on the code contributed - by Vladimir Vezhnevets and Philip Gruebele. - Here is the copyright notice from the original Vladimir's code: - =============================================================== - - The algorithms developed and implemented by Vezhnevets Vldimir - aka Dead Moroz (vvp@graphics.cs.msu.ru) - See http://graphics.cs.msu.su/en/research/calibration/opencv.html - for detailed information. - - Reliability additions and modifications made by Philip Gruebele. - pgruebele@cox.net - - His code was adapted for use with low resolution and omnidirectional cameras - by Martin Rufli during his Master Thesis under supervision of Davide -Scaramuzza, at the ETH Zurich. Further enhancements include: - - Increased chance of correct corner matching. - - Corner matching over all dilation runs. - -If you use this code, please cite the following articles: - -1. Scaramuzza, D., Martinelli, A. and Siegwart, R. (2006), A Toolbox for Easily -Calibrating Omnidirectional Cameras, Proceedings of the IEEE/RSJ International -Conference on Intelligent Robots and Systems (IROS 2006), Beijing, China, -October 2006. -2. Scaramuzza, D., Martinelli, A. and Siegwart, R., (2006). "A Flexible -Technique for Accurate Omnidirectional Camera Calibration and Structure from -Motion", Proceedings of IEEE International Conference of Vision Systems -(ICVS'06), New York, January 5-7, 2006. -3. Rufli, M., Scaramuzza, D., and Siegwart, R. (2008), Automatic Detection of -Checkerboards on Blurred and Distorted Images, Proceedings of the IEEE/RSJ -International Conference on Intelligent Robots and Systems (IROS 2008), Nice, -France, September 2008. - -\************************************************************************************/ - -#include -#include - -#include "checkerboard_ocamcalib_detector.h" - -#if MRPT_HAS_OPENCV - -using namespace mrpt; -using namespace mrpt::math; -using namespace mrpt::img; -using namespace std; - -//=========================================================================== -// CODE STARTS HERE -//=========================================================================== -// Defines -#define MAX_CONTOUR_APPROX 7 - -// JL: Refactored code from within cvFindChessboardCorners3() and alternative -// algorithm: -bool do_special_dilation( - CImage& thresh_img, const int dilations, const cv::Mat& kernel_cross, - const cv::Mat& kernel_rect, const cv::Mat& kernel_diag1, - const cv::Mat& kernel_diag2, const cv::Mat& kernel_horz, - const cv::Mat& kernel_vert) -{ - cv::Mat im = thresh_img.asCvMat(SHALLOW_COPY); - - bool isLast = false; - - switch (dilations) - { - case 37: - cv::dilate(im, im, kernel_cross); - isLast = true; - [[fallthrough]]; - case 36: cv::erode(im, im, kernel_rect); [[fallthrough]]; - case 35: cv::dilate(im, im, kernel_vert); [[fallthrough]]; - case 34: cv::dilate(im, im, kernel_vert); [[fallthrough]]; - case 33: cv::dilate(im, im, kernel_vert); [[fallthrough]]; - case 32: cv::dilate(im, im, kernel_vert); [[fallthrough]]; - case 31: cv::dilate(im, im, kernel_vert); break; - - case 30: cv::dilate(im, im, kernel_cross); [[fallthrough]]; - case 29: cv::erode(im, im, kernel_rect); [[fallthrough]]; - case 28: cv::dilate(im, im, kernel_horz); [[fallthrough]]; - case 27: cv::dilate(im, im, kernel_horz); [[fallthrough]]; - case 26: cv::dilate(im, im, kernel_horz); [[fallthrough]]; - case 25: cv::dilate(im, im, kernel_horz); [[fallthrough]]; - case 24: cv::dilate(im, im, kernel_horz); break; - - case 23: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; - case 22: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; - case 21: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; - case 20: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; - case 19: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; - case 18: cv::dilate(im, im, kernel_diag1); break; - - case 17: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; - case 16: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; - case 15: cv::dilate(im, im, kernel_diag2); [[fallthrough]]; - case 14: cv::dilate(im, im, kernel_diag2); break; - - case 13: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; - case 12: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; - case 11: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; - case 10: cv::dilate(im, im, kernel_diag1); break; - - case 9: cv::dilate(im, im, kernel_cross); [[fallthrough]]; - case 8: cv::erode(im, im, kernel_rect); [[fallthrough]]; - case 7: cv::dilate(im, im, kernel_cross); [[fallthrough]]; - case 6: - cv::dilate(im, im, kernel_diag2); - isLast = true; - [[fallthrough]]; - case 5: cv::dilate(im, im, kernel_diag1); [[fallthrough]]; - case 4: cv::dilate(im, im, kernel_rect); [[fallthrough]]; - case 3: cv::erode(im, im, kernel_cross); [[fallthrough]]; - case 2: cv::dilate(im, im, kernel_rect); [[fallthrough]]; - case 1: cv::dilate(im, im, kernel_cross); [[fallthrough]]; - case 0: /* first try: do nothing to the image */ break; - }; - - return isLast; -} - -//=========================================================================== -// MAIN FUNCTION -//=========================================================================== -// Return: -1: errors, 0: not found, 1: found OK -int cvFindChessboardCorners3( - const CImage& img_, CvSize pattern_size, - std::vector& out_corners) -{ - // PART 0: INITIALIZATION - //----------------------------------------------------------------------- - // Initialize variables - int flags = 1; // not part of the function call anymore! - size_t max_count = 0; - int max_dilation_run_ID = -1; - // const int min_dilations = 0; // JL: was: 1 - // const int max_dilations = 23; // JL: see do_special_dilation() - int found = 0; - - vector quads; // CvCBQuad **quads = 0; - vector quad_group; // CvCBQuad **quad_group = 0; - vector corners; // CvCBCorner *corners = 0; - vector - output_quad_group; // CvCBQuad **output_quad_group = 0; - - // debug trial. Martin Rufli, 28. Ocober, 2008 - int block_size = 0; - - // Further initializations - int quad_count, group_idx; - - if (pattern_size.width < 2 || pattern_size.height < 2) - { - std::cerr << "Pattern should have at least 2x2 size" << endl; - return -1; - } - if (pattern_size.width > 127 || pattern_size.height > 127) - { - std::cerr << "Pattern should not have a size larger than 127 x 127" - << endl; - return -1; - } - - // Assure it's a grayscale image: - const CImage img(img_, FAST_REF_OR_CONVERT_TO_GRAY); - - CImage thresh_img( - img.getWidth(), img.getHeight(), - CH_GRAY); // = cvCreateMat( img->rows, img->cols, CV_8UC1 ); - CImage thresh_img_save( - img.getWidth(), img.getHeight(), - CH_GRAY); // = cvCreateMat( img->rows, img->cols, CV_8UC1 ); - - // JL: Move these constructors out of the loops: - const auto kernel_cross = - cv::getStructuringElement(cv::MORPH_CROSS, {3, 3}); - const auto kernel_rect = cv::getStructuringElement(cv::MORPH_RECT, {3, 3}); - - // clang-format off - const cv::Mat kernel_diag1 = (cv::Mat_(3,3) << - 1, 0, 0, - 0, 1, 0, - 0, 0, 1 ); - const cv::Mat kernel_diag2 = (cv::Mat_(3,3) << - 0, 0, 1, - 0, 1, 0, - 1, 0, 0 ); - const cv::Mat kernel_horz = (cv::Mat_(3,3) << - 0, 0, 0, - 1, 1, 1, - 0, 0, 0 ); - const cv::Mat kernel_vert = (cv::Mat_(3,3) << - 0, 1, 0, - 0, 1, 0, - 0, 1, 0 ); - // clang-format on - - // For image binarization (thresholding) - // we use an adaptive threshold with a gaussian mask - // ATTENTION: Gaussian thresholding takes MUCH more time than Mean - // thresholding! - block_size = cvRound(MIN(img.getWidth(), img.getHeight()) * 0.2) | 1; - - cv::adaptiveThreshold( - img.asCvMat(SHALLOW_COPY), - thresh_img.asCvMat(SHALLOW_COPY), 255, - cv::ADAPTIVE_THRESH_GAUSSIAN_C, cv::THRESH_BINARY, block_size, 0); - - thresh_img_save = thresh_img.makeDeepCopy(); - - // PART 1: FIND LARGEST PATTERN - //----------------------------------------------------------------------- - // Checker patterns are tried to be found by dilating the background and - // then applying a canny edge finder on the closed contours (checkers). - // Try one dilation run, but if the pattern is not found, repeat until - // max_dilations is reached. - // for( int dilations = min_dilations; dilations <= max_dilations; - // dilations++ ) - - bool last_dilation = false; - - for (int dilations = 0; !last_dilation; dilations++) - { - // Calling "cvCopy" again is much faster than rerunning - // "cvAdaptiveThreshold" - thresh_img = thresh_img_save.makeDeepCopy(); - - // Dilate squares: - last_dilation = do_special_dilation( - thresh_img, dilations, kernel_cross, kernel_rect, kernel_diag1, - kernel_diag2, kernel_horz, kernel_vert); - - // In order to find rectangles that go to the edge, we draw a white - // line around the image edge. Otherwise FindContours will miss those - // clipped rectangle contours. The border color will be the image mean, - // because otherwise we risk screwing up filters like cvSmooth() - cv::rectangle( - thresh_img.asCvMatRef(), cv::Point(0, 0), - cv::Point(thresh_img.getWidth() - 1, thresh_img.getHeight() - 1), - CV_RGB(255, 255, 255), 3, 8); - - // Generate quadrangles in the following function - // "quad_count" is the number of cound quadrangles - quad_count = icvGenerateQuads( - quads, corners, thresh_img, flags, dilations, true); - if (quad_count <= 0) continue; - - // The following function finds and assigns neighbor quads to every - // quadrangle in the immediate vicinity fulfilling certain - // prerequisites - mrFindQuadNeighbors2(quads, dilations); - - // The connected quads will be organized in groups. The following loop - // increases a "group_idx" identifier. - // The function "icvFindConnectedQuads assigns all connected quads - // a unique group ID. - // If more quadrangles were assigned to a given group (i.e. connected) - // than are expected by the input variable "pattern_size", the - // function "icvCleanFoundConnectedQuads" erases the surplus - // quadrangles by minimizing the convex hull of the remaining pattern. - for (group_idx = 0;; group_idx++) - { - icvFindConnectedQuads(quads, quad_group, group_idx, dilations); - - if (quad_group.empty()) break; - - icvCleanFoundConnectedQuads(quad_group, pattern_size); - size_t count = quad_group.size(); - - // MARTIN's Code - // To save computational time, only proceed, if the number of - // found quads during this dilation run is larger than the - // largest previous found number - if (count /*>=*/ > max_count) - { - // cout << "CHECKERBOARD: Best found at dilation=" << dilations - // << endl; - - // set max_count to its new value - max_count = count; - max_dilation_run_ID = dilations; - - // The following function labels all corners of every quad - // with a row and column entry. - // "count" specifies the number of found quads in "quad_group" - // with group identifier "group_idx" - // The last parameter is set to "true", because this is the - // first function call and some initializations need to be - // made. - mrLabelQuadGroup(quad_group, pattern_size, true); - - // END------------------------------------------------------------------------ - - // Allocate memory - // output_quad_group.resize( (pattern_size.height+2) * - // (pattern_size.width+2) ); // = (CvCBQuad**)cvAlloc( - // sizeof(output_quad_group[0]) * ((pattern_size.height+2) * - // (pattern_size.width+2)) ); - // The following function copies every member of "quad_group" - // to "output_quad_group", because "quad_group" will be - // overwritten during the next loop pass. - // "output_quad_group" is a true copy of "quad_group" and - // later used for output - output_quad_group = quad_group; // mrCopyQuadGroup( quad_group, - // output_quad_group, max_count - // ); - } - } - } - - // If enough corners have been found already, then there is no need for PART - // 2 ->EXIT - // JLBC for MRPT: Don't save to Matlab files (mrWriteCorners), but to - // "cv::Point2f *out_corners": - // Return true on success in finding all the quads. - found = myQuads2Points(output_quad_group, pattern_size, out_corners); - - if (found != -1 && found != 1) - { - // PART 2: AUGMENT LARGEST PATTERN - //----------------------------------------------------------------------- - // Instead of saving all found quads of all dilation runs from PART 1, - // we - // just recompute them again, but skipping the dilation run which - // produced the maximum number of found quadrangles. - // In essence the first section of PART 2 is identical to the first - // section of PART 1. - // for( int dilations = max_dilations; dilations >= min_dilations; - // dilations-- ) - last_dilation = false; - for (int dilations = 0; !last_dilation; dilations++) - { - // if(max_dilation_run_ID == dilations) - // continue; - - // Calling "cvCopy" again is much faster than rerunning - // "cvAdaptiveThreshold" - thresh_img = thresh_img_save.makeDeepCopy(); - - // Dilate squares: - last_dilation = do_special_dilation( - thresh_img, dilations, kernel_cross, kernel_rect, kernel_diag1, - kernel_diag2, kernel_horz, kernel_vert); - - cv::rectangle( - thresh_img.asCvMatRef(), cv::Point(0, 0), - cv::Point( - thresh_img.getWidth() - 1, thresh_img.getHeight() - 1), - CV_RGB(255, 255, 255), 3, 8); - - quad_count = icvGenerateQuads( - quads, corners, thresh_img, flags, dilations, false); - if (quad_count <= 0) continue; - - // END------------------------------------------------------------------------ - - // MARTIN's Code - // The following loop is executed until no more newly found quads - // can be matched to one of the border corners of the largest found - // pattern from PART 1. - // The function "mrAugmentBestRun" tests whether a quad can be - // linked - // to the existng pattern. - // The function "mrLabelQuadGroup" then labels the newly added - // corners - // with the respective row and column entries. - int feedBack = -1; - while (feedBack == -1) - { - feedBack = mrAugmentBestRun( - quads, dilations, output_quad_group, max_dilation_run_ID); - - // if we have found a new matching quad - if (feedBack == -1) - { - // increase max_count by one - max_count = max_count + 1; - mrLabelQuadGroup(output_quad_group, pattern_size, false); - - // write the found corners to output array - // Go to //__END__, if enough corners have been found - found = myQuads2Points( - output_quad_group, pattern_size, out_corners); - // found = mrWriteCorners( output_quad_group, max_count, - // pattern_size, min_number_of_corners); - if (found == -1 || found == 1) - { - // JL: was a "goto exit;", but, have you seen - // http://xkcd.com/292/ ??? ;-) - last_dilation = - true; // This will break the outer for loop - break; - } - } - } - - } // end for "dilations" - - } // JL: Was label "exit:", but again, http://xkcd.com/292/ ;-) - - /* - // MARTIN: - found = mrWriteCorners( output_quad_group, max_count, pattern_size, - min_number_of_corners); - */ - - // If a linking problem was encountered, throw an error message - if (found == -1) - { - std::cerr << "While linking the corners a problem was encountered. No " - "corner sequence is returned. " - << endl; - return -1; - } - - // Return found - // Found can have the values - // -1 -> Error or corner linking problem, see std::cerr - // 0 -> Not enough corners were found - // 1 -> Enough corners were found - return found; -} - -double triangleArea( - double x0, double y0, double x1, double y1, double x2, double y2) -{ - return std::abs(0.5 * (x0 * (y1 - y2) + x1 * (y2 - y0) + x2 * (y0 - y1))); -} - -double median(const std::vector& vec) -{ - std::vector v = vec; // Copy for sorting - const size_t n = v.size() / 2; - nth_element(v.begin(), v.begin() + n, v.end()); - return v[n]; -} - -//=========================================================================== -// ERASE OVERHEAD -//=========================================================================== -// If we found too many connected quads, remove those which probably do not -// belong. -void icvCleanFoundConnectedQuads( - std::vector& quad_group, const CvSize& pattern_size) -{ - cv::MemStorage temp_storage; // JL: "Modernized" to use C++ STL stuff. - - cv::Point2f center = cv::Point2f(0, 0); - - // Number of quads this pattern should contain - const size_t expected_quads_count = - ((pattern_size.width + 1) * (pattern_size.height + 1) + 1) / 2; - - // If we have more quadrangles than we should, try to eliminate duplicates - // or ones which don't belong to the pattern rectangle. Else go to the end - // of the function - const size_t nQuads = quad_group.size(); - if (nQuads <= expected_quads_count) return; // Nothing to be done. - - // Create an array of quadrangle centers - vector centers(nQuads); - temp_storage = cv::MemStorage(cvCreateMemStorage(0)); - - // make also the list of squares areas, so we can discriminate by - // too-large/small quads: - // (Added by JLBC, JUN-2014) - std::vector quad_areas(nQuads); - double min_area = DBL_MAX, max_area = -DBL_MAX, mean_area = 0.0; - - for (size_t i = 0; i < nQuads; i++) - { - cv::Point2f ci = cv::Point2f(0, 0); - CvCBQuad::Ptr& q = quad_group[i]; - - for (size_t j = 0; j < 4; j++) - { - cv::Point2f pt = q->corners[j]->pt; - ci.x += pt.x; - ci.y += pt.y; - } - - ci.x *= 0.25f; - ci.y *= 0.25f; - - // Quad area: - const double a = triangleArea( - q->corners[0]->pt.x, q->corners[0]->pt.y, - q->corners[1]->pt.x, q->corners[1]->pt.y, - q->corners[2]->pt.x, q->corners[2]->pt.y) + - triangleArea(q->corners[0]->pt.x, q->corners[0]->pt.y, - q->corners[2]->pt.x, q->corners[2]->pt.y, - q->corners[3]->pt.x, q->corners[3]->pt.y); - - q->area = a; - quad_areas[i] = a; - mean_area += a; - if (a < min_area) min_area = a; - if (a > max_area) max_area = a; - - // Centers(i), is the geometric center of quad(i) - // Center, is the center of all found quads - centers[i] = ci; - center.x += ci.x; - center.y += ci.y; - } - center.x /= nQuads; - center.y /= nQuads; - mean_area /= nQuads; - const double median_area = median(quad_areas); - - // ration: area/median: - for (size_t i = 0; i < nQuads; i++) - { - quad_group[i]->area_ratio = quad_group[i]->area / median_area; - } - - // If we have more quadrangles than we should, we try to eliminate bad - // ones based on minimizing the bounding box. We iteratively remove the - // point which reduces the size of the bounding box of the blobs the most - // (since we want the rectangle to be as small as possible) remove the - // quadrange that causes the biggest reduction in pattern size until we - // have the correct number - - // JLBC (2014): Additional preliminary filter: remove quads that are too - // small or too large - - // In the following, use "quad_group.size()" since the size will change with - // iterations - while (quad_group.size() > expected_quads_count) - { - double min_box_area = DBL_MAX; - int min_box_area_index = -1; - - // For each point, check area: - int most_outlier_idx = -1; - double most_outlier_ratio = 1.0; - for (size_t skip = 0; skip < quad_group.size(); skip++) - { - double ar = quad_group[skip]->area_ratio; - if (ar > 1.0) ar = 1.0 / ar; - - if (ar < most_outlier_ratio) - { - most_outlier_ratio = ar; - most_outlier_idx = skip; - } - } - - if (most_outlier_idx >= 0) { min_box_area_index = most_outlier_idx; } - - if (min_box_area_index == -1) // if the previous filter didn't work: - { - // For each point, calculate box area without that point - for (size_t skip = 0; skip < quad_group.size(); skip++) - { - // get bounding rectangle - cv::Point2f temp = centers[skip]; - centers[skip] = center; - CvMat pointMat = - cvMat(1, quad_group.size(), CV_32FC2, ¢ers[0]); - CvSeq* hull = - cvConvexHull2(&pointMat, temp_storage, CV_CLOCKWISE, 1); - centers[skip] = temp; - double hull_area = fabs(cvContourArea(hull, CV_WHOLE_SEQ)); - - // remember smallest box area - if (hull_area < min_box_area) - { - min_box_area = hull_area; - min_box_area_index = skip; - } - cvClearMemStorage(temp_storage); - } - } - - CvCBQuad::Ptr& q0 = quad_group[min_box_area_index]; - - // remove any references to this quad as a neighbor - for (size_t i = 0; i < quad_group.size(); i++) - { - CvCBQuad::Ptr& q = quad_group[i]; - - for (size_t j = 0; j < 4; j++) - { - if (q->neighbors[j] == q0) - { - q->neighbors[j].reset(); // = 0; - q->count--; - for (size_t k = 0; k < 4; k++) - if (q0->neighbors[k] == q) - { - q0->neighbors[k].reset(); // = 0; - q0->count--; - break; - } - break; - } - } - } - - // remove the quad by copying th last quad in the list into its place - quad_group.erase(quad_group.begin() + min_box_area_index); - centers.erase(centers.begin() + min_box_area_index); - } -} - -//=========================================================================== -// FIND COONECTED QUADS -//=========================================================================== -void icvFindConnectedQuads( - std::vector& quad, std::vector& out_group, - const int group_idx, [[maybe_unused]] const int dilation) -{ - // initializations - out_group.clear(); - - const size_t quad_count = quad.size(); - - // Scan the array for a first unlabeled quad - for (size_t i = 0; i < quad_count; i++) - { - if (quad[i]->count < 0 || quad[i]->group_idx >= 0) continue; - - // Recursively find a group of connected quads starting from the seed - // quad[i] - CvCBQuad::Ptr& q = quad[i]; - - std::stack seqStack; - - seqStack.push(q); // cvSeqPush( stack, &q ); - - q->group_idx = group_idx; - out_group.push_back(q); // out_group[count++] = q; - - while (!seqStack.empty()) - { - q = seqStack.top(); - seqStack.pop(); // cvSeqPop( stack, &q ); - - for (size_t k = 0; k < 4; k++) - { - CvCBQuad::Ptr& neighbor = q->neighbors[k]; - - // If he neighbor exists and the neighbor has more than 0 - // neighbors and the neighbor has not been classified yet. - if (neighbor && neighbor->count > 0 && neighbor->group_idx < 0) - { - neighbor->group_idx = group_idx; - seqStack.push(neighbor); // cvSeqPush( stack, &neighbor ); - out_group.push_back( - neighbor); // out_group[count++] = neighbor; - } - } - } - - break; - } -} - -//=========================================================================== -// LABEL CORNER WITH ROW AND COLUMN //DONE -//=========================================================================== -void mrLabelQuadGroup( - std::vector& quad_group, const CvSize& pattern_size, - bool firstRun) -{ - const size_t count = quad_group.size(); - - // If this is the first function call, a seed quad needs to be selected - if (firstRun == true) - { - // Search for the (first) quad with the maximum number of neighbors - // (usually 4). This will be our starting point. - int max_id = -1; - int max_number = -1; - for (size_t i = 0; i < count; i++) - { - CvCBQuad* q = quad_group[i].get(); - if (q->count > max_number) - { - max_number = q->count; - max_id = i; - - if (max_number == 4) break; - } - } - - // Mark the starting quad's (per definition) upper left corner with - //(0,0) and then proceed clockwise - // The following labeling sequence enshures a "right coordinate system" - CvCBQuad* q = quad_group[max_id].get(); - - q->labeled = true; - q->corners[0]->row = 0; - q->corners[0]->column = 0; - q->corners[1]->row = 0; - q->corners[1]->column = 1; - q->corners[2]->row = 1; - q->corners[2]->column = 1; - q->corners[3]->row = 1; - q->corners[3]->column = 0; - } - - // Mark all other corners with their respective row and column - bool flag_changed = true; - while (flag_changed == true) - { - // First reset the flag to "false" - flag_changed = false; - - // Go through all quads top down is faster, since unlabeled quads will - // be inserted at the end of the list - for (int i = int(count - 1); i >= 0; i--) - { - // Check whether quad "i" has been labeled already - if ((quad_group[i])->labeled == false) - { - // Check its neighbors, whether some of them have been labeled - // already - for (size_t j = 0; j < 4; j++) - { - // Check whether the neighbor exists (i.e. is not the NULL - // pointer) - if ((quad_group[i])->neighbors[j]) - { - CvCBQuad::Ptr& quadNeighborJ = - quad_group[i]->neighbors[j]; - - // Only proceed, if neighbor "j" was labeled - if (quadNeighborJ->labeled == true) - { - // For every quad it could happen to pass here - // multiple times. We therefore "break" later. - // Check whitch of the neighbors corners is - // connected to the current quad - int connectedNeighborCornerId = -1; - for (int k = 0; k < 4; k++) - { - if (quadNeighborJ->neighbors[k] == - quad_group[i]) - { - connectedNeighborCornerId = k; - - // there is only one, therefore - break; - } - } - - // For the following calculations we need the row - // and column of the connected neighbor corner and - // all other corners of the connected quad "j", - // clockwise (CW) - CvCBCorner::Ptr& conCorner = - quadNeighborJ - ->corners[connectedNeighborCornerId]; - CvCBCorner::Ptr& conCornerCW1 = - quadNeighborJ->corners - [(connectedNeighborCornerId + 1) % 4]; - CvCBCorner::Ptr& conCornerCW2 = - quadNeighborJ->corners - [(connectedNeighborCornerId + 2) % 4]; - CvCBCorner::Ptr& conCornerCW3 = - quadNeighborJ->corners - [(connectedNeighborCornerId + 3) % 4]; - - (quad_group[i])->corners[j]->row = conCorner->row; - (quad_group[i])->corners[j]->column = - conCorner->column; - (quad_group[i])->corners[(j + 1) % 4]->row = - conCorner->row - conCornerCW2->row + - conCornerCW3->row; - (quad_group[i])->corners[(j + 1) % 4]->column = - conCorner->column - conCornerCW2->column + - conCornerCW3->column; - (quad_group[i])->corners[(j + 2) % 4]->row = - conCorner->row + conCorner->row - - conCornerCW2->row; - (quad_group[i])->corners[(j + 2) % 4]->column = - conCorner->column + conCorner->column - - conCornerCW2->column; - (quad_group[i])->corners[(j + 3) % 4]->row = - conCorner->row - conCornerCW2->row + - conCornerCW1->row; - (quad_group[i])->corners[(j + 3) % 4]->column = - conCorner->column - conCornerCW2->column + - conCornerCW1->column; - - // Mark this quad as labeled - (quad_group[i])->labeled = true; - - // Changes have taken place, set the flag - flag_changed = true; - - // once is enough! - break; - } - } - } - } - } - } - - // All corners are marked with row and column - // Record the minimal and maximal row and column indices - // It is unlikely that more than 8bit checkers are used per dimension, if - // there are - // an error would have been thrown at the beginning of - // "cvFindChessboardCorners2" - int min_row = 127; - int max_row = -127; - int min_column = 127; - int max_column = -127; - - for (size_t i = 0; i < count; i++) - { - const CvCBQuad::Ptr& q = quad_group[i]; - - for (size_t j = 0; j < 4; j++) - { - if ((q->corners[j])->row > max_row) max_row = (q->corners[j])->row; - - if ((q->corners[j])->row < min_row) min_row = (q->corners[j])->row; - - if ((q->corners[j])->column > max_column) - max_column = (q->corners[j])->column; - - if ((q->corners[j])->column < min_column) - min_column = (q->corners[j])->column; - } - } - - // Label all internal corners with "needsNeighbor" = false - // Label all external corners with "needsNeighbor" = true, - // except if in a given dimension the pattern size is reached - for (int i = min_row; i <= max_row; i++) - { - for (int j = min_column; j <= max_column; j++) - { - // A flag that indicates, wheter a row/column combination is - // executed multiple times - bool flagg = false; - - // Remember corner and quad - int cornerID = 0; - int quadID = 0; - - for (size_t k = 0; k < count; k++) - { - for (size_t l = 0; l < 4; l++) - { - if (((quad_group[k])->corners[l]->row == i) && - ((quad_group[k])->corners[l]->column == j)) - { - if (flagg == true) - { - // Passed at least twice through here - (quad_group[k])->corners[l]->needsNeighbor = false; - (quad_group[quadID]) - ->corners[cornerID] - ->needsNeighbor = false; - } - else - { - // Mark with needs a neighbor, but note the - // address - (quad_group[k])->corners[l]->needsNeighbor = true; - cornerID = l; - quadID = k; - } - - // set the flag to true - flagg = true; - } - } - } - } - } - - // Complete Linking: - // sometimes not all corners were properly linked in "mrFindQuadNeighbors2", - // but after labeling each corner with its respective row and column, it is - // possible to match them anyway. - for (int i = min_row; i <= max_row; i++) - { - for (int j = min_column; j <= max_column; j++) - { - // the following "number" indicates the number of corners which - // correspond to the given (i,j) value - // 1 is a border corner or a conrer which still needs a neighbor - // 2 is a fully connected internal corner - // >2 something went wrong during labeling, report a warning - int number = 1; - - // remember corner and quad - int cornerID = 0; - int quadID = 0; - - for (size_t k = 0; k < count; k++) - { - for (size_t l = 0; l < 4; l++) - { - if (((quad_group[k])->corners[l]->row == i) && - ((quad_group[k])->corners[l]->column == j)) - { - if (number == 1) - { - // First corner, note its ID - cornerID = l; - quadID = k; - } - - else if (number == 2) - { - // Second corner, check wheter this and the - // first one have equal coordinates, else - // interpolate - float delta_x = (quad_group[k])->corners[l]->pt.x - - (quad_group[quadID])->corners[cornerID]->pt.x; - float delta_y = (quad_group[k])->corners[l]->pt.y - - (quad_group[quadID])->corners[cornerID]->pt.y; - - if (delta_x != 0 || delta_y != 0) - { - // Interpolate - (quad_group[k])->corners[l]->pt.x = - (quad_group[k])->corners[l]->pt.x - - delta_x / 2; - (quad_group[quadID])->corners[cornerID]->pt.x = - (quad_group[quadID]) - ->corners[cornerID] - ->pt.x + - delta_x / 2; - (quad_group[k])->corners[l]->pt.y = - (quad_group[k])->corners[l]->pt.y - - delta_y / 2; - (quad_group[quadID])->corners[cornerID]->pt.y = - (quad_group[quadID]) - ->corners[cornerID] - ->pt.y + - delta_y / 2; - } - } - else if (number > 2) - { - // Something went wrong during row/column labeling - // Report a Warning - // ->Implemented in the function "mrWriteCorners" - } - - // increase the number by one - number = number + 1; - } - } - } - } - } - - // Bordercorners don't need any neighbors, if the pattern size in the - // respective direction is reached - // The only time we can make shure that the target pattern size is reached - // in a given - // dimension, is when the larger side has reached the target size in the - // maximal - // direction, or if the larger side is larger than the smaller target size - // and the - // smaller side equals the smaller target size - int largerDimPattern = max(pattern_size.height, pattern_size.width); - int smallerDimPattern = min(pattern_size.height, pattern_size.width); - bool flagSmallerDim1 = false; - bool flagSmallerDim2 = false; - - if ((largerDimPattern + 1) == max_column - min_column) - { - flagSmallerDim1 = true; - // We found out that in the column direction the target pattern size is - // reached - // Therefore border column corners do not need a neighbor anymore - // Go through all corners - for (size_t k = 0; k < count; k++) - { - for (size_t l = 0; l < 4; l++) - { - if ((quad_group[k])->corners[l]->column == min_column || - (quad_group[k])->corners[l]->column == max_column) - { - // Needs no neighbor anymore - (quad_group[k])->corners[l]->needsNeighbor = false; - } - } - } - } - - if ((largerDimPattern + 1) == max_row - min_row) - { - flagSmallerDim2 = true; - // We found out that in the column direction the target pattern size is - // reached - // Therefore border column corners do not need a neighbor anymore - // Go through all corners - for (size_t k = 0; k < count; k++) - { - for (size_t l = 0; l < 4; l++) - { - if ((quad_group[k])->corners[l]->row == min_row || - (quad_group[k])->corners[l]->row == max_row) - { - // Needs no neighbor anymore - (quad_group[k])->corners[l]->needsNeighbor = false; - } - } - } - } - - // Check the two flags: - // - If one is true and the other false, then the pattern target - // size was reached in in one direction -> We can check, whether the - // target - // pattern size is also reached in the other direction - // - If both are set to true, then we deal with a square board -> do - // nothing - // - If both are set to false -> There is a possibility that the larger - // side is - // larger than the smaller target size -> Check and if true, then check - // whether - // the other side has the same size as the smaller target size - if ((flagSmallerDim1 == false && flagSmallerDim2 == true)) - { - // Larger target pattern size is in row direction, check wheter smaller - // target - // pattern size is reached in column direction - if ((smallerDimPattern + 1) == max_column - min_column) - { - for (size_t k = 0; k < count; k++) - { - for (int l = 0; l < 4; l++) - { - if ((quad_group[k])->corners[l]->column == min_column || - (quad_group[k])->corners[l]->column == max_column) - { - // Needs no neighbor anymore - (quad_group[k])->corners[l]->needsNeighbor = false; - } - } - } - } - } - - if ((flagSmallerDim1 == true && flagSmallerDim2 == false)) - { - // Larger target pattern size is in column direction, check wheter - // smaller target - // pattern size is reached in row direction - if ((smallerDimPattern + 1) == max_row - min_row) - { - for (size_t k = 0; k < count; k++) - { - for (size_t l = 0; l < 4; l++) - { - if ((quad_group[k])->corners[l]->row == min_row || - (quad_group[k])->corners[l]->row == max_row) - { - // Needs no neighbor anymore - (quad_group[k])->corners[l]->needsNeighbor = false; - } - } - } - } - } - - if ((flagSmallerDim1 == false && flagSmallerDim2 == false) && - smallerDimPattern + 1 < max_column - min_column) - { - // Larger target pattern size is in column direction, check wheter - // smaller target - // pattern size is reached in row direction - if ((smallerDimPattern + 1) == max_row - min_row) - { - for (size_t k = 0; k < count; k++) - { - for (size_t l = 0; l < 4; l++) - { - if ((quad_group[k])->corners[l]->row == min_row || - (quad_group[k])->corners[l]->row == max_row) - { - // Needs no neighbor anymore - (quad_group[k])->corners[l]->needsNeighbor = false; - } - } - } - } - } - - if ((flagSmallerDim1 == false && flagSmallerDim2 == false) && - smallerDimPattern + 1 < max_row - min_row) - { - // Larger target pattern size is in row direction, check wheter smaller - // target - // pattern size is reached in column direction - if ((smallerDimPattern + 1) == max_column - min_column) - { - for (size_t k = 0; k < count; k++) - { - for (size_t l = 0; l < 4; l++) - { - if ((quad_group[k])->corners[l]->column == min_column || - (quad_group[k])->corners[l]->column == max_column) - { - // Needs no neighbor anymore - (quad_group[k])->corners[l]->needsNeighbor = false; - } - } - } - } - } -} - -//=========================================================================== -// GIVE A GROUP IDX -//=========================================================================== -// This function replaces mrFindQuadNeighbors, which in turn replaced -// icvFindQuadNeighbors -void mrFindQuadNeighbors2(std::vector& quads, int dilation) -{ - // Thresh dilation is used to counter the effect of dilation on the - // distance between 2 neighboring corners. Since the distance below is - // computed as its square, we do here the same. Additionally, we take the - // conservative assumption that dilation was performed using the 3x3 CROSS - // kernel, which coresponds to the 4-neighborhood. - const float thresh_dilation = (float)(2 * dilation + 3) * - (2 * dilation + 3) * 2; // the "*2" is for the x and y component - float dx, dy, dist; - // int cur_quad_group = -1; - - const size_t quad_count = quads.size(); - - // Find quad neighbors - for (size_t idx = 0; idx < quad_count; idx++) - { - CvCBQuad::Ptr& cur_quad = quads[idx]; - - // Go through all quadrangles and label them in groups - // For each corner of this quadrangle - for (size_t i = 0; i < 4; i++) - { - cv::Point2f pt; - float min_dist = FLT_MAX; - int closest_corner_idx = -1; - CvCBQuad::Ptr closest_quad; - - if (cur_quad->neighbors[i]) continue; - - pt = cur_quad->corners[i]->pt; - - // Find the closest corner in all other quadrangles - for (size_t k = 0; k < quad_count; k++) - { - if (k == idx) continue; - - for (size_t j = 0; j < 4; j++) - { - // If it already has a neighbor - if (quads[k]->neighbors[j]) continue; - - dx = pt.x - quads[k]->corners[j]->pt.x; - dy = pt.y - quads[k]->corners[j]->pt.y; - dist = dx * dx + dy * dy; - - // The following "if" checks, whether "dist" is the - // shortest so far and smaller than the smallest - // edge length of the current and target quads - if (dist < min_dist && - dist <= (cur_quad->edge_len + thresh_dilation) && - dist <= (quads[k]->edge_len + thresh_dilation)) - { - // First Check everything from the viewpoint of the - // current quad - // compute midpoints of "parallel" quad sides 1 - float x1 = (cur_quad->corners[i]->pt.x + - cur_quad->corners[(i + 1) % 4]->pt.x) / - 2; - float y1 = (cur_quad->corners[i]->pt.y + - cur_quad->corners[(i + 1) % 4]->pt.y) / - 2; - float x2 = (cur_quad->corners[(i + 2) % 4]->pt.x + - cur_quad->corners[(i + 3) % 4]->pt.x) / - 2; - float y2 = (cur_quad->corners[(i + 2) % 4]->pt.y + - cur_quad->corners[(i + 3) % 4]->pt.y) / - 2; - // compute midpoints of "parallel" quad sides 2 - float x3 = (cur_quad->corners[i]->pt.x + - cur_quad->corners[(i + 3) % 4]->pt.x) / - 2; - float y3 = (cur_quad->corners[i]->pt.y + - cur_quad->corners[(i + 3) % 4]->pt.y) / - 2; - float x4 = (cur_quad->corners[(i + 1) % 4]->pt.x + - cur_quad->corners[(i + 2) % 4]->pt.x) / - 2; - float y4 = (cur_quad->corners[(i + 1) % 4]->pt.y + - cur_quad->corners[(i + 2) % 4]->pt.y) / - 2; - - // MARTIN: Heuristic - // For the corner "j" of quad "k" to be considered, - // it needs to be on the same side of the two lines as - // corner "i". This is given, if the cross product has - // the same sign for both computations below: - float a1 = x1 - x2; - float b1 = y1 - y2; - // the current corner - float c11 = cur_quad->corners[i]->pt.x - x2; - float d11 = cur_quad->corners[i]->pt.y - y2; - // the candidate corner - float c12 = quads[k]->corners[j]->pt.x - x2; - float d12 = quads[k]->corners[j]->pt.y - y2; - float sign11 = a1 * d11 - c11 * b1; - float sign12 = a1 * d12 - c12 * b1; - - float a2 = x3 - x4; - float b2 = y3 - y4; - // the current corner - float c21 = cur_quad->corners[i]->pt.x - x4; - float d21 = cur_quad->corners[i]->pt.y - y4; - // the candidate corner - float c22 = quads[k]->corners[j]->pt.x - x4; - float d22 = quads[k]->corners[j]->pt.y - y4; - float sign21 = a2 * d21 - c21 * b2; - float sign22 = a2 * d22 - c22 * b2; - - // Then make shure that two border quads of the same row - // or - // column don't link. Check from the current corner's - // view, - // whether the corner diagonal from the candidate corner - // is also on the same side of the two lines as the - // current - // corner and the candidate corner. - float c13 = quads[k]->corners[(j + 2) % 4]->pt.x - x2; - float d13 = quads[k]->corners[(j + 2) % 4]->pt.y - y2; - float c23 = quads[k]->corners[(j + 2) % 4]->pt.x - x4; - float d23 = quads[k]->corners[(j + 2) % 4]->pt.y - y4; - float sign13 = a1 * d13 - c13 * b1; - float sign23 = a2 * d23 - c23 * b2; - - // Then check everything from the viewpoint of the - // candidate quad - // compute midpoints of "parallel" quad sides 1 - float u1 = (quads[k]->corners[j]->pt.x + - quads[k]->corners[(j + 1) % 4]->pt.x) / - 2; - float v1 = (quads[k]->corners[j]->pt.y + - quads[k]->corners[(j + 1) % 4]->pt.y) / - 2; - float u2 = (quads[k]->corners[(j + 2) % 4]->pt.x + - quads[k]->corners[(j + 3) % 4]->pt.x) / - 2; - float v2 = (quads[k]->corners[(j + 2) % 4]->pt.y + - quads[k]->corners[(j + 3) % 4]->pt.y) / - 2; - // compute midpoints of "parallel" quad sides 2 - float u3 = (quads[k]->corners[j]->pt.x + - quads[k]->corners[(j + 3) % 4]->pt.x) / - 2; - float v3 = (quads[k]->corners[j]->pt.y + - quads[k]->corners[(j + 3) % 4]->pt.y) / - 2; - float u4 = (quads[k]->corners[(j + 1) % 4]->pt.x + - quads[k]->corners[(j + 2) % 4]->pt.x) / - 2; - float v4 = (quads[k]->corners[(j + 1) % 4]->pt.y + - quads[k]->corners[(j + 2) % 4]->pt.y) / - 2; - - // MARTIN: Heuristic - // for the corner "j" of quad "k" to be considered, it - // needs to be on the same side of the two lines as - // corner "i". This is again given, if the cross - // product has the same sign for both computations - // below: - float a3 = u1 - u2; - float b3 = v1 - v2; - // the current corner - float c31 = cur_quad->corners[i]->pt.x - u2; - float d31 = cur_quad->corners[i]->pt.y - v2; - // the candidate corner - float c32 = quads[k]->corners[j]->pt.x - u2; - float d32 = quads[k]->corners[j]->pt.y - v2; - float sign31 = a3 * d31 - c31 * b3; - float sign32 = a3 * d32 - c32 * b3; - - float a4 = u3 - u4; - float b4 = v3 - v4; - // the current corner - float c41 = cur_quad->corners[i]->pt.x - u4; - float d41 = cur_quad->corners[i]->pt.y - v4; - // the candidate corner - float c42 = quads[k]->corners[j]->pt.x - u4; - float d42 = quads[k]->corners[j]->pt.y - v4; - float sign41 = a4 * d41 - c41 * b4; - float sign42 = a4 * d42 - c42 * b4; - - // Then make shure that two border quads of the same row - // or - // column don't link. Check from the candidate corner's - // view, - // whether the corner diagonal from the current corner - // is also on the same side of the two lines as the - // current - // corner and the candidate corner. - float c33 = cur_quad->corners[(i + 2) % 4]->pt.x - u2; - float d33 = cur_quad->corners[(i + 2) % 4]->pt.y - v2; - float c43 = cur_quad->corners[(i + 2) % 4]->pt.x - u4; - float d43 = cur_quad->corners[(i + 2) % 4]->pt.y - v4; - float sign33 = a3 * d33 - c33 * b3; - float sign43 = a4 * d43 - c43 * b4; - - // Check whether conditions are fulfilled - if (((sign11 < 0 && sign12 < 0) || - (sign11 > 0 && sign12 > 0)) && - ((sign21 < 0 && sign22 < 0) || - (sign21 > 0 && sign22 > 0)) && - ((sign31 < 0 && sign32 < 0) || - (sign31 > 0 && sign32 > 0)) && - ((sign41 < 0 && sign42 < 0) || - (sign41 > 0 && sign42 > 0)) && - ((sign11 < 0 && sign13 < 0) || - (sign11 > 0 && sign13 > 0)) && - ((sign21 < 0 && sign23 < 0) || - (sign21 > 0 && sign23 > 0)) && - ((sign31 < 0 && sign33 < 0) || - (sign31 > 0 && sign33 > 0)) && - ((sign41 < 0 && sign43 < 0) || - (sign41 > 0 && sign43 > 0))) - - { - closest_corner_idx = j; - closest_quad = quads[k]; - min_dist = dist; - } - } - } - } - - // Have we found a matching corner point? - if (closest_corner_idx >= 0 && min_dist < FLT_MAX) - { - CvCBCorner::Ptr& closest_corner = - closest_quad->corners[closest_corner_idx]; - - // Make shure that the closest quad does not have the current - // quad as neighbor already - bool skip = false; - for (size_t j = 0; !skip && j < 4; j++) - skip = closest_quad->neighbors[j] == cur_quad; - - if (skip) continue; - - // We've found one more corner - remember it - closest_corner->pt.x = (pt.x + closest_corner->pt.x) * 0.5f; - closest_corner->pt.y = (pt.y + closest_corner->pt.y) * 0.5f; - - cur_quad->count++; - cur_quad->neighbors[i] = closest_quad; - cur_quad->corners[i] = closest_corner; - - closest_quad->count++; - closest_quad->neighbors[closest_corner_idx] = cur_quad; - closest_quad->corners[closest_corner_idx] = closest_corner; - } - } - } -} - -//=========================================================================== -// AUGMENT PATTERN WITH ADDITIONAL QUADS -//=========================================================================== -// The first part of the function is basically a copy of -// "mrFindQuadNeighbors2" -// The comparisons between two points and two lines could be computed in their -// own function -int mrAugmentBestRun( - std::vector& new_quads, int new_dilation, - std::vector& old_quads, int old_dilation) -{ - // thresh dilation is used to counter the effect of dilation on the - // distance between 2 neighboring corners. Since the distance below is - // computed as its square, we do here the same. Additionally, we take the - // conservative assumption that dilation was performed using the 3x3 CROSS - // kernel, which coresponds to the 4-neighborhood. - // - // the "*2" is for the x and y component - // int idx, i, k, j; // the "3" is for initial corner mismatch - const float thresh_dilation = - (float)(2 * new_dilation + 3) * (2 * old_dilation + 3) * 2; - float dx, dy, dist; - - // Search all old quads which have a neighbor that needs to be linked - for (size_t idx = 0; idx < old_quads.size(); idx++) - { - CvCBQuad::Ptr cur_quad = old_quads[idx]; - - // For each corner of this quadrangle - for (int i = 0; i < 4; i++) - { - cv::Point2f pt; - float min_dist = FLT_MAX; - int closest_corner_idx = -1; - CvCBQuad::Ptr closest_quad; - // CvCBCorner *closest_corner = 0; - - // If cur_quad corner[i] is already linked, continue - if (cur_quad->corners[i]->needsNeighbor == false) continue; - - pt = cur_quad->corners[i]->pt; - - // Look for a match in all new_quads' corners - for (size_t k = 0; k < new_quads.size(); k++) - { - // Only look at unlabeled new quads - if (new_quads[k]->labeled == true) continue; - - for (int j = 0; j < 4; j++) - { - // Only proceed if they are less than dist away from each - // other - dx = pt.x - new_quads[k]->corners[j]->pt.x; - dy = pt.y - new_quads[k]->corners[j]->pt.y; - dist = dx * dx + dy * dy; - - if ((dist < min_dist) && - dist <= (cur_quad->edge_len + thresh_dilation) && - dist <= (new_quads[k]->edge_len + thresh_dilation)) - { - // First Check everything from the viewpoint of the - // current quad compute midpoints of "parallel" quad - // sides 1 - float x1 = (cur_quad->corners[i]->pt.x + - cur_quad->corners[(i + 1) % 4]->pt.x) / - 2; - float y1 = (cur_quad->corners[i]->pt.y + - cur_quad->corners[(i + 1) % 4]->pt.y) / - 2; - float x2 = (cur_quad->corners[(i + 2) % 4]->pt.x + - cur_quad->corners[(i + 3) % 4]->pt.x) / - 2; - float y2 = (cur_quad->corners[(i + 2) % 4]->pt.y + - cur_quad->corners[(i + 3) % 4]->pt.y) / - 2; - // compute midpoints of "parallel" quad sides 2 - float x3 = (cur_quad->corners[i]->pt.x + - cur_quad->corners[(i + 3) % 4]->pt.x) / - 2; - float y3 = (cur_quad->corners[i]->pt.y + - cur_quad->corners[(i + 3) % 4]->pt.y) / - 2; - float x4 = (cur_quad->corners[(i + 1) % 4]->pt.x + - cur_quad->corners[(i + 2) % 4]->pt.x) / - 2; - float y4 = (cur_quad->corners[(i + 1) % 4]->pt.y + - cur_quad->corners[(i + 2) % 4]->pt.y) / - 2; - - // MARTIN: Heuristic - // For the corner "j" of quad "k" to be considered, - // it needs to be on the same side of the two lines as - // corner "i". This is given, if the cross product has - // the same sign for both computations below: - float a1 = x1 - x2; - float b1 = y1 - y2; - // the current corner - float c11 = cur_quad->corners[i]->pt.x - x2; - float d11 = cur_quad->corners[i]->pt.y - y2; - // the candidate corner - float c12 = new_quads[k]->corners[j]->pt.x - x2; - float d12 = new_quads[k]->corners[j]->pt.y - y2; - float sign11 = a1 * d11 - c11 * b1; - float sign12 = a1 * d12 - c12 * b1; - - float a2 = x3 - x4; - float b2 = y3 - y4; - // the current corner - float c21 = cur_quad->corners[i]->pt.x - x4; - float d21 = cur_quad->corners[i]->pt.y - y4; - // the candidate corner - float c22 = new_quads[k]->corners[j]->pt.x - x4; - float d22 = new_quads[k]->corners[j]->pt.y - y4; - float sign21 = a2 * d21 - c21 * b2; - float sign22 = a2 * d22 - c22 * b2; - - // Also make shure that two border quads of the same row - // or - // column don't link. Check from the current corner's - // view, - // whether the corner diagonal from the candidate corner - // is also on the same side of the two lines as the - // current - // corner and the candidate corner. - float c13 = - new_quads[k]->corners[(j + 2) % 4]->pt.x - x2; - float d13 = - new_quads[k]->corners[(j + 2) % 4]->pt.y - y2; - float c23 = - new_quads[k]->corners[(j + 2) % 4]->pt.x - x4; - float d23 = - new_quads[k]->corners[(j + 2) % 4]->pt.y - y4; - float sign13 = a1 * d13 - c13 * b1; - float sign23 = a2 * d23 - c23 * b2; - - // Second: Then check everything from the viewpoint of - // the candidate quad. Compute midpoints of "parallel" - // quad sides 1 - float u1 = (new_quads[k]->corners[j]->pt.x + - new_quads[k]->corners[(j + 1) % 4]->pt.x) / - 2; - float v1 = (new_quads[k]->corners[j]->pt.y + - new_quads[k]->corners[(j + 1) % 4]->pt.y) / - 2; - float u2 = (new_quads[k]->corners[(j + 2) % 4]->pt.x + - new_quads[k]->corners[(j + 3) % 4]->pt.x) / - 2; - float v2 = (new_quads[k]->corners[(j + 2) % 4]->pt.y + - new_quads[k]->corners[(j + 3) % 4]->pt.y) / - 2; - // compute midpoints of "parallel" quad sides 2 - float u3 = (new_quads[k]->corners[j]->pt.x + - new_quads[k]->corners[(j + 3) % 4]->pt.x) / - 2; - float v3 = (new_quads[k]->corners[j]->pt.y + - new_quads[k]->corners[(j + 3) % 4]->pt.y) / - 2; - float u4 = (new_quads[k]->corners[(j + 1) % 4]->pt.x + - new_quads[k]->corners[(j + 2) % 4]->pt.x) / - 2; - float v4 = (new_quads[k]->corners[(j + 1) % 4]->pt.y + - new_quads[k]->corners[(j + 2) % 4]->pt.y) / - 2; - - // MARTIN: Heuristic - // For the corner "j" of quad "k" to be considered, - // it needs to be on the same side of the two lines as - // corner "i". This is given, if the cross product has - // the same sign for both computations below: - float a3 = u1 - u2; - float b3 = v1 - v2; - // the current corner - float c31 = cur_quad->corners[i]->pt.x - u2; - float d31 = cur_quad->corners[i]->pt.y - v2; - // the candidate corner - float c32 = new_quads[k]->corners[j]->pt.x - u2; - float d32 = new_quads[k]->corners[j]->pt.y - v2; - float sign31 = a3 * d31 - c31 * b3; - float sign32 = a3 * d32 - c32 * b3; - - float a4 = u3 - u4; - float b4 = v3 - v4; - // the current corner - float c41 = cur_quad->corners[i]->pt.x - u4; - float d41 = cur_quad->corners[i]->pt.y - v4; - // the candidate corner - float c42 = new_quads[k]->corners[j]->pt.x - u4; - float d42 = new_quads[k]->corners[j]->pt.y - v4; - float sign41 = a4 * d41 - c41 * b4; - float sign42 = a4 * d42 - c42 * b4; - - // Also make shure that two border quads of the same row - // or - // column don't link. Check from the candidate corner's - // view, - // whether the corner diagonal from the current corner - // is also on the same side of the two lines as the - // current - // corner and the candidate corner. - float c33 = cur_quad->corners[(i + 2) % 4]->pt.x - u2; - float d33 = cur_quad->corners[(i + 2) % 4]->pt.y - v2; - float c43 = cur_quad->corners[(i + 2) % 4]->pt.x - u4; - float d43 = cur_quad->corners[(i + 2) % 4]->pt.y - v4; - float sign33 = a3 * d33 - c33 * b3; - float sign43 = a4 * d43 - c43 * b4; - - // This time we also need to make shure, that no quad - // is linked to a quad of another dilation run which - // may lie INSIDE it!!! - // Third: Therefore check everything from the viewpoint - // of the current quad compute midpoints of "parallel" - // quad sides 1 - float x5 = cur_quad->corners[i]->pt.x; - float y5 = cur_quad->corners[i]->pt.y; - float x6 = cur_quad->corners[(i + 1) % 4]->pt.x; - float y6 = cur_quad->corners[(i + 1) % 4]->pt.y; - // compute midpoints of "parallel" quad sides 2 - float x7 = x5; - float y7 = y5; - float x8 = cur_quad->corners[(i + 3) % 4]->pt.x; - float y8 = cur_quad->corners[(i + 3) % 4]->pt.y; - - // MARTIN: Heuristic - // For the corner "j" of quad "k" to be considered, - // it needs to be on the other side of the two lines - // than - // corner "i". This is given, if the cross product has - // a different sign for both computations below: - float a5 = x6 - x5; - float b5 = y6 - y5; - // the current corner - float c51 = cur_quad->corners[(i + 2) % 4]->pt.x - x5; - float d51 = cur_quad->corners[(i + 2) % 4]->pt.y - y5; - // the candidate corner - float c52 = new_quads[k]->corners[j]->pt.x - x5; - float d52 = new_quads[k]->corners[j]->pt.y - y5; - float sign51 = a5 * d51 - c51 * b5; - float sign52 = a5 * d52 - c52 * b5; - - float a6 = x8 - x7; - float b6 = y8 - y7; - // the current corner - float c61 = cur_quad->corners[(i + 2) % 4]->pt.x - x7; - float d61 = cur_quad->corners[(i + 2) % 4]->pt.y - y7; - // the candidate corner - float c62 = new_quads[k]->corners[j]->pt.x - x7; - float d62 = new_quads[k]->corners[j]->pt.y - y7; - float sign61 = a6 * d61 - c61 * b6; - float sign62 = a6 * d62 - c62 * b6; - - // Fourth: Then check everything from the viewpoint of - // the candidate quad compute midpoints of "parallel" - // quad sides 1 - float u5 = new_quads[k]->corners[j]->pt.x; - float v5 = new_quads[k]->corners[j]->pt.y; - float u6 = new_quads[k]->corners[(j + 1) % 4]->pt.x; - float v6 = new_quads[k]->corners[(j + 1) % 4]->pt.y; - // compute midpoints of "parallel" quad sides 2 - float u7 = u5; - float v7 = v5; - float u8 = new_quads[k]->corners[(j + 3) % 4]->pt.x; - float v8 = new_quads[k]->corners[(j + 3) % 4]->pt.y; - - // MARTIN: Heuristic - // For the corner "j" of quad "k" to be considered, - // it needs to be on the other side of the two lines - // than - // corner "i". This is given, if the cross product has - // a different sign for both computations below: - float a7 = u6 - u5; - float b7 = v6 - v5; - // the current corner - float c71 = cur_quad->corners[i]->pt.x - u5; - float d71 = cur_quad->corners[i]->pt.y - v5; - // the candidate corner - float c72 = - new_quads[k]->corners[(j + 2) % 4]->pt.x - u5; - float d72 = - new_quads[k]->corners[(j + 2) % 4]->pt.y - v5; - float sign71 = a7 * d71 - c71 * b7; - float sign72 = a7 * d72 - c72 * b7; - - float a8 = u8 - u7; - float b8 = v8 - v7; - // the current corner - float c81 = cur_quad->corners[i]->pt.x - u7; - float d81 = cur_quad->corners[i]->pt.y - v7; - // the candidate corner - float c82 = - new_quads[k]->corners[(j + 2) % 4]->pt.x - u7; - float d82 = - new_quads[k]->corners[(j + 2) % 4]->pt.y - v7; - float sign81 = a8 * d81 - c81 * b8; - float sign82 = a8 * d82 - c82 * b8; - - // Check whether conditions are fulfilled - if (((sign11 < 0 && sign12 < 0) || - (sign11 > 0 && sign12 > 0)) && - ((sign21 < 0 && sign22 < 0) || - (sign21 > 0 && sign22 > 0)) && - ((sign31 < 0 && sign32 < 0) || - (sign31 > 0 && sign32 > 0)) && - ((sign41 < 0 && sign42 < 0) || - (sign41 > 0 && sign42 > 0)) && - ((sign11 < 0 && sign13 < 0) || - (sign11 > 0 && sign13 > 0)) && - ((sign21 < 0 && sign23 < 0) || - (sign21 > 0 && sign23 > 0)) && - ((sign31 < 0 && sign33 < 0) || - (sign31 > 0 && sign33 > 0)) && - ((sign41 < 0 && sign43 < 0) || - (sign41 > 0 && sign43 > 0)) && - ((sign51 < 0 && sign52 > 0) || - (sign51 > 0 && sign52 < 0)) && - ((sign61 < 0 && sign62 > 0) || - (sign61 > 0 && sign62 < 0)) && - ((sign71 < 0 && sign72 > 0) || - (sign71 > 0 && sign72 < 0)) && - ((sign81 < 0 && sign82 > 0) || - (sign81 > 0 && sign82 < 0))) - { - closest_corner_idx = j; - closest_quad = new_quads[k]; - min_dist = dist; - } - } - } - } - - // Have we found a matching corner point? - if (closest_corner_idx >= 0 && min_dist < FLT_MAX) - { - CvCBCorner::Ptr& closest_corner = - closest_quad->corners[closest_corner_idx]; - closest_corner->pt.x = (pt.x + closest_corner->pt.x) * 0.5f; - closest_corner->pt.y = (pt.y + closest_corner->pt.y) * 0.5f; - - // We've found one more corner - remember it - // ATTENTION: write the corner x and y coordinates separately, - // else the crucial row/column entries will be overwritten !!! - cur_quad->corners[i]->pt.x = closest_corner->pt.x; - cur_quad->corners[i]->pt.y = closest_corner->pt.y; - cur_quad->neighbors[i] = closest_quad; - closest_quad->corners[closest_corner_idx]->pt.x = - closest_corner->pt.x; - closest_quad->corners[closest_corner_idx]->pt.y = - closest_corner->pt.y; - - // Label closest quad as labeled. In this way we exclude it - // being considered again during the next loop iteration - closest_quad->labeled = true; - - // We have a new member of the final pattern, copy it over - CvCBQuad::Ptr newQuad = CvCBQuad::Ptr(new CvCBQuad); - - newQuad->count = 1; - newQuad->edge_len = closest_quad->edge_len; - newQuad->group_idx = - cur_quad->group_idx; // the same as the current quad - newQuad->labeled = false; // do it right afterwards - - // We only know one neighbor for shure, initialize rest with - // the nullptr pointer - newQuad->neighbors[closest_corner_idx] = cur_quad; - newQuad->neighbors[(closest_corner_idx + 1) % 4] - .reset(); // = nullptr; - newQuad->neighbors[(closest_corner_idx + 2) % 4] - .reset(); // = nullptr; - newQuad->neighbors[(closest_corner_idx + 3) % 4] - .reset(); // = nullptr; - - for (int j = 0; j < 4; j++) - { - newQuad->corners[j] = CvCBCorner::Ptr(new CvCBCorner); - newQuad->corners[j]->pt.x = closest_quad->corners[j]->pt.x; - newQuad->corners[j]->pt.y = closest_quad->corners[j]->pt.y; - } - - old_quads.push_back(newQuad); - cur_quad->neighbors[i] = newQuad; - - // Start the function again - return -1; - } - } - } - - // Finished, don't start the function again - return 1; -} - -//=========================================================================== -// GENERATE QUADRANGLES -//=========================================================================== -int icvGenerateQuads( - vector& out_quads, vector& out_corners, - const CImage& image, int flags, [[maybe_unused]] int dilation, - bool firstRun) -{ - // Initializations - int quad_count = 0; - - // Empiric sower bound for the size of allowable quadrangles. - // MARTIN, modified: Added "*0.1" in order to find smaller quads. - const int min_size = - cvRound(image.getWidth() * image.getHeight() * .03 * 0.01 * 0.92 * 0.1); - - // Initialize contour retrieving routine - cv::Mat im_mat = image.asCvMat(SHALLOW_COPY); - std::vector> contours; - std::vector hierarchy; - - cv::findContours( - im_mat, contours, hierarchy, cv::RETR_LIST, cv::CHAIN_APPROX_SIMPLE); - - // Get all the contours one by one - for (const auto& contour : contours) - { - contour. - - CvRect rect = ((CvContour*)src_contour)->rect; - - // Reject contours with a too small perimeter and contours which are - // completely surrounded by another contour - // MARTIN: If this function is called during PART 1, then the parameter - // "first run" - // is set to "true". This guarantees, that only "nice" squares are - // detected. - // During PART 2, we allow the polygonial approcimation function below - // to - // approximate more freely, which can result in recognized "squares" - // that are in - // reality multiple blurred and sticked together squares. - if (CV_IS_SEQ_HOLE(src_contour) && rect.width * rect.height >= min_size) - { - int min_approx_level = 2, max_approx_level; - if (firstRun == true) max_approx_level = 3; - else - max_approx_level = MAX_CONTOUR_APPROX; - int approx_level; - for (approx_level = min_approx_level; - approx_level <= max_approx_level; approx_level++) - { - dst_contour = cvApproxPoly( - src_contour, sizeof(CvContour), temp_storage, - CV_POLY_APPROX_DP, (float)approx_level); - - // We call this again on its own output, because sometimes - // cvApproxPoly() does not simplify as much as it should. - dst_contour = cvApproxPoly( - dst_contour, sizeof(CvContour), temp_storage, - CV_POLY_APPROX_DP, (float)approx_level); - - if (dst_contour->total == 4) break; - } - - // Reject non-quadrangles - if (dst_contour->total == 4 && cvCheckContourConvexity(dst_contour)) - { - CvPoint pt[4]; - // double d1, d2; //, p = cvContourPerimeter(dst_contour); - // double area = fabs(cvContourArea(dst_contour, CV_WHOLE_SEQ)); - // double dx, dy; - - for (int i = 0; i < 4; i++) - pt[i] = *(CvPoint*)cvGetSeqElem(dst_contour, i); - - // dx = pt[0].x - pt[2].x; - // dy = pt[0].y - pt[2].y; - // d1 = sqrt(dx*dx + dy*dy); - // - // dx = pt[1].x - pt[3].x; - // dy = pt[1].y - pt[3].y; - // d2 = sqrt(dx*dx + dy*dy); - - // PHILIPG: Only accept those quadrangles which are more - // square than rectangular and which are big enough - // double d3, d4; - // dx = pt[0].x - pt[1].x; - // dy = pt[0].y - pt[1].y; - // d3 = sqrt(dx*dx + dy*dy); - // dx = pt[1].x - pt[2].x; - // dy = pt[1].y - pt[2].y; - // d4 = sqrt(dx*dx + dy*dy); - if (true) //!(flags & CV_CALIB_CB_FILTER_QUADS) || - // d3*4 > d4 && d4*4 > d3 && d3*d4 < area*1.5 && area > min_size - // && - // d1 >= 0.15 * p && d2 >= 0.15 * p ) - { - auto* parent = (CvContourEx*)(src_contour->v_prev); - parent->counter++; - if (!board || board->counter < parent->counter) - board = parent; - dst_contour->v_prev = (CvSeq*)parent; - cvSeqPush(root, &dst_contour); - } - } - } - } - - // Finish contour retrieving - // cvEndFindContours(&scanner); - - // Allocate quad & corner buffers - out_quads.clear(); - for (int q = 0; q < root->total; q++) - out_quads.push_back(CvCBQuad::Ptr(new CvCBQuad)); - - out_corners.clear(); - for (int q = 0; q < 4 * root->total; q++) - out_corners.push_back(CvCBCorner::Ptr(new CvCBCorner)); - - // Create array of quads structures - for (int idx = 0; idx < root->total; idx++) - { - CvCBQuad::Ptr& q = out_quads[quad_count]; - src_contour = *(CvSeq**)cvGetSeqElem(root, idx); - if ((flags & cv::CALIB_CB_FILTER_QUADS) && - src_contour->v_prev != (CvSeq*)board) - continue; - - // Reset group ID - // memset( q, 0, sizeof(*q) ); - q->group_idx = -1; - assert(src_contour->total == 4); - for (int i = 0; i < 4; i++) - { - cv::Point2f pt = - cvPointTo32f(*(CvPoint*)cvGetSeqElem(src_contour, i)); - CvCBCorner::Ptr& corner = out_corners - [quad_count * 4 + i]; // &(*out_corners)[quad_count*4 - // + i]; - - // memset( corner, 0, sizeof(*corner) ); - corner->pt = pt; - q->corners[i] = corner; - } - q->edge_len = FLT_MAX; - for (int i = 0; i < 4; i++) - { - float dx = q->corners[i]->pt.x - q->corners[(i + 1) & 3]->pt.x; - float dy = q->corners[i]->pt.y - q->corners[(i + 1) & 3]->pt.y; - float d = dx * dx + dy * dy; - if (q->edge_len > d) q->edge_len = d; - } - quad_count++; - } - - if (cvGetErrStatus() < 0) - { - out_quads.clear(); - // if( out_corners ) cvFree( out_corners ); - out_corners.clear(); - quad_count = 0; - } - - cvClearSeq(root); - - return quad_count; -} - -// Return 1 on success in finding all the quads, 0 on didn't, -1 on error. -int myQuads2Points( - const std::vector& output_quads, const CvSize& pattern_size, - std::vector& out_corners) -{ - // Initialize - out_corners.clear(); - - bool flagRow = false; - bool flagColumn = false; - int maxPattern_sizeRow = -1; - int maxPattern_sizeColumn = -1; - - // Compute the minimum and maximum row / column ID - // (it is unlikely that more than 8bit checkers are used per dimension) - int min_row = 127; - int max_row = -127; - int min_column = 127; - int max_column = -127; - - for (size_t i = 0; i < output_quads.size(); i++) - { - const CvCBQuad::Ptr& q = output_quads[i]; - - for (int j = 0; j < 4; j++) - { - if ((q->corners[j])->row > max_row) max_row = (q->corners[j])->row; - if ((q->corners[j])->row < min_row) min_row = (q->corners[j])->row; - if ((q->corners[j])->column > max_column) - max_column = (q->corners[j])->column; - if ((q->corners[j])->column < min_column) - min_column = (q->corners[j])->column; - } - } - - // If in a given direction the target pattern size is reached, we know - // exactly how - // the checkerboard is oriented. - // Else we need to prepare enough "dummy" corners for the worst case. - for (size_t i = 0; i < output_quads.size(); i++) - { - const CvCBQuad::Ptr& q = output_quads[i]; - - for (int j = 0; j < 4; j++) - { - if ((q->corners[j])->column == max_column && - (q->corners[j])->row != min_row && - (q->corners[j])->row != max_row) - { - if ((q->corners[j]->needsNeighbor) == false) - { - // We know, that the target pattern size is reached - // in column direction - flagColumn = true; - } - } - if ((q->corners[j])->row == max_row && - (q->corners[j])->column != min_column && - (q->corners[j])->column != max_column) - { - if ((q->corners[j]->needsNeighbor) == false) - { - // We know, that the target pattern size is reached - // in row direction - flagRow = true; - } - } - } - } - - if (flagColumn == true) - { - if (max_column - min_column == pattern_size.width + 1) - { - maxPattern_sizeColumn = pattern_size.width; - maxPattern_sizeRow = pattern_size.height; - } - else - { - maxPattern_sizeColumn = pattern_size.height; - maxPattern_sizeRow = pattern_size.width; - } - } - else if (flagRow == true) - { - if (max_row - min_row == pattern_size.width + 1) - { - maxPattern_sizeRow = pattern_size.width; - maxPattern_sizeColumn = pattern_size.height; - } - else - { - maxPattern_sizeRow = pattern_size.height; - maxPattern_sizeColumn = pattern_size.width; - } - } - else - { - // If target pattern size is not reached in at least one of the two - // directions, then we do not know where the remaining corners are - // located. Account for this. - maxPattern_sizeColumn = max(pattern_size.width, pattern_size.height); - maxPattern_sizeRow = max(pattern_size.width, pattern_size.height); - } - - // JL: Check sizes: - if (maxPattern_sizeRow * maxPattern_sizeColumn != - pattern_size.width * pattern_size.height) - return 0; // Bad... - // and also, swap rows/columns so we always have consistently the points in - // the order: first all columns in a row, then the next row, etc... - bool do_swap_col_row = maxPattern_sizeRow != pattern_size.height; - - if (do_swap_col_row) - { - std::swap(min_row, min_column); - std::swap(maxPattern_sizeRow, maxPattern_sizeColumn); - } - - // Write the corners in increasing order to "out_corners" - - for (int i = min_row + 1; i < maxPattern_sizeRow + min_row + 1; i++) - { - for (int j = min_column + 1; j < maxPattern_sizeColumn + min_column + 1; - j++) - { - // Reset the iterator - int iter = 1; - - for (size_t k = 0; k < output_quads.size(); k++) - { - for (int l = 0; l < 4; l++) - { - int r = output_quads[k]->corners[l]->row; - int c = output_quads[k]->corners[l]->column; - if (do_swap_col_row) std::swap(r, c); - - if (r == i && c == j) - { - // Only write corners to the output file, which are - // connected - // i.e. only if iter == 2 - if (iter == 2) - { - // The respective row and column have been found, - // save point: - out_corners.push_back( - output_quads[k]->corners[l]->pt); - } - - // If the iterator is larger than two, this means that - // more than - // two corners have the same row / column entries. Then - // some - // linking errors must have occured and we should not - // use the found - // pattern - if (iter > 2) return -1; - - iter++; - } - } - } - - // If the respective row / column is non - existent or is a border - // corner - if (iter == 1 || iter == 2) - { - // cornersX << -1; - // cornersX << " "; - // cornersY << -1; - // cornersY << " "; - } - } - } - - // All corners found? - return (out_corners.size() == - size_t(pattern_size.width) * size_t(pattern_size.height)) - ? 1 - : 0; -} - -// Make unique all the (smart pointers-pointed) objects in the list and -// neighbors lists. -void quadListMakeUnique(std::vector& quads) -{ - std::map pointer2index; - for (size_t i = 0; i < quads.size(); i++) - pointer2index[quads[i].get()] = i; - - vector> neig_indices(quads.size()); - for (size_t i = 0; i < quads.size(); i++) - for (size_t j = 0; j < 4; j++) - neig_indices[i][j] = pointer2index[quads[i]->neighbors[j].get()]; - - std::vector new_quads = quads; - std::for_each(new_quads.begin(), new_quads.end(), [](CvCBQuad::Ptr& ptr) { - ptr = CvCBQuad::Ptr(new CvCBQuad(*ptr)); - }); - for (size_t i = 0; i < new_quads.size(); i++) - for (size_t j = 0; j < 4; j++) - new_quads[i]->neighbors[j] = new_quads[neig_indices[i][j]]; -} - -//=========================================================================== -// END OF FILE (Of "OCamCalib Toolbox" code) -//=========================================================================== - -#endif // MRPT_HAS_OPENCV diff --git a/libs/vision/src/checkerboard_ocamcalib_detector.h b/libs/vision/src/checkerboard_ocamcalib_detector.h deleted file mode 100644 index 536af47b07..0000000000 --- a/libs/vision/src/checkerboard_ocamcalib_detector.h +++ /dev/null @@ -1,123 +0,0 @@ -/* +------------------------------------------------------------------------+ - | Mobile Robot Programming Toolkit (MRPT) | - | https://www.mrpt.org/ | - | | - | Copyright (c) 2005-2024, Individual contributors, see AUTHORS file | - | See: https://www.mrpt.org/Authors - All rights reserved. | - | Released under BSD License. See: https://www.mrpt.org/License | - +------------------------------------------------------------------------+ */ - -#pragma once - -// Universal include for all versions of OpenCV -#include -#include - -#include -#include -#include - -#if MRPT_HAS_OPENCV - -// Debug visualizations... -// Ming #define VIS 1 -#define VIS 0 - -// Definition Contour Struct -struct CvContourEx -{ - CV_CONTOUR_FIELDS() - int counter; -}; - -// Definition Corner Struct -struct CvCBCorner; - -struct CvCBCorner -{ - using Ptr = std::shared_ptr; - CvCBCorner() = default; - cv::Point2f pt; // X and y coordinates - int row{-1000}; // Row and column of the corner - int column{-1000}; // in the found pattern - bool needsNeighbor; // Does the corner require a neighbor? - int count{0}; // number of corner neighbors - CvCBCorner::Ptr neighbors[4]; // pointer to all corner neighbors -}; - -// Definition Quadrangle Struct -// This structure stores information about the chessboard quadrange -struct CvCBQuad; - -struct CvCBQuad -{ - using Ptr = std::shared_ptr; - CvCBQuad() = default; - - int count{0}; // Number of quad neihbors - int group_idx{0}; // Quad group ID - float edge_len{0}; // Smallest side length^2 - CvCBCorner::Ptr corners[4]; // CvCBCorner *corners[4]; // - // Coordinates of quad corners - CvCBQuad::Ptr neighbors[4]; // Pointers of quad neighbors - bool labeled{false}; // Has this corner been labeled? - double area{0.0}, area_ratio{1.0}; -}; - -//=========================================================================== -// PUBLIC FUNCTION PROTOTYPES -//=========================================================================== -// Return: -1: errors, 0: not found, 1: found OK -int cvFindChessboardCorners3( - const mrpt::img::CImage& img_, CvSize pattern_size, - std::vector& out_corners); - -// Return: true: found OK -bool find_chessboard_corners_multiple( - const mrpt::img::CImage& img_, CvSize pattern_size, - std::vector>& out_corners); - -//=========================================================================== -// INTERNAL FUNCTION PROTOTYPES -//=========================================================================== -int icvGenerateQuads( - std::vector& quads, std::vector& corners, - const mrpt::img::CImage& img, int flags, int dilation, bool firstRun); - -void mrFindQuadNeighbors2(std::vector& quads, int dilation); - -int mrAugmentBestRun( - std::vector& new_quads, int new_dilation, - std::vector& old_quads, int old_dilation); - -void icvFindConnectedQuads( - std::vector& in_quads, - std::vector& out_quad_group, const int group_idx, - const int dilation); - -void mrLabelQuadGroup( - std::vector& quad_group, const CvSize& pattern_size, - bool firstRun); - -// Remove quads' extra quads until reached the expected number of quads. -void icvCleanFoundConnectedQuads( - std::vector& quads, const CvSize& pattern_size); - -// JL: Return 1 on success in finding all the quads, 0 on didn't, -1 on error. -int myQuads2Points( - const std::vector& output_quads, const CvSize& pattern_size, - std::vector& out_corners); - -// JL: Make unique all the (smart pointers-pointed) objects in the list and -// neighbors lists. -void quadListMakeUnique(std::vector& quads); - -// JL: Refactored code from within cvFindChessboardCorners3() and alternative -// algorithm: -bool do_special_dilation( - mrpt::img::CImage& thresh_img, const int dilations, - const cv::Mat& kernel_cross, const cv::Mat& kernel_rect, - const cv::Mat& kernel_diag1, const cv::Mat& kernel_diag2, - const cv::Mat& kernel_horz, const cv::Mat& kernel_vert); - -#endif // MRPT_HAS_OPENCV diff --git a/libs/vision/src/vision_utils.cpp b/libs/vision/src/vision_utils.cpp index ba58d9c969..7f5ce6a04b 100644 --- a/libs/vision/src/vision_utils.cpp +++ b/libs/vision/src/vision_utils.cpp @@ -111,7 +111,7 @@ void vision::openCV_cross_correlation( // Compute cross correlation: cv::matchTemplate( img_region_to_search.asCvMat(SHALLOW_COPY), - patch_im.asCvMat(SHALLOW_COPY), result, CV_TM_CCORR_NORMED); + patch_im.asCvMat(SHALLOW_COPY), result, cv::TM_CCORR_NORMED); // Find the max point: double mini; diff --git a/samples/CMakeLists.txt b/samples/CMakeLists.txt index ee4b9a8275..f86821dcd8 100644 --- a/samples/CMakeLists.txt +++ b/samples/CMakeLists.txt @@ -256,7 +256,6 @@ if(MRPT_BUILD_EXAMPLES) vision_checkerboard_detectors vision_feature_extraction vision_keypoint_matching_example - vision_multiple_checkerboards vision_stereo_calib_example ) set(CMAKE_EXAMPLE_DEPS mrpt::vision mrpt::gui) diff --git a/samples/vision_checkerboard_detectors/test.cpp b/samples/vision_checkerboard_detectors/test.cpp index b23ac4d515..8cae026371 100644 --- a/samples/vision_checkerboard_detectors/test.cpp +++ b/samples/vision_checkerboard_detectors/test.cpp @@ -44,52 +44,30 @@ void TestCheckerboardDetectors() const unsigned int checkerboard_size_y = 9; // Detect: - timlog.enter("findChessboardCorners [OpenCV]"); + timlog.enter("findChessboardCorners"); // bool detectOk1 = mrpt::vision::findChessboardCorners( img, cornerCoords, checkerboard_size_x, checkerboard_size_y, - true, // normalize_image - false // useScaramuzzaMethod + true // normalize_image ); - timlog.leave("findChessboardCorners [OpenCV]"); + timlog.leave("findChessboardCorners"); // Draw: CImage img_detect1 = img; img_detect1.drawChessboardCorners( cornerCoords, checkerboard_size_x, checkerboard_size_y); - timlog.enter("findChessboardCorners [Scaramuzza]"); - - // bool detectOk2 = - mrpt::vision::findChessboardCorners( - img, cornerCoords, checkerboard_size_x, checkerboard_size_y, - true, // normalize_image - true // useScaramuzzaMethod - ); - - timlog.leave("findChessboardCorners [Scaramuzza]"); - - // Draw: - CImage img_detect2 = img; - img_detect2.drawChessboardCorners( - cornerCoords, checkerboard_size_x, checkerboard_size_y); - - // ASSERT_(detectOk1 && detectOk2); - // Show results: - CDisplayWindow win1("Detected checkerboard (OpenCV)"); + CDisplayWindow win1("Detected checkerboard"); win1.showImage(img_detect1); - CDisplayWindow win2("Detected checkerboard (Scaramuzza)"); - win2.showImage(img_detect2); - timlog.dumpAllStats(); timlog.clear(); // wait till user closes any window: - while (win1.isOpen() && win2.isOpen()) + while (win1.isOpen()) { std::this_thread::sleep_for(10ms); } diff --git a/samples/vision_multiple_checkerboards/CMakeLists.txt b/samples/vision_multiple_checkerboards/CMakeLists.txt deleted file mode 100644 index 654301304c..0000000000 --- a/samples/vision_multiple_checkerboards/CMakeLists.txt +++ /dev/null @@ -1,62 +0,0 @@ -#----------------------------------------------------------------------------------------------- -# CMake file for the MRPT example: /vision_multiple_checkerboards -# -# Run with "ccmake ." at the root directory, or use it as a template for -# starting your own programs -#----------------------------------------------------------------------------------------------- -set(sampleName vision_multiple_checkerboards) -project(EXAMPLE_${sampleName}) - -cmake_minimum_required(VERSION 3.1) - -# --------------------------------------------------------------------------- -# 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: -# https://www.mrpt.org/Libraries -# Add the top-level dependencies only. -# -------------------------------------------------------------------------- -foreach(dep vision;gui) - # if not building from inside MRPT source tree, find it as a cmake - # imported project: - if (NOT TARGET mrpt::${dep}) - find_package(mrpt-${dep} REQUIRED) - endif() -endforeach() - -# Define the executable target: -add_executable(${sampleName} test.cpp ) - -if(TARGET examples) - add_dependencies(examples ${sampleName}) -endif() - -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() - -# Add the required libraries for linking: -foreach(dep vision;gui) - target_link_libraries(${sampleName} mrpt::${dep}) -endforeach() - -# Set optimized building: -if((${CMAKE_CXX_COMPILER_ID} STREQUAL "Clang" OR CMAKE_COMPILER_IS_GNUCXX) AND NOT CMAKE_BUILD_TYPE MATCHES "Debug") - add_compile_options(-O3) -endif() - -# This part can be removed if you are compiling this program outside of -# the MRPT tree: -if(DEFINED MRPT_LIBS_ROOT) # Fails if build outside of MRPT project. - DeclareAppDependencies(${sampleName} mrpt::vision;mrpt::gui) # Dependencies -endif() diff --git a/samples/vision_multiple_checkerboards/test.cpp b/samples/vision_multiple_checkerboards/test.cpp deleted file mode 100644 index 0c9baae46c..0000000000 --- a/samples/vision_multiple_checkerboards/test.cpp +++ /dev/null @@ -1,105 +0,0 @@ -/* +------------------------------------------------------------------------+ - | Mobile Robot Programming Toolkit (MRPT) | - | https://www.mrpt.org/ | - | | - | Copyright (c) 2005-2024, Individual contributors, see AUTHORS file | - | See: https://www.mrpt.org/Authors - All rights reserved. | - | Released under BSD License. See: https://www.mrpt.org/License | - +------------------------------------------------------------------------+ */ - -#include -#include -#include -#include - -#include - -using namespace std; -using namespace mrpt; -using namespace mrpt::img; -using namespace mrpt::vision; -using namespace mrpt::system; -using namespace mrpt::gui; - -#include -std::string myDataDir = - MRPT_EXAMPLES_BASE_DIRECTORY + string("vision_multiple_checkerboards/"); - -// ------------------------------------------------------ -// TestMultipleCheckerboard -// ------------------------------------------------------ -void TestMultipleCheckerboard( - const std::string& img_filename, const unsigned int checkerboard_size_x, - const unsigned int checkerboard_size_y) -{ - CTimeLogger timlog; - - // Load img: - CImage img; - if (!img.loadFromFile(img_filename)) - throw std::runtime_error("Can't load image!"); - - // Detect multiple-checkerboards: - vector> listCornerCoords; - - timlog.enter("findMultipleChessboardsCorners"); - - mrpt::vision::findMultipleChessboardsCorners( - img, listCornerCoords, checkerboard_size_x, checkerboard_size_y); - - timlog.leave("findMultipleChessboardsCorners"); - - cout << "Number of checkerboards detected: " << listCornerCoords.size() - << endl; - - // Draw: - CImage img_detect; - img.colorImage(img_detect); - for (size_t i = 0; i < listCornerCoords.size(); i++) - img_detect.drawChessboardCorners( - listCornerCoords[i], checkerboard_size_x, checkerboard_size_y); - - // Show results: - CDisplayWindow win1("Detected checkerboards "); - win1.showImage(img_detect); - - timlog.dumpAllStats(); - timlog.clear(); - - // wait till user closes any window: - win1.waitForKey(); -} - -// ------------------------------------------------------ -// MAIN -// ------------------------------------------------------ -int main(int argc, char** argv) -{ - try - { - std::string sFile = myDataDir + string("test_3_checkerboards_5x4.jpg"); - unsigned int checkerboard_size_x = 5; - unsigned int checkerboard_size_y = 4; - - if (argc == 4) - { - sFile = std::string(argv[1]); - checkerboard_size_x = atoi(argv[2]); - checkerboard_size_y = atoi(argv[3]); - } - else if (argc != 1) - { - std::cerr << "Usage: " << argv[0] << " [IMAGE_FILE NX NY]\n"; - return 1; - } - - TestMultipleCheckerboard( - sFile, checkerboard_size_x, checkerboard_size_y); - return 0; - } - catch (const std::exception& e) - { - std::cerr << "MRPT error: " << mrpt::exception_to_str(e) << std::endl; - return -1; - } -} diff --git a/samples/vision_multiple_checkerboards/test_3_checkerboards_5x4.jpg b/samples/vision_multiple_checkerboards/test_3_checkerboards_5x4.jpg deleted file mode 100644 index ee7f371eb35334a31e971c453dd7f3d97a75513c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 111376 zcmbTdWmH>F)IJ&t#kF{$IHf>a+#QM+Elwe{Sb^eh2~wbV@#0Y2iv)*2ai_SuYl1aE z2><-vcddKB+zitR000L11$bNrC;*;d z{MY{LpZwRbF#qeHVqsxoVL!#j{+|m64;LE;4+k3?mjD+J|G$QQM@WEA_}_>BCi&l= zK6#3X`4k@q8|Qz9{D0~my8vXkPmC~`FfmvFPslJZ$uJ&!0gPxlpZyqFVNr2OX<2z)eFLPiskx=~Pfu@O|G?nT z@YM9o?A-jq;?m~U_Rj9!{=wl9{NnQJ`sN?v_U=EuFaVhUs}{Qdf7FW%t=E(P_5kNU zy)d45qc2P{tf$O;*w5s2a6Y+`v+xJwQphLd*LLHv3h2TpKfC?Kr(zS_WQYH!+W%Q4@a8Mj;Up-$>y0-&edHRRuU(E@3RcLO zjrxl`%G1yCDfNhh061zVufbM~5!?bD@xh617tVmeVTwCKsM^>gAVkgQQnB_Ss2%h3 z>uQc1zH+DdVXJ;m^*>_$;?M60Oc5Phj>0UB3`9&Mt>=C}rKAiB7%uGRdo>O0xSP(* z=g)`s9l;8>)MP2vMiVzNAif!AZ_TW7iN!a*VzYPlzH{;S+-q<08h#_(oqliAILyf8 z+podaPX@r7ruh|1#zu#UWfMPB|F!^!DoFa*8yNd#i(g1z^!G_Xru$uQIi{giKG0sq zC@6W&FV^1NhPbq1wjg9~C^Ym%PyawsxP4#Be~GU=o{MkeD_hH# zsb0M_uT51TYE?V;DA4#3fbY<2GAeDg{;V(s+}vu9aeGz?q(C_L$^RWhB{~G@S;Peth>)s8?B2HU{HxIE%Q0OXkHRpxa)?0vePm z?HyHJ4XIer+cU~}U%Sr%z%XkzXX>%xOD_G;@J~a@uQTmq!y|z6?S74B9Jyd=sfCNc z2mkTHa)Y=BmRW=Kq+N5{Sr9#(I2s<`$64ef&{J>B9xam2yr!K+Oqumc8meF(5BF&d zhE1Ju7C-EG4Pb59V%c8R4D(QfyXP3|9?BumU`e`4rJx@;so3Y^tmXpnBoy&SSZ*&A zZ~XxE0tPC0Is=n*HB(uB?<>!bD;HOAQMLcm((aRef9msqYx2D$SM%$Z50JS?Q|qby zzZM8*(fshLi16oyM}`e%nu=;!pRZa&<~7WRQOf)CNUEg1M*u7twF2U1*=dz?8*Dip z8Vd+{a{5_iLe8vdpe9m0qE9PQJU131mZR!iZK7mn%7K-!MU!@$Jhvb&-9vy698SDX zc#zWMq9}M;2h97UoZdYyPNL=_w%L3=#uuNuT%UBP*;BV02cWlU&92lO+7gqh%Kn{v+ZGA^xo3ywX^gQED6VE{OfolOA3v< zrYeKY?^FwlXRa||wVXG?XSz?iM%}xXfwlpn58=ocoB5Oj(S`S4d$9TogLB6_xYjq~ z|D3XiEcr+;07S=C@2+dId*PZ-zO{U!RUb3v831;{k8G2Zt0>(sYXyl6lzP2%dG{G# zy4d@)Q*KG*J^7N=YQ zEF&`W5dh)yJp$U^-A{~-IEUp(HPb*~yF+q^j3!V=7~PgvUcm{9teGhXPiG7iw|sbG z>ZNQ+iYa*t_?&fA&dZ946G8#z8m^(%S6?k)MB+h*SV>Ng#ts>e;WE-5kAOwxZKA8_ z7tn9EW~<(mkAUZk(KjrJc~Lq^VWmJTAiSo{#5X$euVvP@RN0W^g-AMmA;X4&kZ2RH zzTmev2kWSnnBAPMq&i?c5_7Wxyr8iCx_0*}`90WAA3Yh=;SqrKfPi>(vy&FX`^~`p zohzKI@32Iz*{q&t2r|DfZDu_e$t!yVm#yxG_56d1$PM`Ir#;(S zs$$R|ZzE?GGE|!ZeN><42p}Uu8D}eo5ydt~D5uH0&7wML0!|jIfB-0p( z9G~iuX_dSWJZf@8YkLWMR(mOQYl@Slq>LH^suhju_Ua^IH37AX4E^0=SicLqX%aCm z-;Soip}5Bgnn!^B*4}i>2Gt|rH%_3aB@wlyog^>>*&O8@fl zzok*uU8~tW9qheTub0(#Wv|P8`<>e>ph>7kCE$|L&`{Hxc(VG3a1>q`*--JYrs%^l zIQC=24Ksq1uqZr&v+Fh@V}0Aaw=p3EPm~E+=v_9ok;>qrKcRF}35L|$I43-cR=0(eZ5FTNkWA43Th%2=<5X_MSiT~z!72du=8cgSsh3x7BmdSUYO zxzbmQAmti>b}iy44z=X<2q1q1@KZ^Uaa175cK@x{O>~d^W^I9Wv3XybBJE`mR>0up zNHAV#aBy@u`lMV%-;X$`WP((VRB6iR#EVi!!lFL?aJ`}^v%KVR(9gL+6rn8d&bSjK zmUrUt(7rU-kyK|>n^@Yy#u;9o2Cjv6Q*R<)yJuNwuAm_23;={GoO(-t|Hd}BoyWga z_0{du1~xcK<113>Aq6EB@TM{DUq1?C=FO)cRw|!Y3Na^GnLf92d>`LPUR5oE_PsG& za~qH@qF4T{zdhktU2`dI%UJ8(1?Rd2F@DVno%j?#7b)|3J!I@6o}|vb2hRw7gm2jD z+8e!~%=($H17x>m--n>~M>#gMk`V78vRCc2hNQjBK zE_+V1h3!*7cW={Zyymh41zlf(^Ib>zT<;BUa|O)6-4aNlSBs8Ywz|r2SuNC4I@xo<_P)=B59(gB4}|e%7XW zZ~(McGUyG4X#q)JXF3L`Vq*Rc=mbIiN>|Vm%1HWRWuDfYF7U{!FwS-Mk-d(as_?UA z%`0AMO=c$9oXfqN$W-vkeQ0|G5ZcjiKi_q7B#Eqf1blh~L`@FuC_2#Rp0ZZUWV^1( zJY;n;AxKd2tpbgIhcuNBfq6Oh@vSXlJ5kZPQzxG4?nFpDF7UI2ta-<`ulxR}&V2hA zP@TIso?*P|=jr$+e$@EnZRIZC$9HmP_*%+$2!nZw7 z740kS^XTD|pYs|ZPY7Ff;+|>}JYDkHj^lowxHse4x&Z1r4*xXa!uj4_bLDD<=`b0nv4Jme0<3 zR~tlt8AD7$vGa@1XMf%fIjZ3_G$nC72w`)dgkQ@zD4NtTmfM%AFk|# zi};7Flp(^byT7mQyDL)*^H`AGpa_cU;h$`7{xh8Xsq5`Ko)kA;HcP#vBx>1o^ZERK z2WqAGX9J=YUY%+&EjX-9vw~ex5*}rgf3{t_Ce+66mnjb?7aDn!34)BSDPO*sQSrQ zl$tCEmm>+tRTxvz@Jeh0ZrX_fkDU)iDpQ`2lU8nnr&(GmruA6@BB-o>jPiCa;ZMhJ z#ZPKr_PV}*BH*>1agg6Zo(G884$Xi&M|ARQIH*MEgu6zP+ET6^bTTWjbhq#R#+hr6 zz*8)8BvK4vcK*x<@h09$V*U;6?r;8Ns#zYjw(5)HUrGrd z?6|Y6Y-$rtr6UGrK~wb^#}6zHnT4bm1!DVXWARm&kJMAPfR^6Ce{gh@BL3&j4>vC4 zYb!c}ZF)V?K08aUI8}BxNBPsQU)fviu&MZcfcD5oz(ci%5sC$|=W9$kC1ykzeB^LS z64S}azyJ#yi3ENAMwrDQSMvj+LTAvKc;RN$mUtR<#j7!0HpY0gzv>bJ>Dt`?-jM}m zM_aO6iEWaeSe`$33S(?!6=WALI{fB2f3cZUA)GzSf69+YlaYYj%_Hyi?G?1)lG60` zKWs<4F&F030xY27plsXCpH`0my`aH@xz6&`vbO`LKiPF5;=HBj*5i+WS1560JQRcn z?luB{eFWfwCR!PLCL(fpBHq{krk1Cog169}6(_Vc1l@_aPRTDds7@ifZK#Tf2lfB@8>_8IkDv4*W~bR`gGF2 zRA#E3W`p~~o_&^xAB6GZ>*XsLNQVGOgmYALo2#~jT7p8Jx1jzaR?E!<=$kUUZ7)lX z7$JrO9RXn-h@^n-2VR+!fD)O3b^1|0%2Bd1^AO7It8!hWBjU%l#oV75w7FE1DPmlV zRnOoJ2|R(Suuhirq+1E+qXRo9vnRQ}o zcApvIcm$ZYb8T-8#Gi?R$%ck*gS2IebaMwluiMzI=WUtd+S=ydx#(}xDXIFs&2D9g zrEgl0m{#@s;$I%{W^yY=PwwvsnBJ*3PTAFc1n{614rB3GhQr#6D^5f<0kEL)v*4I#{f+cQxF*o z((-Gvdb3bkB2k|ZmyG#g=uSiJw_4N8ZnOxDcCMhT63Th4sW85G`=jMJi=^ikg|iIKGPYP@4e zcwKpdtw)Tr50nc)qu~(n@$;mfQlE7=nyE$~Ub9`2M9}ED1^jY5y z-~%x+GXnqgW!G{&!yP&Ya+`MqSlw1=rT_CscAmz+^t9K{J%6#VP=sH!LM(23tM^;} zWk3u-87oRpe`181qu5_>giOhh;D?OK?!2K>p|nF(qnVd9pkGN`@AF^1#3{@HdOv^t zT!<+@DS`9Au6F+^d-qp*Fv0VswAYZ-a+KMb?aQUs=Z4#&WJPpzLPZ4#MQntBPDbIH4{1O7SogtvwYG0r_Rc|&{o}pi&n{p z^@Y??ud^$z4I!^GOST|`8|4DOlG=Wi7^lBTag5W@4d+nct6NsL_ML$Cy`s21WyQBW z#khS+Bd^`Ql3pEV7>)2g&BT*wUQJ5Uw;sm0r=gh6xqUX~(=w>KvE zefZ`nHW@#TPS##-qn+2#^B>J(0FV5aQ+pU~b88GuWPEeG^dz?Y6 zjTnJ@o?7o#XQOc?E4?`nK}c~&!;CZJ?xxP9KFW7vr8Zses|De_;)YCkr!@QlF@iIpNxs4LZ_Ugk8v_lN4?7w(?^Je6 zOlhNwk3PiL6;OH`l-H@gnK9LR1U%W5;R4};y9vQxCSs_5+jokmG7=jN`U=!Z=2_z`mcluEwDUct>qHIp}ep{x<t-imTpPL>rZm{ICAqGQynqVX3E4_U;a8CR@P{kIXk}454=eRy4xECVDr;Aq`cP! z+l?$v-2}7?0b+ol^WT zZ>P5rxBg*X5;cnIUWb`I0v6V9ChH-8m-}jc+nc?u@ItX)~6j*Q?69ashA4HC+CLU*-w- z9(+Y8tm5TCr{QwRdh2cRVl`{1gPi*=A~h9R*Pb?P*oq7!*-IN}WttSqt<4tO@MIGg zCzY!d`cu3ie057;D|Fv|uZfNY-ge>yc-H0ItoKYVt+%YwHzs^d^5S(neMwToT8a*Z z1fcdn1UtCjIoO+81VukRUSBf6e4EE*9jnD^@th>}bqPAETml=u9^(v2mR@rn$Z&wMhIH;n){!Vcv z)vqWkVK6qrFdmC+zDgmn>r8Ia^2JkMRk!=mL$wPH&r1f6U1n=hCSrh)i4S#X14Ci( z2SuMYulVE`@2yDN$Qe%1ZC44MdU>E>6-xZ!Q3dg8thtZ7lg>O49!nV&P4Hw6GCdE8UfcWNoA%Pa2sbA7F3I zLLl3v5DE4QL*e(IBqK>c-IJJ@XQHBml;jGIwCq+iF9ghs3B(3Ar18w9a@Obb*A@7C zbxrJ{te5ru(5LN=8$-MCx>HuTC3FK!DE&c6EsRAmiHOhKSJMWt@!%@?xmHM)d&R@X zvAG7E`-UGT6Rp1L6R4Oqmgp5HfXKM3~0xJhQ2We z?YJhXMp9Tx1y;F+K$!8=0L*X(KLZVyMPg%Q0$0 zEwU`UinOzw-RR~Len?mdkjX=kA#bF#%QH2nV{AKKe^S!a;%LryZF3#ioJ*ki-6JC1 z;8sO_{a`O9<;iAN8=FTyK@q0cC}Nr6An=5AC(FBpB=g(x0z`9(sVxd}MIVE)oDe#p z=F;_9tH#91J*HWd;!mI97qa~q&(_f1Cqi*{--#&z-nDh1V>6JeH>Gih(bEgCY@F6Rqk2|Q4&wWChOY*y>$$Q54+A3d9EJU{jMN0}6iuN=CcA{yR zV)S|=LHX`or`pUO0PdZfP|DY@dpCb(dG{%+lhd(%43{PI#<<3=ey2wtzT>f1uk#z% z3Bgj;$43Uh-Efm~5K~;+SkX@a3F}JMEwI5u#}vJpWv$4c=e@?-;whiOL-sZ+631x0&KyffS$# z2By@3zJAhOOxGY#$_=<1dR3*!V;qDRVq};S8_%`^tXY}pL1YrqvmGmm1D(^a&cdG& z&{S@3$`cEmnz%F@4W|tb=zJ^*hv>JWz1|9Gj7XJ7LYoDviWq&o$%Z{Ys)J<2ni|hI zb;IH!+yHRJgkNW6ZMG6ZB7Lnk!^J4zg(oH^cxtE}H=>d1CHX56%%vuhn}E-stxq`v z&s~b>`=yb=ruzWD3|`KFJs803GG6rO3qoJJ<|t3j>%dKW`5o5yn^VQ2e+|mR&&~Dk z6@7mDXl?G)D!g2LshO*-==YP$ao)u40i1A``XM;EVzPUn75Zxy#WB{pmKR_O7yoCH zeo0gzhIMZ>pMv;jD83$9?HsUD7Qivp*549{+4V1DW*lq&TiDRfzT|xB7`Ix#azLV+ z8~4E>ht=XeHa2I!r|#c29@v25UA@x0OQgCO*8VP|iO&+=nhNcPfp%xM;Rwlq(^Krb zjWQh$oEnOUthSu!GAf7L+R|Yty?b18xJt-|w1y>Jr0V@uxG@QPy@swzn&4ss+qamO zu4|ksY@f8WGasSv#+ixs{?shmql*KUYsGr0+aLD41n2fvgBiY<`$u^Ykqgh#1=9?k zYnf?S4hq+X;OM?GvpJmU>;>cibhNilt%wCuQ@PB-FSE(x&1KZ0od=a`%(;v+N0SFH zo_xG`Dz6tJCutB_Y*+JYQ78DRpEt$9Jge6U;Z=SzfI2I5fYMfLng@bIy0lDfBZ)Co zyxMoxw|XESVNdUI7^642Jmj+W-l0v#eXhfB)9@r|`!K<5J1%u}L7^s94 zeTZo%+6aBo-@>?DLVwL&N)T^E_@=s z`q>*ErL+;7M}U!R*Mq}B%{MeNotjci0fjeg8S0Y!C=9(ltI5AI<4~OZnmVB}{W+Mz z5*Om+Hckdd5MN&yt#J%&W$JYd-a4VcyO#U4VvR356aIqO8L<(J-6))T6~Q;eujGlX zBq2`fpytgqfQxHXp2*;n;K2>To3d2Ogke>Zk;9DJ;rNV?6MN^?P3H&k9Bawdi(CYD z{RjI@m@YJ3jgN7C>!QW(w?Uko^`Qiv;xK#!gbUO= z631z?U8*@s7lIlNlKGqkVo&?Egy_9@Z8Q-7zVynMbY-nIue$vDt(d#$h3ZUJHGN=3zLb7k7C{YH~=(D9YtB8*Y z(-?J~37w~;uN92G@9k!?!kjDg!V60fl?;*~f#(;JHO?+ideBeB6tRCY?pp*K(!5co z4G zeQEwfm@jtZuDxPE*GSNM_HM&(R!YWXCP2YQ@Bv3P@km+1l1w?r&$Z7%i^u@lLUUY4 zX{SWiz8390)gL>amta-9R4Jf8cdymjf`_%44h`>^-e5#No4=`jD0s`<9RJ77&MzR- z$n5B;s?d4lXA;WqJIveCIPxp0EX!^(t`%2iCSkR8DR>h^CeU# zpVKs6!If5H!hVSYVsbxA`P`Y%%Y=8m8XCyavZixb^}jJVz5yzFnZFDpB&kQuR`A&A zA{)x={(jjnaGuB@7+garqu0Ru0Zjtg9#Wgnczh}!A;r=v?>!H}-M4RH$nJ1h4xogW z+!#*^eV3*~I1HGu7hQ^}2sWhrN^%k9A`22bjsF8phc0WO2$t{NL4R8zXK5wJjIi*- zcurvL;bi$J#S?&?aQKA#8O}e&0Bc)#=2lf&R7C71{H(b3*B~49FL+F5eb!E{uGUtd z!%~k<@24Yn1{GynYtG?$XzwloIDCww-qr@^Rh3dj?&(|ENl_a*?Q&O}uUGkf+1e?f7{=K0X?r!ET&nPh<$j$%>^1!*+}yS zP*a<~M!cwgS!LO%O0L=JGi9wmV)0oCXSe%q$ItKpjHIAL5pyD>?m0CAH`WP!EI-U# zBR;c;R!x6Z+d;Nv81cp7iB4bY5LYr6&-~%BKVO2FGrT2-_~O#cxP6>8d^TG>bAV$IS1c0nsBIp}YEfN^p1i zI-WGy`XNdH@els?Qg8N+k;>PGmHw!W5bWzDHb3~`IWP(O`y5G)c{B15BQ*P5Ij(rl z!`BHb&Cli+<(xv+{_Db>D~>XH!!w){GBk!~Kn<=#^gEg&q+i+-Y&-(U)N9{U$Bhxx zc8Q|n(#r|hzw4{R_V=I81+yV8t(R?n<8O>Rzclx8R5YtjJ84gROs4a)L+#Bwx{EHU ztGl}|5go)&@4@#ySOkD*YA>DOc7>9|4=Z7bubdX631r z8Nt?e_&KZODFNvK4gGzt9PksUHy7q^coKQ9z+MxM;z@;hHF2}lwkBk(By~%C3n08) zkDrwrZg^g%S_H{`T?2kKY~tdg=(4P;K{Cu~SkdZx4w&#Mga}Ltt)hLk;rT{T4|NrmIN!)il_Fz~v^7 zT3<3`81HnR@?H#fztz+;5p_pz&Wr$WwY@PJwjOm~RPWG~LKC~A`nhBX9u@eD3RB=x zBxP%v4MWa1Kf~DA%~4`;`YY?H< zoKMZBa#VnbFWd9*Y%X8N@Yp0Ac(s?Q7sQ$KM+h;mkI+5zUJ1Q=V(mom&jit>f;8K0 z$<`b}T*BwN>X%vju$l-En&jxFM{yu*ruGdc`ydOlW6uP?*O5xc$VtZccM32jSi0yY zmn$829s{LO$_a$a)M06LqhHjrJLkDwuJ=sXk1aR8ztfd9*EE$Z%cpu7ZN>L6J!$v> z&b?963;x!++aI<~Lb$r1PVtk$!weLWPg5;MG**AQ$MnJFi&PckfB>H4Q7JWX-Qu6m)P& zq_N1CO=aCZ%QZNz0rA|Jl;%f}=;4^!d$(8m-)&=iqY`JSo&~JHe3vBt(seunYL0q` z4a2I+2;Pl;s~N`8In;SkNR%HZ$~L=IJ4DMz;+~U2q0JIv+{&O_B%;w=0zI5z)fsRT z{LX)p#*}nCmj#nZ#qR>}D;K?;eva9OMc!Q$`Bt53g@U-50rE^oO=kXjMzuxSx>ggl z#{Dy6X^(fX2a~nhAr!uj=AyO-s7B}gbQL5xAGR>(FKg7lFcY-VJ>Z>cOC`tMyYOmZ zdOC;oeRjF#QPLDg6NYa)mGxhnnTU5U4Gb_+$b4FV_T}s@BFyOHAAWrdKnzG|>kiF8 z1}JW37B|jb4e2Cbs0iH|-BcDfJ;gnapK3X$LB4_2M4uw7+?69k2xB|L;rvCWV?0cLy&g%x=!&3?=bTkdG#Y(%&$V9;{GCX4sG(vNEsQZ1j4y!q}tNl5g!hVS~g14Kt-iO~Wlr`jCRl2c;yFUt2uGq#~mv`??|0 zhJ$RLV}@aiL6+TpQbilD1~!cs2glwxPqtzH3jMvGlf0^V{cI&+R+*(7G8oA#Zkcsc zneDIl_3OA6Ekkh@^IH#F!!-kCOPKI(F+9tf5p$ICUrjgqbPT+YT>zNLO>6=QK%;)2 zI^plViLlRqJ_C~h-4L4Abq%5Tt__BnKZW;hJ(`X{a(y=yKSgV}k?|HVui|$@crvdf z8U4=R)DVPe@dk1a2fXmu)W0B+-0GlKZZl>b0l1!;tM51uBHO5+;>Q*gLR8-hFaODp zJfN%5GT8;aMWjj*{Fx?uNx)1qU{2(;wDJu1Q+7f4fY7!~LwwYd9l1)>$AHBIuy}^I zx<(@sx^d*3xVakO=ltdPpCbZ=lcLzBJ!7(^B>L7UQNpIv`9yV#G@ z8`{cWZoDLvXRpu%+tlHQFfJ~#MQ$>SeVV*@ohV&HQSK;yjLlkv{?i{pJi0R$@L^OsDHyd z0J?fpf@~&?z)q(j+)YqsB|0@)JN{5m{p&sT=n)=v)j=o2Y`cO-W2;%F+L=pvL4JYy zN*&Klt$!e=9o2Afig8=m&t(PSi;*Dor2m`| z<9pKB`KtqBrZT5d&YBR+QD8MQDd@F>(XVBx^NjRXt%a4&^_^D*H}|mY1fxmG2+iX8 zgIQ#s=Rz%aM7#~gfcvpdc_PV3Gua9%8BxW0`^#VjhxPb9_$}>sSxjP0BAcSOP+z`N z==Fn97S$4?&6K}Qexg_?o-yjP=nJ?CgFDj`?W5JFtg5B-!g{5mIG9ZOoE03cCMbpY z)OA-jZg&=^v^Y_ka|6fjPqou~m^p#=uX^Fd=e)HX&3m~-OKiDT*Z*3=Nr$btd_L zOcu&+0>AME7T)VeV;Qi!5Nk1IWqgWxNf@PqnVV6{NM^LC(#`rb0#NN{*PpFc_GE{{-i zD*yEQ>&X#kCtlgtR8s3cm@^ih_dSe3>yTU|#rDnILm`B_f-wpW0b{%w z=GC%M%1XfFWpV7UVGBH;tCYwZD>5`RZ@?qidDD$&YN`)OL-}bI0{au8--^?gs)T3f z^;Lz+1KEcTz^ZpONUCTQ-ZX4^>op_3kW9>-V#j6zI>)Y@YRvjQhqqTbtY67@oAnTA z5Fm;u*dU2Erw{Fel1S>sR=bzJNC@ti$TmmZ=^YLTdh6@YN+Y^_L z6-OwoQcg0QG>3-XXjK>2e=WxA>o25&*M(k3w*k>57{RRfWR*bL04Z2R{MDjhF4dPI zU#wF7t%L<`P8y~#R;D=aEg<406iIpBkFF1H3X-0NYu)(F3u>q>QjgA<@TVqOc}a*m zwYv`-?*d^T9s!8A=doa`e2$0!JeY)WTRV&5z1~6bmT+E;GDjkXnJ| z@1{v-L01>(4-m({y+p?a6z$**=VyIeP&}WyiwW&G9dyFMjnT`!O={e?T20RtR$j!l zQj5}SIk{W-pemRqXVSKx#)r@KK5r5(|wZk1ng(s z&7Xl!(A8~EX&!RG4l-e(TM6_s~K#0kzi5lDYAGiluAtXBIh`ZW9bCoMIAFI3r ztx`_MY)~|-OB1O#j!MIO3jrhHZs`{`WU=^FrWu9FEv;>ON#2WX5)wRNEV-wOXmi#7 zkOH-@dS=EwfEK#pU#iNg;?9pDwqa95sBcgR9-Dt|HJIfQ;0#3w?d|_@S@#*ZafFjA z6RKFptIZe-Fdq%auyMr1V9vAo*`7NuLs7(-4{2a4yz>Cgn?nc>si~u0?R2OFj^vNN z%_Y7#Un$w+ERYy#2?%rjcj|wyxUNx*QR{+=E$@6(FzV>T6mDp6=Gqy?R;>*GZ`F2xPf9{Prd98%omq0^brtunQMNh+uN$+ zp4w>W((bAGZ*^Q6bQzXfeb(1E^=+qq+{v^}0=2h<{8%Pb)Y4J38JK=EUUJWbByU03 zQvb>3{_}Uyj&~{ACr{PdT90APVgg;21?7RFw?(;A?y@LA9%kN_&l7p&OlG=zc$S}fwium{^8%M)`?4kr>L7#QPCJRX zXFudOLmY2u=H7&<;xDpI5rlJg>o6v3dRx1=PHcbg-=;s}(5=im$uM+x1cEdIm(SVK z5Q##)yDJ;n#;99&F zpJq;FQ)!|cxaQ_hsO^Jo&ld`AG9C)97X-oIatR<(O3DFvpF;6FB8LW^K$T>i z!3Z%NS;VZT_a+be9>a2kyx~`6#lG)-#%)!tz|Rz8$qFD(6qD+z`32ob2E$xRPQnTf zo&*0dMgfUVB=I~-nZ&cB7+=c!32frgUyDh_aT5x?|GNKbreOF^qQv{}g<=y_@eNhA z34MjYSiU>~C5bJy$Nu1I%4}wccRYVvo1@Yi91WqdzN2jsFSuJ4Y;)?M3IEr-zQlFe zBTPC%H?ld{_%SjqWVpu{b9XrFpY$vmo?1K2r6w%3pEAeFr!!Xg=lbnSQz2~;*6@O! zR1`PDZks^LWOz>sK4SNBLrU(7wfSH5uMS2>uHS!4sFn@Xhn!NDRN1PR8`GqdSccsy zpXYGnNqZZNjbt2|W#}|e#d}mw89H^V9Mmx@)8dp?k~~Lh!$f+u9JOtgS`C$t)~mF8h^1 z+$me7{dFZ&E7d8#vND{Vob+y;(J;)MTVj~E-s5QYlGL&cz^wQ{5_DiZjj;IAF3~h4A5NiIp6amypq*(lKGu^qKxenbGh9zkI1`Q9&`!JM z6o}Rc&?Z>${oadcUDvnC9dWuhHS~5Lsz|iH4dbb@PNATOw0nMQJ$})CPA4O9n+iYw zllvSgIJ@^Zz;^REQ{v~k-Lqa+H)jkv0b9OZxQ zgq_<#H_*CVoc0Ki5Dr-5ru#nZz-5GR1KPc@Km|%Mbe43x)>{oU{Sal-gHzh*dr9%D zo|@UlplBUH#O-Ms^H&m?>OYOnRkfpbl4aSrnYuA)hK|kEV~gxSrj8!ox>cI(Qbke` zid=nv81`AK#I{qqJY)7{eiYbz`1}L<)?J-wD^Wj};{~5li#vCd6RN2BY>VGP*oLs; zN5!SZRlb2nKX0yg{+MPWcW*DRM8^XcCoy?|5r9}zw8GmJIDZ{DsMBun4Qd;E!57*k zCQ~J7ci8aVN2;aR$@_^is361r<7*Dk3E6^onOkgTglv6BQuEyJM#@Sp%z=vXjqS@P z?Y&ebze-zsK5%QSyY^;i zzWTEC$x%Wr`c#BxN^}CG zTvFwW)0fTB>z5X8JBL(tz42*8ruNi;Apg>ZS$S_9j!9Mn86E-q|8f=5_JpL`zl^PC zTF=~8hQBWsWi30^(8e7A zfQF%c8$u)7ZV`tl!l6Nz^qVQg9^J@-x!F^2(Xm}S1a&Q8)hrtz9*`7mkH6$VLB=KW9T9bRRc}+WP3suUp9pmFxa?lamiWCNt%0z3- zI9>y1;|DIATYskOrJm-rZPI!bTBFmgXhY&h70nuLQTuxz>xsj702}MY_VB(;kJ(uo z%WEzd-)#Wg+>lEZ=#0SWvZUN`{Ai#1xz0b`6oV8M(rJfCs~)TIY20!Wj$m@nxjtE^ zX#c0Di46xCQtU5*VEauSd@wEZKC47g zg0!ykT)a}o-Wug(zoH5u6|o@slS@FljYB`JuM9lYl)DV^-R~g!BIH??*HsR#JQCL> z^$syj6zgNwX4SLCLO)Kx@-tHUql=5^>BpOC1#eDMJ&zp5xAi?QT@*sVd_bcBeu##5 zcPeb%v>^Vq%SvcpK-#b7OUoqJ@y#F7kn55YB;1~X{F_RzqbxQF#P{d1P|5WJD5BR@ zAz5Fn|L`dE146{|%}_h+VPs)qMv^1s%M?-_-nQvc>{eh^_`#XPxM3RF&I>y%dX6!NT@_AI6(>7&wadYk++5 zp98>iF*yLEWz>~}hPv`>KKAgLhymtPx+)*^gF@0Y2*ci<2N_Kr&im>DqB}!Abaj8E zG@-lqh8FoCyli6eWk28Hn9p?`J|)v`c-io}s^dl4?ZQbM2adVglxtx6l}poi?>nsq>l^@vmSe-9 z#tX?o`5*qso?&~ew9pO=`$q+~C%)WlqG2LCR{MBrEOT5GY%bjL*_dkj4V_g^n>~kh+C%C@ ziAm1-poMxfrYLt@at#Hp(YIS=un9foR3~%~-xXB!<=1jkRv{O`7s7~Ztwj@r`54rEJOK_F6p~{!nNUUYI&h`207SBSj&qcp+bp2<%bXrpr z7ASGfl43r9Mu(rQ$Y5QY)D|7W%hURVFb!w$^4b;r80M{KjD4&L>N>x=e?KqDy1qp;*Wc5^9Xj;*@5CSj7SI z&11>4x`UNNJ!JhgcNXu93vg30XTpHdkHcH)`T<5P`Ji|HL=X-BFk0Sg6lKU2Ol@Ui~9uBGPP5KRG@&tu>A> zz?qs#*3G9FBvdTr9@GyQxI+_arf$b?cTIjVQDn<$0LMyGvZ9pMGh!SUyAifT6K@&4&-l$nt^#O0X<#>aM4F z;&^TK;69oP@XY}b1iKoV*5O`V-!46?>og34?)jU?JUN*PrWSO-oaV=k_)EM<&9{%+Hg^cc6(b+0F|Qa20Wh6+Q5Ve#1)^W1q_AoL81QJqe|DW>m-;1HEi+{+4Ky` zvDf1#6H5es90@G6(LVspLrkYW;U94o0Uk=s4_9JX0HOYM@+k($=Vs6GhsZsla*Gx?PK&|t2{vH#&mzPlAzf8n$!*?UFwR}{_0oWBcl zu|Mt3Gn*_&O_)7y#4Q23D{*mE{z>v}fcVm6S+WCi@lQeeLSC)SmFo}NQw0k*1+KC6 z_a?5!j8|Z7JMkHpt^zg)X*(z2Pd6do*HAIY%?+;1{DN_e_1D9~b>Ee$^{H*&ofdjAVsZH`X zt$Av_eTdTvln7<^m{Xg zo-7-3NV!nrhxE%1?pDCXhFX&D(jHZj{z*452lK(<=McVKt(fOJDsQ55OPUvAYWBG< z7w7XbmNNzJB_N%I(vD6Gr2Q8t#_lY_(TbYJb4Mq~0=Wo6pLbE1rM~1+is&4MXDrD?o}~qzD9ewQblwT=O1YO*b6}#IxR9@%bgX?a!L3|Rhzkpw?4$? z*3KBw-e|b`(r@XW;-E>#|A&z!L+qPrAVjEs!+K<4gz*;|&iRN~UD2nU_87EV-~GH; z;n|HHx2X+$5(a2Qa_nMGwwm0VxEn_YmM|s?()=9^~)) zv!0m2qRjGM( zXwuK#=VmHkBJD_fpnbwaAl3#`WyGJSHnvu6glhkMvsFD$)czciJf>njw#Z-;3GM zzYI{m323V^P~&6|$robB_(tG6#*=NT|NGKh+p*(op{~e@O0rYA0p6T+=l5XbxE`rY8h$xIq~1 z!_zlvuHKCN593s#a(ykruG)tyfv8O&bJ0(CSGW|r_M7j1Nk9K*%HJ>Mmosn2CGGC* z&)T~|PthMM0z`Tj$h;~Q^9{uQT*u4fGVqQmkl)_l1E_gt3#eN6n5o`iH`v|!Qq@v# zJjJD;gIMI68_rGW7A!9cD6fVoB$%0>e^`oLijv!ZR&p69;$`kDD$&mrT(HNH{2xYo zdi7PZ$bT3eM!(UIk3%4&I%py5TK0^IdbbN;15(dA7SsE5N#x$#Xq4eH+>qa^0qx~B+!vw+{PpAQ@=~ce3N3`GRjdNjGb`=5=%hhVn!)Hpdixpz5)$}o7Q6QB zaKmG)7>|!{ZowdgU>q}Y$j_s{e*I4JUJQ5?aUf-4-g1oXkpxXUc~t(I0d|oqF^>iE z`L#J4i=K7Bs{sH-7l(KMdpOHKh%|mfH`(%0M;EOjx3|V#V6Flr!tun_Q*CrocW0h; zbm%xIQ8K){={PRZT_wP_MVSQN*MR0pNnTeIunl}Zv)y>=&!FBw2 z`cLO}*V1}n%+_p8L!RU`VP}ph=O-3tIPzj9VO(x)wn;woKi*LF z(>-H3Ty|4$X#U+kqa@Kg7w78hhCaN2-jIj(>1cK%v?f;;mIGg1DEW^^4f9^Hn ztW+N|R!&uHs_GL)6rN`>LD}|{3TZ4Ce+_Jz?)-XmNy5XG6FvN7^;>cL)7FdGAH!nS z$KM{nTLC7;^Yf&=1S20YI*NA+FAAJe5VplTrCb*uc~6gj^x~H`eH9+YIuO@BE%SH~ zeo#^_)KU>hpu+v@C}duUuQ-+4bz?}K@d*->QZF4IT3SCfZ!0~e7-Y2HZK^0|u*aU8sH#tU+|zL^7qm9w6}?Me7lK4IjkSwTNKjZ#RzoGW z{7c6h%F*0lU9yL1$I~1@C(5WKrFfy5mlhD4VT=mO^$w&WILfv#Ar}}9;Ec>NK7;gR zBt82jER6GmuajF~@lGe~53=_a0tAm2&d0bG;%R zp&PKe*IwW=eL?xIFE$ghr8Oae`PbVOOHg?D?TG->nCm>+S2y8tI{iZ58e~S4>Jlp{ z26yaKd4f>Zu233wyMzOfrX7&q(Ud+%+QAxqG1J=8M)Jqe=iUB;(eb*0YmcSTxx>83 z9X<64-3D8k7M@buYZea z<|VhD|E_IN$3_xgie_`9e;vDPZPBjjcQ*A|5L;mZFWB^{@13SPJ}(oxag2Zsj|TTS z>q=-q*C2OJZy3&QzdhDRJNgZL%)?PW=Qya_omTkUyuXy=h2-oeuS;n0`k*3efi>*% z{x6?jk^QitNpVY9`4caHJa?B)3)Q)puVmIiJq6QA9Bp$TO!SVBgc z2CHX7GS7$o^b<6uXMcP|=5%$&;3v@89B=;BV+zF*UWz)~17)_eYP{5f zS@T&5Le9wp$M9rl?7y%^FRcf5r~0 zoRv_L$T2E*#T+N!Zm%VZCheBO7dIGsn#A@@0dV8|>(taJ-hT*GIg`40+bLhi5k_SX zgUC%GRa(`r#wiczIh!GgB#V?;=8@;CFAv;o)AMflp^3ZXi>SzB|95L<#Gj#*JVcAMU?@?L8wO4N5EU)kt{l(c8dCd!c9J zFq(452v$kvC>q$Va0Za#dCP13cKnA-C5m9aq=Ah#6@>E7skaQYce)5jmGN1Unsq-xgR2K(u;gK6n||uot7IRL_wj`;I$iRoIr2)oq;I_GK`pSZWx_+F zYJT-?cJKWL%5*R)L!81eOr z6V&G#f(mw!5bc`~GBWh3NBt2lXo254#u!tntmJb$joj!WbX^u?Sd+qf<%E9p!D@#| zAg$?9U0`B=s*OWpm)wIdiYI@F2<~P=^7Y%@a9!2tcUr92ZCBC{A%`dYnl|UHZ!PT; zpP#=ToA^gv0Vg}6{QGnl)uf$P^Q%GAYJio=oowJO?bw(@94pgxFMi_aD*V@+P&5rzr^3E#KB^e|6xc>Ez2$QoewHJ zQXWcR-G4xReY3E@=$b28?%COsrys`AMR+Y->)&8u? z$}$ltRl>UM@S=LFcwCtS9F;o01D|{RCH2Bz3*~nP?(%$O26WtZ4)O~-uiw-VCFcH% z?eU^3t%UE=0G<)k-XmXLfYrUk2D2voukB^0OPp7!>CA~0LqE} z$tvX~ds$0N^Mt&}Q}(%E*LN3A>d6UU9b zvKfGcs8d6ecwHMkR9p&Io{a~=J{{8hJjsngBMlqk2gLcf#(dCjsNQ=ANGH6V?vd`m zsXTC8_v}zOQ6L53SQsW2j}WWKH65epV2;$6Btrss9#hA6kHYMB^FYkvUk6M-d z)wXI3^>1rVPV%;*!sNn>ZY$k9vTXdNppg@h>+_@wK8HX$?>GJ3?Z^n5N1D1igiJ?u z9kw7=?2y7=^fP~tdw1YkMAF~Di&$#SQ%(}E2~y$Q2AspVL&GgsZ;#ms5|za0WTYDJ zS$i`9e?`#ctq_>Zw$$dSqKOi{$ZIWEr3FF^+S%@`x->Ke5G)|_kV1b7aKRxnbYPu& zhb*&6X8ys37x8Yy>apROWjN)coGqM1#eI(xOljPQx0-d4l8wjsCoYz!;p^)1b~nRL zmhIkY56y@nlYJE89>DcGo3d)!j}R_C8=x>3A`+XI&BV0)@~j^_IrKjyATZW8CA`Ql z;*J13rB+Sqaf%< zIvG7R0zC4ur9rWv@tgg3CE}7`Qmmla%r3x7w3aE2bWuBIy=SqD%13{w{L$k}-ZS5- z5JMtEL&fo)G$AOiUo1b&C$Z!q@AbfJ)1v=P)1Hl7l;h_DKl+1up!pS=n$|Hn2#Ro=-mYks0RZ?b-{cGS*x z?1)>n>-LJA<4o_jJb=TdtEaRl=F6)n6x)n2%lu79s)4#c z$nM$QAyA=bN$aOw58|q7eI|^-eQe3qgU(diGE_`;li1j5l0ooM5Q@zSO-p+J(i>m3 z9qAZj2a5Jk+~A9nlyYNY{$(10-$Q{xs35^hOWL0zj>u-EeRmB5FD(~3G+sy5l`gy+ z&Q*BDkuQ-6uNp2DkJ0zz6kB{;HRyj_b=rc6OOXRXfkb`jd&t>viPsP>U$9fc3#JOG zl$-G*z%YV+9=HOgzrvTMSh7ZVfB4M&&G`Mfd#p_3TG7gLAa3b?w(+q8Ko~%Cn;q@c z<+WKqv#NxX*7vUPs~l=o#6Be&ZUrSJGe8OFI;FEt6pmK!O#{b4wG^RdXP{2CpTg8o zY$j=|paJh7T5JtW%6(uHY39AM(<-DIB828o)UsrJ9u%!7XF_&tu~FIgTxbdqp~vZhfYuq;P){+<>U?e)17_Dr zV87_~T{;>l7lNB0oh;H$peP5A4LA4T={VT zV$+UdEj-%4SGT4R7wI9w(pwTl{zBjXG|?yhS4xFFNvL=uZG>ia0NzQ-<8WF#sahlt z+OTNRx=-dfuS_P`Z77UnmvX<~w@ZknAX|e#Ds@_t$8O(o|6Se?@AFF%epUBd;t%wojJFBp^QOJtv#-q0Q1=>q>T zlSjlVK*1doAlqiYJQTJ)9bIn@sT(nfT2hFr3<{gWU`SNF=~M7M`47V~3&rvu#?g;^ z*8Pe_eW%Cpl#j0i(yBF zl<)3m;QsYMONsm3bD7g*lnK!^J!)uKJ|^y?YD6z&DH=J^EoVH$>#K%#)QOsKj}wkW z)FPHj49Xk7<#ky$#}rVzToXod~VUv zL0?#emSREy+OlW*sLC@}8%AXBfpzNolKcSKm{#g~p08?2{)FmAv?7EB!?-l+z@!AY)M0=Ii zl)Fobm9bDAOc6K%Y*Nc^8WiHJUB(Q9*lWcBzCT}n=T|h&XbPITyNg7z_B~29PMugx zU%_P=a%|3MCes~<1w2j|3(Y8(W3^uwZAQ)v|Z6C(JEF;@Nxk(pJzLVpu z>;661M}yGTuV_1=-N#;rl_iIr@Hl4)>de`lwClHg9Jo3uxj<$;kxT8Yqf%R@L=Tf- zuVi_rbgbl3ywr4z^}1obT|B~+UJqo2S)DM>l0L{}!Levjxwb1PKAG%Pw<_5#85tvb z;l}iHy3m4Ylj`y6ot?u1BMu|g^5n1Hl$QJ$MaJwrABz_j#O_ilT%4|jcJ>aIuz&#` zhaFtQ(XM#UwTtv@E9NOz{(!&c(mlR9Woi86-5^9Ka*J88d3@F zy|bESkn`yZg_+h7I1$CG`^WG-|JN$>lf{P3ii(km{AvhEn=NbxvVPj_QsK!BZ3YR* zhxC?2zD~aApxfD8HvKH?4BM@cXmcAN3)9xw9Z#f)^&hqId>l6I9kC4eD%*EL0jQ3R z)W(hj?k^3u*M}VhoyAXHzs`vD?$*S04fGa6S8FiXJ1F8b4itJ{keB>3l8?m#tskbV z*M}0s2b`f0xbYUaX@`-{93ZchP^?ULzhY~4zU_%X*VR}X;^gR5I=)fHmuovOf)J6E z$#LwIKzw{b(ub%Wa}$T}ufE7j+Hywa&FKYQj!HCqW9T80NGb8+7jW#6ek^%SKK{3L zX27xFnNkN}*vIYv!@xPn3R7|I?VFMfI@NKH;vZwSj>Aen3K27J9M!Q)-9t>88S2T5 zk4{~fgs$O}MS|)`#|!MjE2D=2M+)u5zuA0m&$)$pCOd3b93x#xoksnO+mMACzXLBR zycm-`pAyW|AB%5VSJ!hmDW{4hFgSbA1dhl2^~vJ1EokAIB;p!p_tVVU^-VFYW7HD* zUaV-zI8N^$nZgqiQA&_<@tKH;F;Dkcf~f=)GYe)gN!2#=T(xCODEHxFgpX$r={1eI&hnRI42td+ior90=r7VZO8@u9udqkH zNa5lH{V@3tV*{q=ZP%G5o>8(p#K0$6VYhYbq1!m+q4sKp&Hfc}-T)z-f>k2 zlx<*4cZ1ImIpNv9@Y*l`*VJdMA=YL+(mQYP;iD3;&JdES317?NnN^c3oHD1)I$=r?g; zesX`6kEiC;mH8lV6ml%H*z9(!hDS(lK@0t%z8KC&@Gn?&EB%-J@UZM^Fm9P+n&!8W zD?!1&xM4hSyzfR^$V2?8=ZXaOCdPdL=WdKBDJ9El&{X>M>Acid{|1;jhtd)Hz!^mX zSCjWIB-7LwwwRnR2+*X|VI6{+(zKaF$pyg=+DZW!wFJI+j0KKk??Qr%idscUFn!l(H{hG@`Dka zOB3Yq4XY@&t%^NPuI%^*8>arEj*U7NpI2N3bFSi>3EC-cHIF>rsLPa=|?4S>kcO=~I+s?}$@Vq14`Rr0#G~12I+5nH~;RnG#jdtAMP=B1h zw@G>9^eK{Xed*=f>RbDf)uU@en>x!EvEEFhM}oJRetX{|jf0l$V& zhFoJ)RX<}prSZTI?;;C3aH@^I9ly}KRN0Olh2ty=DpbCNarQJxwK}p+oS4P)4dA-E zfTe$Se|4^^^*&Eyo65Vc|4lq$EMoy(!<_b=40(kW;rhH^d6FhCT7kI@$JQ%3vdp6H znc^7VzZt%at=ieEW^|BJGmCEh6s)>pI2cDp`h&{#fNask~L@zG?IB*ofle_R9v%U{iD6BPEymGwE39g80jEWeHF(+*nu z5&7``AsVt)pGDyBR5%YP$$m7ba_Y)d3YU!D|8Bw4!YvP z;6Dsw&$knDs}ko+$FW~NxrV+~rxhJF+1n(o@o z|I0dHs0U=z$u7|3KCQKp_~0Zk_!{A88EsU~zZ7^@PXeGOq9>epDn%zShtt=*M*WR6 zMT4NBs**~QED4Tx*S_!zLw6ewn=An-n*1=h1b|_E6RX>Tc`LOp8W!C5!hoN8D0+E< zKxBc0hZ;bWK@kGKT>NEdWB5xsIKXYC#G7ax)FT}so@3pHi)?+&cH<0HJYM5T0?*C% z!%?hOM}_zDi!@FV?Rb~N$c`V(J+2ZzSj7l{a1gbr^kyV5*yTTrd#1oq;k~TqQusF1 z?t6=&a}nt>F0uHeabOsShpqBKzNB{BJi9yX6%Va3WNd0i%$pKj!E?=HMa_vn25HNa%dFvfxOc&< z5da<8+rJ*Al2jqW+sY>-fYiAD1>7&e-4m`1|0PEE0eXRY84& zt7W5QkPi=`OB%%dOFgpVv*w5w-?vEqKQ1Mhqm3R9kK>E-(4buYejYeL%s)rPxNZ7LKlQ;VKs2^pdrto!8`Sp@({6Drg&RoW z&wxlg$4Z$xQP2AYH817EnvLDMH@EdjF>vVPDyXyRm9*cuO}SoNb_uxRXr*;@z>zb9 z;WU@#+{&4#!lktC1UlN+VgVlX6iw#0sT-P8^HA1C5RmlwRmsfVB-yx~{zZ)_uabXg@zSxO1bzh%emR z7FDd1;kAu|YTolHpR2bn>?GOQEer;HaKUVRCu@bQijTymzXj*7=aSA!(d{F zH2|}DZ)&BfpM9=$3vhWoD4>#%2_^gmPwaPraBYUgv@B;#J2@n&p_MXqSR<-i+#7k_ z1E7#}gZAcc7f$~k$RGZ;uT`WAC0Ffd5xh0HN?A70$NTBM_EH&}At7@~w?~=^$gqx! zkS5M_Ka-AOemRh@nv%)*$)gj0_U!UW3x)PsAgtuo!@e9V>)&3pWxc=)<|@O)ewcqB z4{xuz9s6{#*Q1jY(>*8i+{Npp085iu8ZoWRyXHki&MlKIDy{e5;SG^nHD;`e7fTgm z#*M$S7JE@%eY!+Xr3Xl4rc@-eT{;z;hN_&~avEM<*ox;IO%fYg@N3BR=B<37=0_Lg zxsuBOt=4;ei>{DPhGQl|0=_}4uZE^KOjjkI$wsNeS8{CgrLSJ>%@H^&Vf_`d69TjTER9ZM!7a6D^Kj@2T{~0SU56itgU+w-^FHRm73Px z4wJ`p{5f7xz-ji|fcY*x%rh7SEe8lG7>BFLL_m{gMfNLrz+eyYZT_BhQoeu+6^<6>z^D9!N=llxI z(ck&>jotKHi9lJ#%8?c0REuJGqGKGe5#dtaXM>CjuyF}-qmPP_pM6Yz-IPPLrlCuM z|2D1f|I(+_&?F}&{VUO0R>%QXwn0OXV}@xG*8XJG)i0@W-q`2j#HcA^Td$<*K&1b? z*f@Dg>A_uOGuyWTR)WrrT4%SEBn1a*lH^MlIneZ+C}IcHOi^yrLsqa zMf}6QK&GVKAy4cAI$=-MQU1p4f}U@s&8rQOld6+&Gz*!91rTC?j($5nbx!*(KczRn zw3%=AbG;q2hOB9Bz4DljFhbCNTLI=|)H5JGjd?`C6iB10{AA_*$%3<-uSPOW>!l>M z_A*&=bkWHhHkstGe%tiL;RS8zE~Svpe;A*e5G>DKF#8VtHD9_if|UEztCo)2`9HsV zl{MHWLLxAAUC4mf{59eGxP(X1W`<8^kQ(hBA}Uegk|{prz)vR4hk+;Z zr|^b>*7QuhS{Z{ysP7$KK3r2cx%Q(M1#w@vooQ?Xoo&i;*E5bWd4*3}^`!5%b(V;H zvz-y2P!_cAFq`+|&JMCqiGSx~xIW)EyuLo`q%PQDbow-{O5LS5kg(oQr*vu{&rsUq zEu9VfR$ec9pgdU#UwaTWKEP-A>RG4QPri3&(D&_2R(DXG@{Yu_e96|rMFR{>%5uc} z@8MKYsrE_7M%tG3Qsy-JpEVMeQ1oOMU&>_%j!h1c=O7NY8?giN$a5mh`D!DU0r}@R z43@3Uok$Ljq?fE1zPjNNiMyVwcYttXt@<~+@*rLGO~t;iQPMCQrdB)z?<~emGXQLy zx}Gok_Wf?V(4I8ORc_%P%M#mdpQzAIDg$rgoyAl6{MgU$EGxSaG3~H1|F$3bAv<+d z5G3&qs1_W#G9uQhmGUA#y3DU^-^UM6mk5d$eQa< z1US1K+_SKf1qc7(-dN#HKo?D4CYw`Qr(G2u1ZJmA>QTGz*XF%y-$+Aa4dQ3aAtZDGfC10kJ#%JekBX4k@jDGu!h)>e=eHPl>Xj9rSEk;* za3;Q7jrQew@e(}%40-Uid3sJN9mB4(6{JLMsQ&zgGYon+8J8w4Z7a9>FtS;T#qeG8 zBKIRxZwH21^#L2zTg?5XFT~&Xv-*<5IRT)gUC^Up@>{b;rjEg<%pXtkzLt0VcE)k# zzz2!G=EP;K9Q}0AO~7OdG3YPfsce>e5b;ff^Gdjw!0v@i%IF0nK0zI+sP1%=Y+_Qe zhB1f-g!aHsPxC6yLR*4~Z#oW7I8$4vSti!3YL?CyN|uT0-kh6|F`qYV9;#}j-1bW9*Ctm+6*5Qc zcP@^;byG@uvxt?6sUGQmDi)22D-|*&^!#0+oAvw2bAh47(zP*N7r@)6_B5e#eK=lp zxtD~oFJnX{s9#pex~f{3s}ti~v^ZKbviY&SH1(Fc(N^MRpsR{U@wy&857%}F!!DhT zLm03u;=Wy(aCp?4YR@d|N~H8EhzQlSqv<|-y=#q3l69iOVl7bWAWq_5*&*UN_P_XXB$Wh5p+W`4L%j{lwi`c5`cHduxUugrbG?bkp+M;y#r zg=8Sqzjj|ersMI1xr4SoUqiLc=G{ss)!@f%34P?Q%*=+l5ANy|FKy%&WS#V^{`-m4 z?AoZu5K+dUy=mNMyJ@-)=;JWf?*t!&BHJis1fVb3?@hdh1@r00H4)vGLPZ}^Z%nK> z*VPv6jQVPh(!hjt>`nz!IO>|FeLUaAs1565gnh->vO?R5tMk`kW&ScH zGHA8)F)!s!oSsNRDJKl%XNtseaN*!!&@P zJ--Oh&N%VDauu6Ms~aw9;`gm-!#M=aaEVN3OZ11{#SF17SG|Fyj|1&UZ8d<% zy^ck!Bd+Mo1i8#|unlQ$`oInE$sDgwXD8dn@iVs@Q2WeOo=x?u`zwp{!hU*$EP6_P zVV12K5S!-CcJ|B5M77E*RdStv!^tZ)osB-E3JstQhw@(0YNwbk6~ooLRNMn%fVgdi zbZC;v=MA9EWyzK!SJ9t=)fl?Dd3^uts?=Xt-%7_lQmT{xKBHKDo;!a*A%T$w=yS(G zH6Sz@&suxOA1M_$DXL%$8@HE1Ac>K9j-|^D8oM;R3(!Wd0hVR)>{Tn*N)Xbmd$rm1 zm88O#=RxDlT5N|wvrBinQPJa7Xik^t#_eq+dV6tS~ij-2j(KMVYVHG)@4r>b649m$#5_ zcoSh`*!sEqecnfQ=ffL3$E;`IO@hHGf5>K3X@AP^(5kk%+~rw3QLK7IL`X9z!xGY!zl{&YuEOO^InmYJ(DN#)`vmo)b z&!DBUwvpk9K)kQcr!-wv{@?LdCEM*V|D^-1qQ<=G`+&~x9WAtiVCLIZNCr#fI!xE? zliQrH@8ptl8bK=ylb3C<3T(uyCsz{59%j^|kSg#m{qwltB{=KqT=KJCtNrJ)=W}4^ zai(js97QF<6Iq-mrCjSecy9pp+7zM(5y8)uoca9@k&w$8 zoL1UE`u6uM=kXz6_=gKe+kOrmE@iJ+A#rzTwTw4Sg}|4MS;w1uV8~!%6axNhs=7M* zBq7!%L4BAEZ*d|5I3!upj>AX04Z|3N28ySH22&ZxqDlC4N|r=0@464!L=q zZ6=rGvn$q$B+@NwAq8`cOGXZ#MF-1?j8SpLhhDJ1-ohQD0>aBfjd+s2x~eb8?LTIO z!d5NXEYoz{igPX|^!CsSo03Eys%=hcpJ}v`U9q&BYM;$Uws^VQw}`_DniA>Pg8oPB zGzIXiSr#&x8=Nim=^O66TKkT93CnOI{O}DocvkJB`af>Y)vk3mGxE(-mFDxK_K}N{ zojLEmDGxwP#+Zn7>W+~bS~CF)7=7;lZDf^|@5}PLV4*L=obmfR^IEwAn<&S%U$TrK zo=-C^8iBj`_StHb<6^K~10^pnDF~^F$AOsiNaoDK>fjvJ`McQU`IWIDmQ=eOj047vHc#n0MrU+OQdo$TMHf!p{b)fb~|-M`b1R=V8r%7$n@qe%C7M zDOf+!ry}>}6eUInGeaU_NQ6vXg|tojOGT-uP7Fr)_ za2~Dmvu}2*+D7Ge`%he<^7d(7w2=?n(v8?g?Uhif&MF?kN?S^rYnjpG5l(--kjknJ zi*GV8C5^qdSf)d@R!u|I(zcSAN^$8GeK^eKU3^FrHsG%-N$dI+-B8bHd(rFk-ch0% z0-hdQ@KyO-_}w4Umcslvo+#5G#t>jP1U^Of0~v|`0>!}rr9D-$+w2QVZbp!`KePUz2x<-@ZZVWoI-<>&nrxR7Izh+J- zZx+94W)$K&@k+NvuZcXKE2!jrvUk#KR^o78jSIy&aBoDb&{N}z% zeSN7wwGsZzd?Hj)$in*V8V^b4AB|Y^? zma^&QQlr`(`4DpRS!jBgyzA%r&jI1GicD6l#4oJMZ4wm^dP5|eb`o#$&E(liz1}<< z_;n&#Ig^X{t6zvw+5h)4FU2y|xPT9OVQ65SArpB_g2R}3HBn<9YxHr|b%eK@+LVuy z_JwwaXxprBLa?9b{;0rUJVu|;%}%`pc|k_=@+k&`-&GMb+1z{-ro)@J<*^`CR8t)} z&vel8!x$WHkMOth*;=FSuZU>r$eD9?Nk2q$+A&rA<>g_0(!i;-s4AW3U&mp~D@oLm z?ysoj12r`Z_r1z`@kTzXG0Y`ZXmOF`(2$3XRiy712)+`&E^@*cFz87=)QBy;a+R_#14C;{eIyxl&Pt|Q~6 z)Tj2@4%qT-)hLW8H;}Nz?~BMisoLq_LJD=^HqbuAMB(4Ip59FVd!F?$_yoNIOYzqJ zLU_ap^Bbl45c`0O$p(C5SG799>Y>rpq4WbO=GA~G)%uCo(d=5oMOWoiTABWBh1o(U zU7V>m(sJFJVBMC~s%iAN%tY<5q`|-a8`p2j=sf7!Eb~UdGxw;v^D%Stgns2X<@WRy zm)5{9;+FNb#f0#Dv*2w7+G&;?SbnH7Nw#6?o%G0-@NRryvM?{N(k4vtK7O5)7U`x~ zE+fq|13U4Q#C}ui?znXJ`MiS(XN#VllmUBjF(2d4TIiOiU@ez5rj{${sRp@v7}070 z`{)iHdena(GzLvz7p3c<^GJg@S5(a*kcv^M0Q(g&!8Ja6M}zSGBgB{rvOKyIQ) ztNVR>_}wDVHHJ%rpxnd3LKc`OM3OGraQlrI{8CcXbkWvZH>MA<8-MsC7@5s+mOS$i zsUi%;9jN7KGR7i72-%V*6*bLrJII0IS%LV?p3Mh*()X=8KfxPp`GaP z|D68VngIj!%Lb}_^0dAP^4HPd%X$Dn@!Qzs#1Tg9_i4|siLY>pK*BEi`6IBKNUqvy z9P18@;Xb!8iAORxLF4_Ht`}Ij{9@$WLY-f5EKOt;youK$B+)n8nN#TV`7})A0aD&8 zIPsz`o`HZi@8ZHe8;GL(55q|Jz*Z&EGx5z9MnFlk67Seo6Wx5Vb9s}4X=*v)=?KAA zc^X5g;#Tw~5BcI;4Y<$qx}i!Ep-o z3s(BdF(%&i+2Oz_!23n)n0x|yHOjGo(v&l+?$hT7K?RZ6^$iU1NT{1hRzUWuA)7}y zV|lKo%*UBE0YbueGs&AAuCCGT@WVz#_{cYTWnBq~Y8xsExg*P+P%ODzm1*v8 zMZW6&?mB()N-P&4p-!8cL`Vg7$r`HRM$@@5fXqXUtWw5VD*aWE&8pLDW<}QPMzKtb z!JOfwKRUmrwUSdT8=e``_eu;C>BDVnPujJ7`(n!WsLMFr3QgWN_hXurj~4dD>_q&; zDVP8YsjP$OQS@#eYs>mWKn<#e>cerg%SVPEi*YY_qVA)E^pD;;76NyJNZg6Y`ar6UKTG3& z3A~7$&h+!5(ZEoodP-lrp-dXmXpwUHfUDuPZIisRogy0oQ2AHdwOqcF$3k>(?yN0; zhQ%r_;xHCSQ#T-+O({F+Tow0~1a+DDUE&GFb!u+2r9B59{Q}cKZ!KV=%hCgP)z{)c zi__un_K;;-hun>2$mpT|^zk(X3D0k8m##`p1XOo__oxx5f0z zQqSb2vDgZ26jW&-q1U&D#s~?jt=b9-9|r|h$F-{;iv?%r+f|11S(9ai-+q2d3=Xk) zDLx||CH2PJu+!5i0CuR}QCVzdL-zge3nz473=bM8ax<|J{2%>@j z7Y&U3qdc0LX+{E>7?JlzYI!3LJka0`*!1k|lGixVjeoQw<#jpewQ{{X5RM{Y7ICCw`*W#|2WR%Lt5-HRQ(DIjH# zl6!5ZF4fD2CkH!mOhz&ts~YadOw(1Th;3Ef&ryLwOPRLSzfA=w%H-_Uvx2ibZU=%o zR1$`al=GO5#ABLSyzsg5z&XkGtetbk8g`EZTwl(J6mgcVAsHssINjZUNO6rxHEZfy za|}bxdG?Or@m$A@{wHZZ9Jet&&iOJzM!kQPa+>$VoqNUit)uu#+>|E`HqnJ2h^yWi z_(ED`)HT^Y*Klyhb8su%!(}w7B`ixK^VsSW{7)5%H^6aR3mz8zhft7z6rN&9o-YA27rK zCnpCvuR^aYNobPUbpE{0mCSKj`J~B|o3l-kP@B)fd`IJ&txrHhdnoC<6uPvvT0=Z6b53O0Xv3rIK z1dRDS?G;xw0u9{{{XfyWr)QWVh393hlh>Upx1ZEt^L3N6`~5m z9>i4vR{#%cr0oRX_5FX5&xppisig@slA_vXOy<>$Uy1W72SrV9(43Qj136a##4>8 zZ67^+LAp&t#FMa}BYDX^s|2iA2$JI*9QUi*l#g?%%HZCq(4Yzm7dB_!T$1ofq9)y}f6pS{w0<}r=YEy4whm;BX$AOxW?$^p_ z421L2tOX+=MmehY5Hk&g0DItft!dOtOB}e0Dx_}rMqH~HVoZg3;;YL95*$0{)~#K6 zicEU|AoI;va>wOy(z}#f(dc>UNk20t{{Tpgxp-tJl5j@`sD^8K%x*BljOMx=F*yK! zRgtbrfwrOody(3No6((gs$J?aZY|FnzHZeV?g%@a@_J)9s<6p9Ay8+Z&bIV@Jp#$+3WAdb|W zrK?AoQnx&cZ*Lg^5>802-@zJOc9tJ%k&3Y#3|BR$>Cb(1u^9354xKvJp;%g*dsyw# zF^ml4ipFy0JnU^nWe(bxw2L^4hAw*Zo`$>61Xx2P;qb?4;IC@sv^z&FwUA>!oq9)t zwD}`s1~J=_UVVAw*ZcoiFa?(flnf+pZ?O zJT`lCUfv3mg1g^$`X6zT;abDpt!g`e+pBYt@s6V&tFBFQvK@uU2imd>Ax`fzueCnn zOMuK|P)Riyk(1^Ke>(J*$JyPDEJJK8diJe5O<5A#$dz9sp(i|6Q#sD?KOEJoY0KM^ z>ON6J^c0e9F|w2`ll)DRR5zFn|N*A7PHPuYfpmd8Hyvp&5Vr^sKI+Wj|VX zNVOdvgFLneaVOZ)w)ar1$JhbVm5hXN1tN)v=ngv2t}k^G+U-`u9Amv$B{^`}&p}Yz z7caC#54LJ&5-hu8j12yjjJ0D|Q76+_HOOBx2e&?-};4cFFD*V8uR! zVz;esMP7Y zX1z`Cd>*is3__>?5uTOmF~=!i^(p`yde?_2Nl!~}{{R5|X0&-LN;>G+*L!tf##h~( za@{G=&j?+~DJpp4qg9ogE{l$!;-`sMX~bZY)Bq`79QtW)zvM)_Fl2?BbZ$<2d(=;F z6P)?1Iq9055`;#v1OCt*DYEa0!B~~DKJWFZpnw9*6cECzTVG51nN8?6REx|m(r)RK)}s(ZB)I3NtxRB%Ny4eg z<2|WFQ)I}>Fgnyro>trM8b9@pYa4*lTHFxBoM$zG;r{>|=^DY= zr{BdPQ_j{I2D&?aN?BOo0>4pM`!@->Lf?PO`tm%vDzs;7v|-y=-f46FZlLPob;`)4}5X)zl7&oUldwNEJK4JIpgpZ=$em* z?I$JRPI`cPX0mQP7cJBN{>fQ0j)N6Aig;{a@t~idUz0uRdAuf)sIGNh4fxC8uNT0I zbt4??Fv%y&fsdti*6U$<16y5h;~|0TUK`>cgBEvZ?RrBstgH7*4)vd>c)Q}~!wJGj zzihRP_aNbaD)6f0T3-z$)9CbnF6UGyM!)c;{TcKWwkso??o|VzHC-WsGxE&igN&Nt zJRSQfw>9E zGQ2SfQ_Ne345Qbr45km62bDOcz3imml_SuMRV}$}t^Iz5H)U&; zjlu~zCBtVtbf+W`$lyDiH%@xf+9_W$2(qAk?Ee5tt-5HWE*LVApQp8E+mf^vpYX|) zjgmpNu?P z@fP>{H$b;B+Y^S6`ewaM9$P$9PvMVO`XZ$sSbIv2(MMI|PmDHJTlDQ5i;2l9ioHqv ztC+Cx7m56RclPfU+{pwCcL-M*uD8J73aqqdONrqVPRB1JW36{^+AXvN%n5&WmySS~nwA*_bu@(pogM-?i zdw9yDV*$qs1wyx1(}Lv}r(P>axqNT0Pm$tEQ>yPa*(A3fdY3X2uwdi0Wov#Y8hm6& zDbHei8q>A=bFmRx`K7qpG0Cczo)wyVkv69oMJFONgZNP!ww1ph$Z(Ypx#!(<|lySJrb{7Lw+;4g$4L*47zlubIR zDH(2a&mX5s+A4Kggd=z4QmJ1XRZ*aueUdwW4c)!6?Nu?L7#Z(c+mc2S7c5wgM{j!h zBfx*Pmy7-|{7#QX&?6T5aFZNh?in7{^{$+^FxW&{L2ZC%@T!#>v?a?cU3s2XYnRl^ zaW0KV?=^RBoOM*Zl2?nxuZFm0w zhCKRrl++{C^3RKRx078Zlou`|&I*IuHIHKqa9Swym>guQcRsZri#1!FSHuk{jBw`+ zN4-qaNFwtb1IHuYgr^uUm;4j!92_AUenLnQx||&L=QUF9c#v#K4lqM=(A21Bk&fj6 zXPox>ReRapcvK&Eo;&-}c6%dQNvT_N8ufg}A&<%rOxF?dn^3o~@Vmxe4BZARx4x2H z+g`9Q?zIiM4y@1pRGACgGoqcBD5j zs}bfmPW8_|qo}hINIsn^Ce$?)$yWoO2{itxD{fELpq-V@g{OeYoyXSz^`=QRxjgRV zbOyPZwOvXk$YtlL6h-0-;f0e2@~7-2(0aUUSRM;qdhUrX?R!L*sy+>?P zsg~gYjfOjOT`-QxoDz~!Zskksw2ewD5Kp13Ym)LvOR?vYO?CGE6S$rOD=PHKZo;u{ z^z@eR$c6G1vQ9V^NyS~4Myw>CkxNL^1;qQ=zCe45=pu?V!YdGdw3e1_3T;&w$0Sv_ zVscAu-N3?%PV<(AGMkjIaJJZt2y=jYcdbil(8g6{{4-Rdier+9Fb{g27Iu+TC`GZzVX^g&NEDw7>FyJ|I0tax_xGl(#+Kz|Qcz*Bk=RqecerKA>CFkes33g4l;a!cAOpuh zdQo(ldyFJ+!oNMvDa;j4Or-u4fJk5F00GvOi?=w>G?Mp+XK}7$X53u;4|)L#Ft6W$ zDaqz_Tzk@O;J8pZ>6$HI-CTSvAD9csa61aL5o9}BK!BVQ#{h9vArgrLfq+d~f3)=2 zIXy`f;V43^T$SRQy1lQp)%si=`F9Iej7kekNY7zgR^fJrSr`y{5m?sY{O!&Z9)y$9 zw&Pc5mu!HM*P7<3YnjxtXVRatzNZ^#<`W|l2LKOh_bVH_c_T4-ubgzveB=8nYA+1! zZ6kHS7(8bJzJ}Ar#OiMVW^f z&S|DMR^Nrku16H&tX+1IjQa6eQ&Liu+UfcpZS=jz!Xr##RwVxb6&FB^$da+!%{tV| zBpZ z9W#oB9^sFcVjPZ76r&i%e81B-zcTV2m{2qQrOrDmRQC4>iauxQ#`D|OsLLJPGVUpu z$i@$Pxf4k7j7AU3!0%Pd%^i}_{ozq7BwkyD+lOL!>M9p8DL=e^p0vzLQ~+>$^GmV% zIR$aoImIO#Jr`r0B)XB21bq3=$?Kk!*`!0#azPyl#S^Ic$|uJ#s53 zD5$>g`uz=}tgb#e?bz&TTyf7d`GPz}L*!%Dq8KTXJMclpO52hWO6MJGM(Q}V(!l-M zElQ9GE$&uGrESNmlh%{s94n}JD(X;MD+xV%aB0z_dBK^7=~ui~3Gg-8^1%iJoFDd0 zULGwp+E;AWjYS-ND}OTl&w{T0E_lD;=Z!8~N7bcNNlEg{a0YAK{ty1$Ha7x2H^v2( z&jw%Wc(0m1DI}lpncm?>1kH^7O>@QBIZg;YtLPMw&nCwN!JRnSp_f>bsLuA&==n0cVTBRB^&@GtCfu4^O45nBuA^2-m9w{9!$ zn>)GVg&A?e=jwf{!NkywI<7na0AKJ=%Cmg7Ic_#oBJXP(5*t}mOtLmf0kPJZE|aF+ zrrUr{djU{d>hrJ)(Wo8rd8=uDT!MfM4nQ@*X{Fi!0K+%s9ayhI$Oxz{Q2aoS}Ek!jqD<|9aIygRJRG%9(8m~aJp{oa#re66{aUmOqz zHIH+k>Na7H)sP(h+Sa3uS}vVfDK9_Ix%3!(&S_b@`7+wfHwzXx$F) zEaJS3PECZZ{0GSUJy)gv^S&6oB-O9V-`)Bi{8A~t?E93SGv1Qs!Zi!Du_Nygc&`-F zzAAh{@QW?4iZsD2Yxkv6I6XTG^q&QMY4FauZm}ietjB_{*#1@X_44d?4XI8yT`jS4 zQ&CPX>&WOD!4zUwBLn3*s#2pye8FNBeJqa}|nskZ@jv!mpJu0l0R}8F4 z0gpIiny9HabdHW_PVb>~~VIKRNt(XLj#}&Z%%i{!4%5>cgUU|6y zFXic34G)g~CtZcNR=2dzR=~)vufo3%bYBgHifEEsfyr~uYv{1~bsRg3sFQ1=+x`!8 zjBTV zyGi7z{*|?*T&=aDwZRGs`r`(><<8@>(?i6^V=H1Tr1v##V_4j?Hr#in-p>dhe6i>- zYa;u`D{UG3G6LXj4c4ysUdLGR8Oe)qCnV>LS1f72i?Tf0iBgX}O%o#!3FIppIb+9O z^|PUPMr)>7r{5Y54o6z*bWa71Eq>8*s_&1wNb6T_cf^I-vA z)}6{aevzhW@a%y%FzCjj{=>48;M`nD%yW`5F>G5)q4%$%%4zabbGGN{ya$J;9I{oq%1`jI^q2e-*TYe29xYu$O~5J6 zai2>2%oOq!H?Sjtn)u81An^x>J{|aCZxVQd@;H%Kc39w?3f=K1?ZvA2=f|*kOX1>$ zw`qbr`OZdh#}(z`XxFb=Qswt=zxBED*}hqg&2vmnCMwX4^?PY!>ot}%kIPoc>yT>~ z#k!0GPmoV5e5!lnwKKx=YAxaGY40COEKBFI%XX*yxMhh8Uore_Z z+FIDwlIry{F6WDMlFH{Bb6+t2(w;1d{6!_INJvgLlkZ

lw7st}YrS0bycPpKAEa z;`BPFiF{*oEtDJ7NO{k_d-+sUuF}x@?i_?%>Q$Ga%8wCA6ouhjeQG&8MR_A`E_ob~ zYQ%mD@dVDPh`Tq$ohv@4;OaKBdpx9<FwWW0x9#{+?mY4WY?OBVN3vh z@luH9W&yCIRFJDSa>@dp0q;>5N>4@7_VibOb&f|T9T1WEZHEj;pv_y26u5O`$3iKQ zB!m(W9@wi^$t++3yl3SHy+U@gTah>BIwX%Jw;ZVHx~*uog8NfMRv-hDpRF)P<|6E% z3~^l-fHb+KnB5f|4hi~JQ<8AHTb!7hjuczI=UHbQP{AFnZbu!fYech&XL%`sJ zT=t0!q0?X)0|K`7dzmaW@&E*t>MP5s7b)2J$;aAMvCsI1=`OW4#Ed{}4t?v&{{U$Z z6~(3aemxf6X7gs@ww`*CUXHUqWV@J+s-)zfPSx|@#a(t^7JNW3MC#DM=RUw1@4=>@ zI!DoD^y4g4t39B!^?Mwqw#%bWS{0^o^f29mhnitL-UTgt$!P96W!|uBwfiF z!gE<5P1Q~Zp(Bd*Id%U4f_<$BN|Y3TuQE8Gg@z;t*aJ$@TBj|$8SmPpiKIK1a2Y&P zPnt4>XP@s>sYyHB=xw#DBX+l8kXWD6nEplp$v*q4!MBz6mI?vv4H81gMgoj?HFsAf zy>w+(F@v>oJ&CAiiCPn!=dsONmMfHevI08&>{Jsh&V;T9ernQJx@M{MGlYNuHy%3* zUp;*)GOSKKNA2g8WkQUBO0g&~`ri`8`KyEn$>S#$I=5KL)|(ytj&56awwS;$=uR8`mv@}O<2jBp98=V!U3A3;%-*fTlF zJm$7--Z>#(-gF+lYZ^9?IRpcfp0%@QxWKJ3QO7`QDc<(7Gpd{2v)DgoJwo0sY(ix` zo=4?hPie_(^7)r<&JIr>g?y3wK57zL_{J4L04zK8>0ese&var(5h({4>0Ul5HB#!! z=ly!0nDGra490rzW@_xVBq@=KgTVv&(9y&f<&d6pgG6#nVgM-INY6c~@rfHC9FI{|CRx#hg*SI4NFt_JYn`pN z{=crLL>-lw`0gQ*hnXV~M>*|NBE$w^k=PTQgW9WtN5~a76O+dvdsWCprFSSmF~~d< zLT$x#{+b81hh{LlT2=$N%`v4^CoK3q>F8Zmx2VYIDK0$SiWL{9BQ-59Tiajj{s}R5 znoNt&wFpZ}#C~;F@WjJ(QZONNw>ZT~BHXKPMO~*nH(CHP0;KK0@7|&@gR{5w{eN1U zM$u(>uHp!Tdp1UWYUC3`Ds5I^sxyP$sw&AGn^T1+fO=HkY>GAvE_xA)QgV{kKh==s z9c^*9(Z`QAH+}%dJ!tVY*&YkIi!c8G9?g-T_Dwik%<5u7ydJfsVPbAzHrHsbjyW0j zt!cMTJk4pjo2l%pLUQ{pKe?ZrzZEb%Wp+b1GM>L$=NHT5mgl&yyFM;{#=aBr$&*vj zHd|f3PX~f|_pg`!C;rU;01&<%+&jspnV<}DBz*Cj`aC`+jd-p{uVeK*zdOtG58=yR z&qizh$a1Q9)*?^MxMLrMec5L`2G%uch#(JI_*?c;iu%jPkw-j5STGnT9qaB(ca+;l zkiT#NgI+#4E_Tm=;Kt!oC4n4@;C?86(3&s93&a|sa3td+(?3e>b1IBy z@~@abZR0yb84NJF!R~oAjv9qJ(@~n!)WadbVY3W#qgQJ^kD&Yq@%O<#ID#`{uAz2b zW8KI#*~O_^+~9ev$=C07uggyl_|L>X7rR@nD^h6LPDUEN)8QxW$>N;?NUZ!(wrGYF zu{k*WtERqG;Q6U5{(t0pd5;Lq~2h#AY#^5_?dw4*u}z)=PJx#NAli-7lE? zgAu_4rBhut=GlwD>_GJAHP_zwV&q`NqZs?Ss!&?o*-wKPJGsfG+#0%H@IS2%sA46{ zz04c!KGOEw!+UHP)WTIgqwUpSPxvQpUyrQ|+E(&soLG3%$KDH&#FtWCK!9hb1M;rJ z!G9ifdzr*qw35Ri!TIyo@~Tj+&Ay-_xVIQ19E#Do_9kp0(J$jR^8nNiWCmJPdYeQmf>pq;~UTH2YmIOtTQgn?~KK zfxxP3qgk8bekIQ4#t&+>ER!m25iU6XDoc3fljcs8Sy5s1Q`Ak%|#q-Y&;`IF|+Rf0LbUV=a{^!1y3rXty1=r?RT>O05kJ{_JGqz!+l8j zCrH(1Fvar8$pMc!; zXZ#b_!nYG^<5H5)VR{xHO7$_$qQKeieWw!Dr-9+=B<*yU-?{d#n*7spNbMw*gYL!w0=6VcIBblL-Gy@=I=q=}{J$|yPe5zsr4`Gzy${K7F_iHMUqgww zmH}|jy@_svJu0Qd@R5lN40I={s}l*yXW4=Y$34HssoY61KntlP_dn;Fx1~!ZxBL&( z`Z&d0ig&bl_sAHKIOeK6(X$o#iO(24s_d5zv6WcC0eHn{HuT*qfHTSGtzEs#GoqUJ zZuDn0@oQO!PVl|M#VfDLj=gv_^EIqXb8|J@lb3VNd!NURXZ|FH%0B0epRIVr7V;z@ zmH_7@iuzm?K3W!P&7W77Crbwup6=nL*+n(z$UGiRZ(KnNfT7RII#hlfvyd^F&=a09 z+ckSpSrRsV$~ZU%wsN$zMzX2xD%ltkEK^+-QrHJIW>}$)+`75I9EwXgq>@IFv4%V! zN=;SfjRJxPussD@ifu93N~Ml}S&r86*$*Is2sOlbkHcco&BdTQ3F+3mxz*%y#|NG> z#b#@#%Cdivd-0muFW%7gu+?W7@~w|NF{$C0=hGFn;kaPIV$3o)tcjhB?T&<=1$3Sm zk2c`pbB?>KN$8HeM3iZlk|;v`@_w}{EDQ(?*#nPyaEelLa0ufB)Ud44;1yhf#!Y9Y zhb7+P!31LrTb_gyR-=jr#$1dJ#*!G^H<&`>Z#>nQW1R+2jN_>ORT9)N34ZlMgaEFNhbXKrfNl{~igEiqLeDaSo)pS!)5{{T^G3InwD{MxFeLDJHJGMiG62SStxY6I zB3;O&5m`5`*A+{(?&x+u2`3|dk+%Y7YxCMTZhLrb`L3s-eNITgU7sijHpQI$N9}q z13otfOlKfwo{Bb#GpgEKlg%7KMgjH6sGDo413B$e87FAYcAWIVrYvWMzz6HzruUAT zU;4QU@mr8h6fOv6Za5ohg!&t}&lla=hh;ZKo~37^2tJ9O_bpxuETC zr-gi4@Rxyp5M7TNX{Z4(XX{@ON2zKWUF%I}J4VXHf{pK9tsEpV6q9YI-sj%nvPwDLR|@qe)lIMIwa?Sb zOZ_tbKRU*Bky&yXTQ&11?Zp&pYK!w9$By;o{{RbrYabr?8b!Cex;HQk1`-_c>0KYj ze~H(B8~i-CT1J+4qUDu2qJ|E&8tP4H-3CpQ;_{5qN~>J0G@0N7U~J^jr9`6*oSK^Q z%KFA*9n1w79z$_V{o#-nBcDTFyH?!$$h*DItG{7XRfwK?@n2WkU9SR6_88q?EB?aU z8k`EB$MdQS5>&Si4X2Kw@ujORSh3fjps46gemP> zdh~MJvj++=ykfbKCxb6w@mr#7jhw2>m`7{+Ul(~?PbAKnzmkYpdNV`Q6?N2P$9r-PGQ>-iq5 z;KvsFJV@Yyw~wW3{jkd}1g(H@20K=Mk2Aw(3_t>`g0+mW!4Q^6*DSpSbG}C=lz*@4 z$IUj}wdyKIZ!Cc>WFQ01E3fcZg7mAYS5cZyJ#$<$+*~UG5MFsEyH5=27tmNNLxYTy z!J)-1dU~8V^;JPAyI=A>9@bwEz^fPlVMaYGAIIMq{0s2wN0Rqc)DjUIl6Ogr^{z+7 zUMIWJv^$I4>KS8VG1~yw=O67&@w>*}Gx3$yn{%r(al6+~_uWr02ai-Wy8J<-tfF5!|74y%+zu3^~ejt;@zB@&2(r;Kn>&|^> z%kfxzB^Nnw)49{anT8u9%IZ|C{pmdyT@RbS6X+fw@MOv3ORXuy5RluC1Juaa@ z8t?4cE@L17I`C`Azi00h_+#N0!iCj!tH`5c9_%r}JaLMt;eXmX@8fsG5#ik))efGL ze8rCq&(gknRO-6k+n3#5erM+|4_a9InVjSMxXS*$l02i~pX{6BUyMF9o5Y&sypUNL zcNbxfGuxW`BjI1dF9>`n(NfDovBQM|NioSdu7gO^VbZkt?X4h*6fQ_#rC583f`XxO z>6*h4im!{Cl--iqey5q5=UCj{rRu#pMQp#!SGZ7xi?%Rx^L~}(e-nIBas8|;;FDkn zf;#oDP1Pm)KA!Uezi^T1n(^&NezUL1B!LdcI0mziD!!UnyrPs;CstmFvu4swY^YhA zEBB2-aT+KP`{ju|ingh72qrS8j1Fp)*E6JqxapElYEoNS9+fU@Xf4CT6`@k3XQ}n9 zsXU)7qefU`r%%SM-dxRcMjcNaanhrmr4bn<3a4%f^sSLn z-z5~UvPQ0xZjf3iLP23w^^%4!E--RWIIU}Vvw#BN4sdHbQ2FixvkoegT+YTcIF;eDVn+wHZk_f$JS*m_7LF8b^UelAZk5;Q zFl?|4fbu;nleLV!$WVHoYtS@XITFS-Zo?-Yl~dg9#YslQV&CP-Cnlzf-Cc(#`=lDS zkQ{u?k~&nj(8#AF0CekFHgLJLw<3xpDsdSnvCmqY2$AjIwDvyrJaNdmV!(sbj+F6i z(>kKEoROYuJGIcwO+KdIfb`gzn&w5xBZFNuA~%_s6W7wKXqIhhr6gpi+y_I7(Xx!Q z3}BygT+iNbPxyTg5_LJG(fd*^*;Lx6yoZ4 z+tFx*-vb;vH`H~-06^IY822YM^b)fSGVRWK^rbCuA7Cg!C%;;&YSQR*ruP*V-dOh{ zVZG@ZJ8(jIOmcemr!jA;ItIPhLmNzm6z# zH}MgGIHZnQZ;af8;Onh4AV%zF=DPrXgL+f1RRFVfHDtP49Q(A0P^^T_2hjNzsq%NfKAUq#>`y=4y zrE7WND|I`I2*)Sa74emXvc+>8n@3TP&c3+)o^Pkrd@BrVA_5d+KT7lQk&2D&xA~t3 z#juN1=6V!H9C>dUW7`IvhB!tTxf$af>91*UlP)AqM>sV;%cN4iVvu?PTozATem~ds zW8&M3V3NVGmU2{%N2N#}7GdR_a6cdZy+IF}9El2^Imhy+Fq}C1J~7Y+=~nL;-J&^r zGQz4b+S%asJ?g#5f(da6IUb!V!hNG?Ssg(i-KvwtD=;YQlg?`&vv>0R2Tdi^jr@rZ z&WuiTk=mz@NEBi=YysSHO^QiGTVG<5diqqb`J<~V5OIS_nv&_gzaP}6cC{snNXXn@ zBNzlznLb_0`2^>aO-9?1gzLs?RCxjrj5+I?e6f$a)6~N4NU3tD3YH|`@C7wQ48g|k zdm6JPyzJY-1P;8^Zv=zpLO49BH7*f*FYEprLuDnk$af$)S7l?K0sSc?Z!!{yt-HS! zArq2YVr}b9Z!r`}9EwhQ15nbIsei+FEokm%qed=9{rqr2JXPzf*(`L4r-Ob{GFP8! zk9+x{Tq()V2Bg%YowS>Rq+rC|54CTHQE|Fjf5Q%3va23$==uKh_Q%z{8{>)eZFUhY zvPxGy2pRfUwEQ{v@8Ca(Hu1ijsVs9a8=_{fi2nd+D5rzRw~@OK^@sV_DWQ0?Uhvhz z-0513kusd&UcHInXx4``G=GQOecm^PaG0um^gYRb2ipGtwcFdv;CWeFaNF{*KU(-^ z){8E{26lXt7$H(PIrOED||IK zOWb?Kc;#0C_#?I} z>TlR*%@Q24jAI=2=~-i~?5=b1V{yuPleL;XC*q&%nczPhLictS%WH5!Do}Bree335 zia)a7jJykW^1)=%+o}0oM{L*MUp$#sD}p$x+MbyW{kuhZYL28FhZ(Os500w^XR7IU z`kx_|aW*>!)Mojk=eqfyI)24=Z>C#G1=KAY4xxuVE9ltdj2)n3KK<+F-;2K%=lCt- zFZhz#M;s;c`#X&NE4cV&`&D>L#?hn~*J*7#jlVJP`BYY+R!Ps7P4^=<%dxVnEJI%G z^}5${*I&!Q!xqTtUo3vx)2k|}$i{Kc*1nptzl&40^Q^BC*Bml7b6+if+pQ|xDu&Nq z{^qX$tybNC;f}5mi+P*3W_;aYs@`dH39M&$m>#Ir>E8|i0BWxo_%c}1?(RvUUZIa~ z%DkYNcJRRZ(}PQ#yZcwUR-HQWw3W}$u{bO?E*7g4&$_-5{?y(S_<^#<>Ab1jW0T&! zdexww1$Y}EfI$`TC+x`#^7!Tj1CKCg2i#ZRnn02rIu!E;Jg_+WSI%PTQlnAED^FAM z%=ZIFFUPu6o|d_f;@eoB*uNmIe;VTpTOG$~;jyFisph`&0BBs{{S$;w&-uFCwu6kvUn9X{Je9`b5=J|opm8Z&+i8AdshCX=ErDS zc@+zf;v%xVC8jg@jU?QSmdQD+XUMO9wmnES90f-D?0Sxji6TeTg;09+tqZAP5dc{6 z*WQu{3>M0h0bNg(sYXf&uAW=Z7uc zNL9)*{SWD0ZQ$*LSQ1JX1-c&f>^efTS}TN5y)jd7d1!h0qjairCU8F=HAwVthxf9` z#ZQ#j1CGYOF+L#baq6BYySgNU=AKFSuhEa&OJ5pK!<&dhg?C&7-=VM1-w%8?@n6J$ z5k0<%VDbrNz-3(bucgYIXPirT1x*d|r@Y(J%IO)67S|#7RKCJjB@uS8+ z96lqg*Hik zVm7Jk$*(f_dHXx~(_GVE#Xn(qt?kD1BaCn>>`gcJa`5lPUmU-W^-IK_*h#$*9D~k9 zZGO?V`e%TC70+X#!xRxLJ5^A17(Hv(hG7`EP^7og@BELhp~MQNB92*v*JR(9TOXgE zKJkvdb9UYzxYXr%EzZ!Juq)_q_$Tj$qPf(Lrz#vTL)4Cy^8U4PHlgAP9gcTSd;8bZ z-?PWYPYV1I@C=%r^~`N_$@{qdPClNs*_lSIN-CTqe zw5>8Qmv;*pDmI2Z{VDOuYjL*X)RtCIMl0ff2K;>S$H#Ar5UX7nth~{-AbO3$zR}Sw z?(DRvVrRh-3=HSBe9j{e>?O-5ccJ;7ZI;U{#KwfBd0AiPQ1Rxc6`qRwO9E8<^0>>j2-F#2Jm{}N%gDsE%>0CyPUOQmMakvAW)eyfguAd}&I67X>1d{4r zzPOJVQv4qM>oV@vAYye%hEydu`@@c#f4_?|6G#1pL243{B!_o=jK5vKD?5}@?;uRYaudD~f%@mLe) zkVvk-K=HPbZE70w?L**oQ(r?UwGKp&ti@rc2WaeeaI6@}A2vI7tnEe!l)IJ5sw3hy zgA(jZki@nI0jmwFCZz(jEH<8MV;Od6^Xb#8PG0idc9}J`(lxZmbI^lX8qSXPH$Gyc z`DF3!R!sBT%qNY)?LRl?T?|o0uW7-Ai@AqBv?i&~PwTl#r?IJLvp8w3l&By#&7NzC z_=hSaeqSUGIrXni)O4$hIXtIj&IwRQO7jnjPV06dVgS!>=DO)P%0F@JW$&K1q0Q)! z3GdN%lg}c(BTt1Qw^)i0a0Y#Ag7Af`lWJ*!fw*Uy^s9SW6aZXc4l_<|b6C7}Mygul z78r@#Q0MDTjwK|Jho|dSMY&QRcWl(L!1&2vGuPU&otB3SpHi@jC0*n<9gSV^-Hcb7 zlAWZ5IU<`ix!Pk62RsVsd?Th9AvXnvagYys&T{0Ard4XF($Vf|7}78z3P=X7S-_ba zP~;q(R7N=;CPJlglZw4&k_J$YF~)0?o0d06nNrb4#)$-M%94UX>IZ7-ZJH}fbAZGF z>&dKb4%ydh0&+(r99EU=@}wpqC>cGEYQlGNw*LS#$*Ijc%Uuy&WQfYs`DAU&7Gqu^ z@w3E3#GWr*CLqQ*&&)yU0k2x|X0miI4Ns`cFv*OBABBAS+LV_wUhDUBgSe3!9>%+H zv6Z>4tNxMh_$&oP^WeY zA6jVu)3df{8wu%7!yE<0E*KmfQK$_V&OtRjkwuV(93Og!1JwR?J+nw<2XLv9Z5JKM z-H`msPI>08X-yH35y3r1YOA!ss4g@0t2%4W02e{%zOv`!2h{hhWSx>KZSu5@WMCaj z42+J3zMuV-bx`^@mUlMP;11RD`ZUbJ{Ke05E9igOBT&PeMz{dFloY#=vtu@>4 zvOWUww&GzBY+_D2^GM4Xlq<0VAHr&Jkavb&2XnR>-zN~ zEv*=_lx@KQB!7CNHnFy3Qb9ci@6w$cN=abJl5v1(%qCov*^hHk$lt}YzxDlj0&X(V zlo=xuGr50Wyo!8N#~H{jMmw6g@P<>lmn3t8`co!_qd~Q!#yXy&qHmSzxBkDc@-%Z* z9;{O|U3Ret+NFh|Q;fEInynj3pd(8k9l_~R4>g}~C_pDQe5q?~Oyv~GUBWO>2^s$Y zIjEmNmHMg zXD78xQNY8xat<(Qr8W%t%k7i;R$shM$s0wh6iNiS<0VPp=cQ@7L;Z<6FemqCAC*&8 za!FZGoaX@Iw){RMzl_g^?sqSm!za9K8@sGp(LF_fF2S9|4!FaEs z!&akO2|=H&<++{@Fr|7ky|-OX$M#fMo5z;qBY&(N4Smt9{6Fx|jC4h|)-<$`G(ddI z(!L-4lOUPAeQ%TeV}gCfeuZgvZuSu{kw4XrGt#`AY@BLdF5Z7}`R5hao*z5srzV}3 zbLBsbU$EYtcG7BI48k@G2yy=a*Q=kh$HUEY;ohX$Zog~gGPebfUX}GF#f-@h%Ordc zT-VEAwkM7?{{RH)aa`z^enYEgDt+lwtzQ#*K3z+}W3l{0hj(njREA8i-3&9F zS1hPh!^uW*{B-;O03*f5W!T)ht*b-l(D@hk&yol6ODNnp*Ve~{noA3j&N#|YT+P{~*5}9f`eoLh<}15bjH$s4F; zMk6BwlbZYI;-BoJ;NKg;CC;C39lgN^1$q)Kl0SP`(UaC=gGIg(+kub%1{ zbS9N%+`aUA)nz4>ySuZ~XP3%=5F3neqorrw&Ynw3cXY`IwOwnIE*H%kLh*yasvaPm zLuZAMWrhYTon5r8x#3V;^->?;M2_=P5&(JRW3DUMwDPNFk%Vu$InOoaUkR;lq`Fy) zD|!r9uUW?@mx9APc{u4w#VK9-Z~b|mE^9RLZ60m$x8S7T7A;oFOMsDNZ&G^mR(=!y z&prwGS*N0DT4KE6N0}=xIq!<}XrPgZZQzhbc&X<907s38WyapV^-`SbLy^45}s2nKn{u6Oo){f0IF02En|6L`KcZ)&Ps2V8Cg@vo)B)}@8PN1sFX3>IO7$?`f5 zto5?ftA2(50NLN;--JF0{6CiR?oIbDnMlV|#~rJH@vrS8;{O1RK0S&FFJ+F=?m$RY z`)>BEKiX?R()=mn$vi)yfUw)KT!zkYYZKr;ohGT{%P3F=#LLI0B8P{=(V;5PTD14y z(AGJ24==%1#oF_da&7OgM1GU}0@LEtz8%;`Vr|ADl22YM%l`mw8=2(rul7cr6TFig z1YY^gdUReo@b|+X0NY*bT9i=)s|f8yl65HSdM6JK^bk)^sq zB5lNV9R@4sU)XctuZX-Qqm64^fnr$~E5C#FucL0HmKcvJcMceu@iCPZTuc7De_p5O zneHkW%;v2~yQ|rHBZc^fr$ctxxGY9<#c_LLjrPM6Z3h@8yMG;AJdCkNBIE;{n&jk0 z4jCCs=aHV(h2tM|^f2;X#b2>rK?29RND7=~c{NsTn@qb-0X*id-Zj=X85EFtTB|Hm zFy(;HC2H=utaYufR$GWMJR(WoCGDij-VrbejH`9sP;Df-=W$S8rPR`{H!P zwU&Y5Whh8FuYd5~vR2LP?(RXt9i_gN;J+6pHy$mS5R7j)!RyUyhg}ZbkDbbKmg>Y` z4=oaHPkSlA73k2x7zAx?y|c}89|$yOy4^c4$QTvf&1WQEyNrsNN<8G^>p5a%li1FU zBV{{tk=xd+M-n*0MZoJ)t+Pbm!|%mBBe5=|5=9C<`W(%-u?4-Hb6towu>|r#uC~_R zD@$dGP_N6$HI?D5Ij*jQxd1OD``1V1u{$@6WP!WZvZ}4Ej!M-VtLQ^*98!GSNf^f* zR*stzgT!Z?b*k_yj;y?N6|JK~E3jcA<0FDAk!cNgIciEtYHn#!2;v_rV6Qmm6&?FQ zEWwJg_Re_qt6_{b&51zV4nHc*xwv~P8L#G*aEf~UD;jOedz>`yC#LU2dAG;!6ot2s zK(#H0ATs8>r^T00>H1_kS{BOyTy)8;{{RzfP2xWo++R&D=&jhF%bMamMXAlGYH~{L zfuE4|;=Nc?e5&W&<@jG?6$P{vzHe9lMLb0z+#(>3xik|P90u#pJtk%Z*5O_DlhpNPN;qCz{0R#^eutcN@t8gnd&-fxEFYOg>Oa_cX(~e|pm>>;@^(7AJ6ZB=#qz66`5OZ*2*FQSu$$ zooV|Ju1sJYV+ntGkA12E&YT8eLN1m7;hZPc;B1oPDQrMp$~4p8Kg{OUw` znMhfbbH*u`4INt})s94G5W(Ve?aYD89kR~&oOyt(;dk5kQb z=yauaLKFeWr6B_XM_+oA%aO<<9@P9e8=Z!Jl&*s6#3U*Ezbyzba(#MKtLCW32R!G} zp0P-SbM3)DE)5Fe*5pX2P6A^+d8^hoK%bd$x1MR%mNK&|FwW%88dFd%*v=-&aaE^T~OZmO!8U_oa0 z70rl><0>L`|V{x$2xNKu;#tfQQgdegj;vlZ^{A&6y0 z-u|@>;`wR0<2c7SHDqtV4Uco0Pc7dltPVP4)X7R;*Qe+>O47NX8(T`a+w%^X=B7r8 z1|3_T;M7+!&lSO8g*fDn;)5m5Hym)dBpR5mWZPQ$_Wr)(p~YWvL>BH(?%8tK1a_zH zf++T~oB>p#d#L0&U;%9PtA*ci1%dCu;8Zy_{K87ov)B?ijwFsEeqOA9&osjfA@WhM z23wk$r&9?8fX9GA#y<*$=9x~zw1U5AIT4w*Ttz8>)oryPbUg6$m*6q9jsOa2=|aWHbHr}gqXp*6gb?Aeva zT$<%PdGMdXKM*Wl&souti-H85^H;64iHl&&r~Q(8)ak0+HcXNXXMlTA6*x&sJv%?h z;h|E#8lsdXXXJeEaqthr9|Qbko+ys&M`$Gkf_e<}{VV7%1$;s9r;4m0lSsZvM$wfA zwkyQ{0Bqao4}_i4T;X%__Um6Lcnjl~js73%pJ>xHS11oCU$uG*2U8PIo10VY-baeh zurbDS{_(48*2n4tO=|I#@<=;Q53PJ-`+ZLwdWsBV8UALwAA>))E|=m6qtkp@D#ZIS z<`duFit``aOT~5`B)eP9D(NPT$snoE1e!3kYEr~nQD`_= zx1#+{>gaqO@gv246T4T^bqSZ|A1|53bEhm$)70Y?E}k8)Q)&Jo#%tJ}xmo%xN-(Vl z8Klwf6Z|Xj{{Y8b3;q&S9(<~Vu+JyGc`u57A9$C-7fo-h=~73xI3#tixBmcQyF7R; zOAoxb!5-Dz`4)ylW>|<{V_*2a=kT5fo>??!#wfhb0IxYKZo)v#KFxdz=z|Ypb zYxZOC?eB&>I5fRk1XHgBF&QSFGQBF$P7?c{$gU{IVez?rIZ=04{| zz0?T1_v3Wq^)+%WjeL0UQX}3 zGw)*D=OFTU=Cidu6HnFS`#t5Z@CPBNyw%KiVI{c-jF3HQ)xE<@hYUGANWiFZy1ZG} z7g~zEcR7C$X}WENpV;lKOjsQOHJ{+fA^z3#3N{BAUbwA48(hohk0gRgIl-gh>dhs~ zNbxG*^)-rFp2cU$fY-?D?EJ8s#BI|9CaUX@B=H4EbI&+xw>y-G{`FKSBpS-U z)TNb#5y(4a=e1`kCnsgt@-XUdr!qSqhG}V}fX;-wae#Un^oVYwmIah9F^=`+{sOkT zl&SNE;&{ogM*(cC1lJNO?Oc=TO3BH#eD*nC5oN1osjuRT<_W+ZNv8mBPduB-f7q(_glBo$&c5&^$kIuXmCO8Q}6gE8}fr;&+TbDtN&zb=^_q5>JsC zJOQ6-^)T6ONzv!4?ytrF0Fm|CKL^yWOY1nzBDJ?xeeLkm!+rz!(X0Oe!ok#ZqbLuU zmGgt&HR=8?lTOgQBXTXRmI#*JfZN7CQ(Q;vv7wzK;iaa+puAwVPizY5J}=91JQ;Td zwjG`(3crD_7{{KfS8Zvz^K_*wc5ekaY0dW}&&@B|Cs18y;$`zk6G@qy7;ke{ehye` z-V3=NEt5x+%8TXw)IbolzbU(HJgP?pk_;kJ= z&>)H>jY9mXf_nF_pm@qPrl>`8EuOm{s8r7IS&lk6brsDQq@PPJi20M^@5lcD7W_@r zmd@gNBeh1_u`6S}eR=x<=ytZA4sAkczGhH&XV_Q3_8X?w6f=G4NAs_+z8?P3J|6fl z@Rcpr@fz{t!bA=^$I`OQs7|7dI#IdH#dsRHtUU}C8X7m#M3O#&`0Y5?JU1tY>?B`4 z;B8gT4{=_5@Ei6&@c#gXuE&ZzQ)DN*k^IF|&{viG1^BPx{{W326-KS8UB8gBe6WMS z85Q_v&u2z)fta$hwJh2s$ z`_4bbJ}k4;b+@vDGQ>7caw@t?Azj~QB=jVXMP=z0*Ecthc=8R**#vr4tF6SW0mrZn zT0UBC-MsprQsYfNRq&!ImKMo%Y>*B??^TQn-!GO=p~l9QW19L5wh5;<)cWojq@O(P^`2+e9n(p0^3fK;ykM=etcJlc#7@sHMwM)B$)^q zKK1TiHFFMwEyACat~mNvg*I+=tnceDf30gt`@V-pQ>6zlGuHkK=`U}keWq(8ha4L1 zZ*-V~gXQ3XmG`dW;D5sVeN*9_a}BK_OsOAA%+!HY4-_ts45Q19 zzJF@d4NmgCzovQ_Z5YcF%`Kp>^XQH?;^I9&MR^`GzTo7H@7-L6YkL4_(~F*ep29A}!6IF(Qpj1GCtJIr7J5(PYSP9j5$xWGB% z)}=Qnq?UqmLWKo#7lGQGp#V96fPH$?OpZZZf;(W-!Ekb00C%kuyS4TwR3uyi-a}_O z9P>rnM)u4WEEA4%?@m{7_eeDr!yhG;Tz39+UhOfY?{l1wW2nOC9Z07>&AWtc%Huif zQbrxE)m4WepVpMd;O%D4-%8r)Zf$l(B8}t9rau}{76=(-@Mn=QK=y6|asKIH+F zil%futGpMsv`fl`UJjf|d0$uVRT@jfDDD zXc-m8=#GEhtGbMGDI44X0m$$5s!E`dAbffPdQhz>=yyiWDB8Ahum%Kk+}C07!u}h7 z5?YsL07^60jzw{nOwAgXVUC>FLE&qI2CHu(z5sF4>sU%M<+0`C>HAzHqun#^Zwk*9 z{()^W?qTJQbHJ?;1ZWSIjn7X?=l&61jYGlq()oaa7#(Y-cL;Wu7|-QiRYuxr>W{{+ zB<`yO$)JO5@8$0R%D5PCL-0 zP7H7`9^#uDw1jPtf3=EI41aa;>c*;3l6KgK8|a8{VObv`2`93X(wLCP3YCyJ8ORx_ zr7EKjC88Au)~`Cg-Lz zMa<2&d~&Jd6bI@m{G$duPAbjVZds0O5 zV3RniA|Vc|EwRp~~92X0<9po4l3L^Y@50Yz&>*M!=ym108wdy3!yvEI(8u^FzxYH9)@uZ$Z0ymrw#=NUT@lLtn%aL=Y zUbJkdI1OIH!cwaQY$NfCqNYcD-(^zKxG{@lZKsOm>5%f)$z#V^^jz@93N^+kms znlN0tgN*gAdRY6##;Wv9%t+>vFPb^_k?GdEe}|tO{A=J#*xtic zkjIcVmg2UrmBp@VZTfUQ9K(bmBE`O=vtPR(jj3W83(0#E-P5Rhs4G%g=bD{XJ&AkjIcDsd1N=Q zdeG6DRD*ujUsjxESqPS~i<)reawoQzGEtQe3t< zB{))|qPJ(Sd@Jw;u+o!Jz34zH4QhNyx3tszD|sYqjgT-0@HNf&E54>{L%S?`$%dFfAJ#uhT=T- z+A@7>7vUD3m;N)fh{jLvhH!nwSopQ}jc3P~epBvdn1BH4b6rQnzl9z%@aCWY014EV zrYK??gGji|eVtoMf`#>J$L|@1NK?YPNu?>PN7bKn=>Gr{ydChH;hnU)&FaQuw*)46 zCmk!ttUqe~SK`;ic=Rt0#!|^;3Rs-(8TwbsUlKkoc*Dkbtz)U`j$w=CR0jgRbM_VR z-`l)ax3ai94sd>=yn5IgSX?`k)=%*CJ|`2y_-v0Qsa9U~R;_-`_CD>>3^tl<5WGW( zgAzMe$v?N|y(Xu19*btI>{x({^*^0`IpW_M_q0=vf9jwl@hpW+kO}_auD{`v&NKOy^Yl zJ7HHK=jmTyTHUm49U*ReV>RKwvya2p_)p;kpImU0x&mYTE4jG%k1kv6vSffjUc=tL zcNE=9?n`g@C+B&ZshDG`R))>!&d0?5DYMaZ_j&WXY1)Z;v!BDcb*=E|>+TBcP z11<->C>S7!$N>KU5bIKzS`+h0%M8>q`OlH&t_jY4DQMxhpX!FL_Xm+yHvQRL3>;K` zT1HDeM26^1O&z}cmz_^J&U(}rg@bKY1P-Ezy;8q#z^-0rWO08PHHfs&3f#KJa?y|p zJv#GW8tcd7 zMM^ZV3EzE4oJIfwGBABnvjQFsFNqS^`#?g1yDW3cJoOmKkK2-DDx{=>GjVTTU~fTtz}XqRl)qL z%=DC7tyxzG=97$8zlrW8j>v6nZ$B`qo(8mQ&3*({$SyO-O0HC?=)x4Eguy;u&7Wa@ z%w8~UD$3hI)Kr+{00P~*3iOYPe-EI)wEo%CEi!iQ%8Kyc45XTEwX~4R6_6<;cdw$p z4tUZ(7HA*XTBX9g%B532nCV|XiH%G>RZ=@2l;hm+7{9Dj_+`56c#fr`$K;+j_b6%(Mhr$EHTBF=X-@A~KKsD#(O2_6au3OjMyC~ICf|7b3-71aK zR(dj~)8-X1lY`iFsT0dZIf#-v8Vb6Tx7}y5AmcT5<(8X%hP#*ac#>H+G#Mwg zYF?Oa;R*o<9D~}S(QUtXm7PG(UWTT<(Dj>%e%Bqd`6^CjVUT|s$;nDhoa&@huO^Id z66-N&o*th5MZhR<+3$m13fh>S;`78ahC7&r^*OIY_~);+ybQiuIJhwE!Vnzhp6VFNt%oH)4 z9(x|NY?3Ux$U1UsTUlK9?Qz9pY!MUS_RTr|&Oq|jx$BB@yrl~xkN6i{QpEv0`N}{& zg$q(-+gBh6i^x*PJYafM%!$ThZ@ZKJ6t0pZ100!C*BoM;s^xGb7{*TH%?npxZv8;S zv9HSk{PHPNWcUU)J9+uIr)A&eSLYo?F5-WUeQ8F~ZHuOYC{!3R9{f|$RgPE@>}g{C z<7Jou>IFD$3>Gs1>ocOBlA*ypWOx-JmoxvAYYr^#)feD$QVSMrq=v7X;X906ESLTY}NzUF|4g>5h~&dl||~ zBo?;GxG}eG4+AxQ5)z;Y*dB66PijH}Ho({f{#2;Sukv$~-1VmmMKtwp-z`(q?zg6f zGIExzV=@9W9zLAYomJBU7UQopF-(O zL~z199Q4mx)z%YiTa1G_tkz)c131Y%6GFUE=+la_W`>_4`5)?-j-s`+siTf~UE(}A zInPSU(w$6a5~&&Q*0wA~Yjdrn(B-z{;H#Le`q^m!6M>vO`kFg8s z6ziLSKvaOP(~iBpDd9_^?VKIGK<1*jjF~u?1K496)^};!zv>aQcM+vfxt1nwIXE?4 zg|zZvA#ir{l0f3DPYuGt9c2gBt3c952S)AJH-u2IPpVU!pNz~~J+Sh9q9 z2RPsk^p?fdf|>HT;Qs(hwqs`J&QHXerza=9flHO@VBW?+a~s0tL^5#Px#;a7kH<^(#fcJaawy|#O(u| zes%3(u~esMUeC{|`YuVtSR7>t(sJdJR@Y1V9&zvymAq$d^5ge_AIw+T+ONZ33wY1N zaK)2^ zBj|{3ixA3>jAtZNJ|UcqB6cwzVk7jg4fs*}Tj<){QR%)Sxe?34mnVw#+rJX&y61;w zyV9@LRCvxdwtH7JqbN-&t33}AcpCUzTw_)icVC(DH^&WP?#IX17j{!RFp%JkjB{Jx z3I70VPZoG0RJ7D*Y2eNXZg~8wm-zG>{u622%+6#vBkNo{0L`B_pIY{nI(2EKC3E#m zMgt3sqM=$T=#RVnC;Lx$7sq-dA-fRV7*EQ?^~HRj`$6AZ>OMEQozaMIR-FNe=Qzi$dJn{(+1JMZ01xip&$4%gSdHOxk?UMM7W2V= zkj%s#+ycDyuFhzUmo=K@JUP*NztvES6cLV8D2hBBozpwZQ znLT4ByB+U?f(cNF$Rh*p)E^ve@9#Vjb!TG(NYWt+6myadY4|z^xL^YyN`_Q$i) z{2TDiv@IgVZR1#gP^*r_SJ7(mK_0}BRAV4wzFGahHMwpyw9>7Zv&q01&s^7j5>;^+ zwJFPA$og!DABxTRf;F)Y_D%UC;d`)UzIG^Bv;LLuzq7x^-wu2q@bucX^f{Que6%2p zp53Yc0JHb(hpqVS#<{M84XXUa$ebSjwaxz2UL4W99j*TW!a1XDRD_k>2V5HWB|J7N ze2uqm$KBMcfzK;EB6o~6cIx{T{v!U+UMu*&;<({y-EEq0mK8i>HTIwE$EF=K;oY$E z4(5y#ob$zgetagsTb(wf_LF=1Ovsu~5XJ#Dd=>dYV#EWFzdPgV&CgD>}xx5-B~;U!_MK;)Ey81;T%gx$$h9!v8oK5{{W4A z>+z@Ko!+Y~x*mn8ZG>fAm%Vy;93-lx%Jf_R0Kh$bw=AiPnn_wKc4dChUlOf6L8!Ks zVt1l31P{i%qsvV05gvU-Sh;zokj*XFW+x^?P4c8GmADKCCyM$Qu2`g=hv+mZLWMO> zD@2AWqcLL$&N#p{?;|Qek0&|Epus0DE&%pDsz~_+EZ8{YsH%IXa^AA;K+&swvZ)8x z6!k>fa}m#M4h=n(TbSnz!=WOS2~-9WkM}_7Lw9h8<5(RjRXZbg z$2G=k*B@=ZdE9OU|8Z%%|D z#*MJXK--lRo7}DpV6T2EVRE8SimFCBp4C6@%8jn1p12sI&M*4%I&Rvr0z`x<^7z}2 zyGoG!-|BEP`P7X!mfW}pw-n}YQ zHb@B0dVeY-eINDEP4en0+LS=201i%jQu#}?l0X^sr>T*FP~)#FijB(>6fokFO7>64 zR(rA7ftNkI98z4s1P!-1@5Vcddd8tL^8ElGtwnUCKyu?~QIHS4QeN`22-~5TrzCG| zplw zR7U>*FzPW$Jw&Ax%)Lq�YEo+};2xER{Uo^f3r^e(o|^Ye~t0z{EZA2%OSL{hs) zbt}4lWz8r=Q)NbEKF%fbi&i0xi>B81ygj;VA$7dgnQRI4mSEpM&A$ogV$D33McIOqX21cKZ# zVy8LvHId=J8|Z#3v0I%#Pz+Bj0p_)rdvoUygnttBHOivzZ|kx0zRFRuki}S}cKzAF zC-F2Qqmn#~d*_o#@i1Jh`J9oOe+ff>P2w4k_rCBW;9dsM4EpY?QO%F}HUGpUF%iG~LYgH&Y@ten8W z^{diE=yUdurYfz?q@?+cFa&f1)Ktm1RsOtYe`p;lHKwDc$re+r*!F;@i$JLH#OI0?D)p!O#0g zr7UI4VVY1*IAg_4umw}+4c*O8Gm_Dq&D)_vSV!`hEC7WZ9CWKb3-Qgil`q(J2*6h9 zlTFm2cDBOJ$v7st>&-o$KuZ9?^T%q^9IkHqU-dS0sp2SFYtZ$$JV&HnLz59)M(7N9qz?coKALo_wNn z@6CKEHnpl~n(Vh$7wn8CBoSS-aIvpW?oR0YoVz5Bca|!(Wc{MLPxL=c=KBrYB70U2 zj5sQCF<&MA+z>|{!ZD1DWM>_DHG}Yj_Qmlph21p&01(b@AOH`T(fdk#M6&pyWgexW zlHV>|DCwTHt{V?pg@tIa^)n%hj&1}yGig_)h-v}ymkU_5Jz@Hp^Vd1=3 zLvDJYv4;{hxGOJxk&IF(<*+jvvz1ds!*!kQRWsShg_j1#- z*yDZ-_y*^|9vfXdP(ob?Kr5w}RZv+PG6r*ucB^-D;@F8M9X?!lu6p`l!JF+NcJ%_W zZca{D=w(hG+HO+n?pjwuT4ah$4^D=vUFz1dERh8vfH)X6UrxHZc?@ZANa$A`s(oV0 z2<*(ME*XCII@Su-vD;2DjdZ2C!s-&Nnu%b99o&!)HQab#AKA#pCeAwk6~xbNB-daq zz!`5!?eqvIi%&?6!nevf6`e_QG?P2?Ckw>TQxH;B2_5)?1 zoH+ExG5A!z4~l2J^Fxvk0Fl?4&dFUl9#u(yv&u;HzYau#!^{zNUW3xD$iWyYMo*~6 z`R1FYszYSE=3I{5x>uk4Z20lvpM|5br~QtMQZuT2LyGmlRhSytZWF>0-ehIe7Tmv2&be=#w(4zxofEm^3A;GKGlU<)p0X*CiU(8b~!8JE9RJ=tl~H5 zyCam;w9D@iYKG$KHVM0?J65%xm2amYSZqMRKhDy!wzAg9+DrwI{Iro)gq&w6aLpkFV| z8nx;DeZo*}rcVpP%tw;Mbp(#JB+ju$Tgy0Z-j!0)X;f!;$8(xluG(XC$v%RWqEZ>ZAA8h-TwfPpB%n9Pp(}{qi8Z> z5s>FSMR^R;H0;v6Y|O_w=9Xs?lF~>^6YJKbNTpz>%>ZMS&r13VaD_W4?0xMTP{Y$u zrmT?w1-@S?usZtGz$}S_831&^>MBDIA1s?s_q}NZGM}7D$8c)&PQ^C*5wb=G;Q>7Q z98w6uQNGyw;-@Jta?%U~#yF=*4*2os0q8r?XxtljNusQA{H06;8eb(GVmJv^92Pz5 zK@+c8fyZJ$DqYXJi80Oz#R*%k;je87&_>C%t=RH2fm5Zv*!Kv?$nGhQj7Q5TTXO0bRcufpySVNLe9A>a?for3^#!1dabiNti94ewg z$?MaK+N02Qm%C%G@SeYUqUuR=6i2AYCmdJ1cvDrk*Rx}Nx|nn zm9MAUM-`}-?85^;l~uC04KDS3dgW@?p(%pb$xDS9``)z@X{E0J0PqTzy-_1RY2%(p zkU(&`Cnu$O2gOZk^}iA(of!EdZ=4RC8uXtQ>g%HDb6uH$ZJc}YUMnTj%(q&+^K&Eo zzV+8en^3*adn==)s#{rmtMxLxMR0B}KF=IEL^vGutnHDY*tVx9zBm;3X$JMka~pv6fLWn4U*u;bdB=G+@-ghRV4Yvdeb~N6mO-W6Ee0=Fg?v&0z!6)OL~J!QcI~4ZA(-@ zBSa*!9OP5h6m~n|!kz&%{{Sh8`CD(PBAO#_Fab9J^0=n$+#gVA;sD3Dlh+j#kg+(9 zJ~NDFrf5}&aX&-T7@)>bg%WP|B9~QW2_%S7P%zyO1E{H^ctbRA8xTi0G~p0b1jsT@ zO3-axh-l^jXQeJ+w_?5YF&lPIvo<;8*DrF4lMrG(e=6(egfvHV;~403T)o^Z(>jTO zA4+hNiqV~TcW794lIawgFp>^NYoM@bLJ~8`?bf-=F(;YD#(NyETHdo49$zwyupTJeIl(ka&hlnUc5Q=$%|{!$0VkMvI3z7k11ydM+>kwo6^+_&a|IV; zTf-hc*8C$dmrasI0~rLG_OFG%w1$)7K)PnL^2)y`VoxT#B3nd~&5J+qoEpjS==(OR z#v6heTPjzMYdOZ9NH?l~*WP(}?4JjYq~~r~cSqZ>YPPqaHM<-hNEJL!3mw8TJvR<3 z=Pv^MW!1bjG!Tns=0?ywrq@j)$#O^U5gy0806LfGWgNyrn}<3g?XWp~)@14?5ax zT#S-|-U4{xaCsFS$qcL(CSQD2xTTGw3+4iFeq-9Ao+$=QQw9fvQ8zwa%%JS{GEAu( zy0ir20|upu;od^09l@lziG;hBOdRwy&m_AAX+}?4%}GV-_38KN`JFb3MvN084UGvS z93G%l@W}&UBu+u-O;n0tu>fuk4+kq#Td+yC33KxBNaBdQS?qJlDXm9e$burq6OFxg z)q&8C#`4O>2gaccxLOx5lvQly^*5jjU82uD|;JRZGsze z4@1Q^TOkXSNDka_fO^)RkEC76Z@95I;~1&mO1q6oE(pg5(z`vRZ@=~ZeuteJt}jo_ z@_&z3<-8YgixXqZKPesXYvFBvFuJwE1S1k2KN|fl@fU+Fd_|{8V}1!)5UU(?IIo(1 zHGakNNG8^NDL&#!Z!8b5y>?)$QBmb@Q}1|VIl@z;^?H)CzMZu`Ttk;o0XQQfzMTD) zydmM=7wGM$>sn&EGUF$xIIo`kN8pbTcux7PHCtDWk+5>L^mpuD@_9^5>P9#Qx5hh0 z>ARk<6V#M)=+vhxJF7AujGwWZ2bWgxjCtyI4&SYKCD(zxN8v4XE%kjiMB67)ymhb9 z0`64CXI9TpMRI=-z8UyO#1=1isaeP7ATPLs*BP!_SlPJp&sX^W09qa{UBva26)ZyL zzL)A%{hXuO;AlQVa~R_u)#yzZA$FXOwc-8*`0?QH1?u1MhtD#^sQVSzV!e+-@g|k8 zKrXc1MI}a1M%v`4n%_&GCyl~lu+`tRi&uY{nehrMNVGZbO`^LbY|2?P$QARRjr&?^ zUJ&s_npUSC>vWSFG5-M8uc7`aId2KvfcPOBCp~yI@E^o^UA#|nM7?EhaqnGtTs;c0 zcSqN7=3j@*GWkZlZ?65cKJD-i#?J+4^e9vtzu zyWxAKxYIRBBPwzNp7rz(!7tkTRW}gm-XW05yoCq!^r@|boj1)FbaCcT3 z@jjuxbo)NmjPc*l*FUI09yWN#T=9;6wV`dQ4SzE1 z=00wA0QNu$zmwDY{{V(OTq<0N38DvUjixiyb5}e?=fkJ50~r{oJUSu_LpTgbG`C@lWPb1i*A?j=8PlEZBU5j*V<(F9?JhT; zQblR9H;jyX*RAOm>lLhMlktI(ipIUAW!L)u03%G+Z`vrn#5Y=Wa-p|ax}0PTS4rSs z2-_l;o-E_;gIQ!SWqsgdwkxXejI1rZzdPj|k9x`K^n3pRU)RX_+-*rlf>AH(2@F;; z1cw1o&gC=`T^pJOnME(izYD>9!IgS%`e)L@%2B6 z7jdNJkDNl`ee2rEqPg6!f9v}D&#d4oN>i;>?_`fY@U$Z1T7e!6k1zx4*1t_ZWk_uF zkA^nSSWEi<0Ee-BT%)iX@tiypb} zRj0xE#5`jM0+v)!Cc|!iZu^}{E@Cxkz$zdoxy?s%>79%|_dAHF z?_?@AEygq7ZgEhO?uCBUk_Q0Q-Kk#x0N3?@$mxs~wHqi^B}83&e_D;mBWpo|2RS`O zJ!Vt{yxGASIp(QNc6XEZfwTjjJ5|9q9a*xDm$5QU3o*oHd*-TZ{vy)+J*U0p)Vozw z@=sdJ@jr@fv>R8un&$yiI0C+Z_@(h{Q1Ly>+1lNdfk_A6yQpD3tLBr?_Okq*rZ!yC z(jxqD`01&5rs4FRFLGL`BPe>;l>}#$%`9b!=a6ew;x?0UX}#)$Kw~TfvSj@$M7`^_ zHr<%VMdbN>`-*awV0OcwtvDgyv87N4wGr^yGWPVSllQEc-LIk(VLc-2&M{4RNgH-? z+=_eUn{!HW^x~ZiNJizkJIVW-dwS-C(^hY>N-gdA{zNR1^fBZPm=qL<93lgrzgm>W zq!yA~XWOkcVk$xjF^<0U+-~sD^E5fcq2 zGw3?iQ{E+|uEt0qt}v;PPayWLyF!H)-C3d}V~lkb$=V{xI08}E(z^X9G;uHQKJQXR zRZBjmb+xgr5;B#Lz`zbGO38(|ONb#V!GX!F*yb%5WS0Zbj+J8CLPs)gJr|DE%F=7d z;gnp~+8)*L=f*bL&W<$ul_phO4Eo}>Ztc(~5%NgIc)x>n8_O+4B!=h9P~4V1d9P*A zv8lq7rQ(yfxa(X`_j=z}e6}wQ^*W7o=vuO~^5Vrx zkty6pI#(g9YLRL7a@{=G!W@>TMY+3N<)H~wdM#PPd}r|ooh*7B3Nmi(suzOSy_YWEW5P>`7wfp>D(mkl|bfKN(tYRv9n@MJrM|HzzZ42b5kr}E?i(9)cE36TnRDHr7UX41>ZQNu1jrf zG(f*`KsoM39#K{xL)W3rOd}8cU<`0*Sk87U)kGeD6>l^5rM>QYWqeU+89&!l-@}Xmz;r?0h zPZ%PbHMFV-`&UEF3E!{vxJE87Qaz$PszZ=D=}(l#SSQ)`k|~nIBCsOo8S73EkVJ;( z9-z{bT3L-cQpHSRei!l$6iNTsaowW zpyI5^W?&m=T#dM{YgLIw$t@TIImqs7sJaTr;}4>GZ)Ahy;o=fyp1Oa@OwNU?y%s#xY$UitQ?@JizhkM3dRDuXSc@ zr`W<2c-WrU98|XPqA6i)0yh9+nH=iNT z5Hc_UtQCq2ZEcYu$IN*Gx(Q=I2$Dj;jxZ~qyHBy|t0WSDN&X@4RR;NWxKmb)y$+hv zC?pCD7{~DwS{h%7@3aenCYm;tJo8y`-Mo;D&ZD5=Xi|@tGn{uGrlVC8o>Ze(;#WPB zz&{>hxoGTsLkjL}4fX1}R-tRE!ROfQWo5|Pb6+AwG-&14Y_@pzuE)TC7d77p&W#=8 zG+6^DyJL&3tjZ8e$`6iluiLc_0NAqH~9GtTe(yClV z^9_;Up5!pTABd5r1)bcpRT0$Ase6#f@ zkN*H&R1RNj8;r2P)=5rW@+=lX3Go zN3rtyKtA_M%JFfwSjXpBPgvzHrook-)t$|Gv=X-)Yw)}WCtvRlB z+;~c@;$Xbj=6-&BYq*l%#`h0y8CXhok@YpB@XPjw@ppl4qfvJ65}Y!#XYj1Qjo=>} zT`!nMC1c3z&2f1EaQ(XCz2yj0rjtkP^>BE6T_qZ^O&?%I`%idl$6gGY&g^ZuXwL+m zcp|=B@!=Erih0sL8OhFl>qp@gnra>>x3rdQqqq#d*{`L%UHc>G9x3qZY8pd?xoEc# zqw)2wWmgY{e78I*IGhI$;$9iOC9T=<-~fNiKi0Z$h1SA<7h5lvkR=@ty=nYI_#5KS z0$xa$&@qV^?PXl%t9&4|VdFb^%WWc2!5-qat5JIv?t2*8wCZK`CkJ(Aef{vp(kJkZ zq;fz9?uSwBS3FCiL}CRkf|JPNsQ3=!>|PzUj8Bjd9M%1EQu9$t$_rv71y%7tRkj;rAnoW!TGEpK3uw;bH)E0qO6R;ms6EY_N?!z= z07qKqmFK5U=d*>3bd0dE698e6tnAz=C*Qu zIO|@xCXFCb=Zxcy)rD7ie_NSmZ~d*?p(J3523L}BIIh3KmZQl30FN>=TqWMFw#9bK zy996rbiN(&-KC5QZs#}ve8Zks?NzSkAcGv42hdh2E>$b*_>YmwO|na=@g7nTK&`O;eG4pe~F(Gue@KVI>&Iy21o|>$68hcI9W0Cbgx+?l1Ten zRMj|I3dkfv;O&q2cs}(_*U6AO#gb1-xDc}j^LX|hswwS5jmaP$xgCA$MJVhOigDP7 z%8|Zd2U>bYAzzVs&j%eTg}`6<_!!Oz0+AwV8*b9>J220>A{Qu4;)j{9i*3(4^Rb3_E?rNi4>l= zsd8&p!ZyCeL>bEYS?_^a+V!ilmRP!VAlBkR0-jrtIss8hWVc0?pN#SaK6JHgsLdvF z`fNblgCtz>itDUlZGanm&WX~mGG~{R_fzVy(@qQGJ1Pgm%z;cDAy`T9qM~q%bRvt?QTjQ#1HFHQXKKL zjtq7UVxh~|q3-@F)GcRW3^FKOXBq2WW$|ak5L)TqV6$-2KL;MQjSq@$mHf+_mUhMg zJu5R?m36DNo_RsqbATz)hb!0m^EvQ%A7NQZuZM3_4)hCMDPS=T@(i4Itk~mFrA&OD zr`ESMdoQ#;WVit_!s4hK0E$d2r;((D!Mz7^KSTiLfz`l5x_VzY*xG{>?%`k zLSd$EJ-SnrL?jW3uzG?=T9qWDdzrU!QZ$I-NCEZ(rAMkGt($F&3xT_L)K!*OR^HPy za(Gct>On<}iXZPK;yFCuvx<`AW1Z&E4*3;X1d^`vI`B9c zq$WbeMCC?1FG_b!-v0oZJe@__te}{Q89li*9ImW?cL>{@4k;Ql8;~ym7~>enqn*tH(h@~mJIc?474VT1-ShCPnjr5ZfHJhuZsPPH+4WKkHC<;Drc zEqCSyuPsMh+%h&oDbGv_=k>B>m*#|Wd)D06tfwKzZhb2gUrVnyYN>o4Fe>z$RyrtJ zGBbjPaK1=5?_C##;%O5KfO-s9I=1?mIW~lzMoo1-5VpIH5@s7o9mac7s^t{5D!i1E zv8tA6vU%GEPZ%Pn5WJu<3ZxDODUd?N_W8Lv$>OcLk1GMj?D9=>yS<*L6ukyV_O=0D zGx!dblj2)FlBLLpkVZ)rxfz{TFDU1X;;DFw&CRhbFYxB75=vI)9VY#vzfw&YLv?Jq zQG@sKR&Fh$hlt`V0OWyLej9LY!ij(buN~`L%ln^}WaFU6TA4dZ#{U4<^{F@a>{ar_ zk^~SDlgR?4p3+DeWOUDd^Lq~Ela03oOr$=|?{{YL-$Dms0T3gF?W6x2x#)K}+HzlaR z9fdl0;hHl9w%KfC9938@Vv&AJj@ZHLQmdA7uPUCv(4w}#_5D~%HkHbfX^}>)y4xcs z1Gubd?GbJZTiXD0#~tgYjfB4}mqXh^WR6LX32*E1f=TVkNS;3d%vi6})8% zkxl41;js9HwVCbuSBcU^%EAaExve<$7;brMU`Jfnhv_~qyR+L3#Ow|@InU!=hKb_k zoFa>_a7`&wNjqrSid}EouTdAdjtQ*z564^EJm9 z=Z@8*4x<*}(anWD$gC1@d;We$GE=2JkDGo!{>E*uNjAIT*nfE0ZN9xvt$eZLUxofC z@J0Js>bhg7M&-8gU#EX+Nf4-zHyJq`R~PXU;WvbQeP-}#HgShwPn)-pYqJlSPMmF5 zRo=(jWgJ;rl2q|Z@$da3;O~I&mhr8==tug%GJc}I`S8>`G)r(}#^`|<72(=%?1gvX zFB_(@qTGhJ5^m@?=j&emrr67Ar$cPh4ak8`1uRWS&Zjh4!^F7C7~FE5CwSQzej@N* zgW{WJv()s|a8!aw=De>^{gZU79~8%}=y9xS91@^(=j&e5nyW0kFQ+442SO3dtA*9E!iHIz?*7 z&KUrlp7qDw+{qorOxW&m=~+~6Qqh`Wsq;si-Gl)9-qaN*f(C0F#J5;nv&}q0;Kr_@(ou*m)f%&WB7$!U81er))CN- z2wXO2i#+9d?N7KRy2pXr29{YPL9oaUI#o-nfW#q`06&Km;JxEz9dFcG?^-o6wYMRC zYo76cjV$~*r@h_TQo(*ua1BA@UmR(E8nKpptFWvP?O$5?_s9PL5Op6H->~~pSb_Oe z9-_T0CKsMO(mm|6D3&6koUWt!l6*$^jj4FIQGJX=IXF;jmI}qQwecibVr-T%I%SPeQv6A0+fRq*7U% z_n7v@3AC@=+gD~T#0W7LJ$mtqY>LEf3D-P|QRRmTB&3ph3K>B=e8G(42AgeeLvAtA z6@JX9#E8a8?@xptvL_&Mijm_)=gb6jJWz>iD94yV&pcMqcaMMgbaJ%r#PZ{FxG&9` zmN;Z%g;hLeqVm)nMIk+bBA*ScfNt}LC-4=W?`Gbl%J0;2z`{ZdL7P0(g2CekSBru; z6oDgF8}6`A0ON|1N#QB6COi+kX}0g7H@<{FX9Ntxk(^+fNgyhP54so@ZVhPcjo z`Kj`>ZIy~l^T-45QO@-Q+TY|?+aUP`xac^h2%R}FjFVO&w2-?zk`I@W$69(uO8{7b zpS_B0x3#w_?XlKI;wZ?KcQ;-~TAN}|C+{Fpk7|h`mF3v-j1J&+saD)Hn~cB=a4S2; z&D_tetVr;t!yHz_bUabY^*Q0 zy-6$q$aT9VM*w7pw~?X?17vphpFcyrB4(w`FkUPoSwrN6y;l2n+crs&T3V+CvX$= z@0w1`mt@NETNQHNRzq>~REE@)^8`VTasa3Kii64$;gNn5RHA^p|Xt znKiQbvvCzTyea zam5LywCE($)RH)(<8rAu{3=#~P;PirZ>SW(6}7~BgqS0^9Vv}0JGRRy&N20f90TaZ2$lUo^|K_8n@P$tA;WMqs^&tCtqnR@T7WIAzG>^HBR;60gl>E493_ z0}vqR^{oE@5ZvssC|t25XNt6w+6cA@0c>%_W^2k`)tUO^t}3Cu?Xgs$@1{S)o@!bU z@u>uLC#7gM$k%qo^duU_@b&ak+W9byuoyXBm3S*V02!M(`9SGV-P>hK4Lg#OlDF<4 z>T*pfxLD)z?qCGxY3IoUH1IB)N5sJA2vQsvLgc)+VyXgOPVXqqVra{f+7rAIK4 zNsz+4=cuGIkmX=}sqR3sJc0OCm~UpYxJfOS%Wc`h znvPiQ6}QC1j=a+xp$1V>Y5eO$)nxL@|=)58i`?f^<7T~8<4{h zdC^vXf%Z&y0bBQQryT(me#U1hmbMuO>0Sx&ulAhNwTUCr{6jC6U%nov;57%uHb&=FgZL`c|7LM`+e9QL8zg* zJN8L23)AlOsUAc*3phJS{vOqhma6{%*Yu8dyC8>Y7!dQGt%`#8L|K2*W3&Ojz3Ra* zmEMN{@(wC!nOFo{f=)7crOcGC7y0-903oT$HfZNBbez7+n@(4wU{li4doT(_8F7(= zTh})6FvN~H>z_)BTWA6@401bGsvFD{;z^;DD=MfX1ZSmmx_-Qq0Ez)! zxdaN}wWuSGVp9mB_DxQ;#%Or>a4zp#glZGr`SS z7lGGrk_kL#+PG~e#c3e{?#T>0ir%x;A(Ajwe4hF1^{ix)j{g9kspi$gN}RSgl2UnV zVbh?d%O2$3VC&G;7;lvPf?#;(+N`ANV<1deW=28c_6_ewcCo%w*{GLJSTKWXB zqA+Pm!Q+a<@uk#K+=P-`Wbxjy=6u&{^F1sAZxJTZW8tWsuMYcg0OuyV&paS3kq!qu zR~g_2w~ZJ_FGI#ZTIpn%GUcS&F~QAp&Qj~p;>Aaw6DHSESte%rgg}gNNUF2kb;Jq> zLMighh8>1)@v44HNW`>-M|162Hk;GbbmF5PW+0ANkh5DL8R%+QAjt|X)bo+_si1%& zlCxwHjN+dl5TMI-91%`UwWHW_o`e%j;~-lM1Bwixqf(J@ah^p!L{Qs|%e0<&s*);h zWobwOxIVPf=66h_le0rzm9nDSCp;YWrn<@0+wj9ZdQkD8!}-}c#wsa{YrW>5fs6t> zR*AOv{LNsl?_wucLQC6%0OaPm4~Sn7H2(k#S+|-8m=x_9=QSV1pNTquh3sX7PCUX0 z13h}z&t5R`cA?^}MW?yCV!1m3JuA|};pEzs^gfp=$|YT@wN{-x$vkJ{txLt1?=1Ww zV~l!M5s8_yk$_0+?M*R-I4$|os_f*yZ1nvr)QVQLc0Rr^_HpHoz!lK>W)7WB?zEsP z0t90xpgpOqz_!r*V?8QF2uD1V(v+_hi;GRPAtc}g0B0Ny^e8BPXfxN0^`$Y4fLoF2 zQWQl@tMm1xc-*Ak)*3Pa1_6$=6_P?R3W1J;iZ-tO!a_b?;*~a$f$5W1wx8EQ5X%!f zU_-(0?@x{wMcnrJ9RbfZBcw_RSx!2I$4V9@c<`)12iC1VTdU}E)mPQBH6C&D{?0ao z#Ypi8PRQHn2&t`Y)5{VAfrFAoJ+1Ae9&V5X}gdmw3~d*i}$)?r3nO{ zX_cW;pkQMaVrV0Uf7ftN7^cJ^l>?;yylurc+r8Ne=`S)!Y{k(AdvSm}Qr+6Ju5F>< z3P?P{SP9DXd2u<#M`Bh3VULvdub<=aD)~2;-uLcW-E!0 z;Y}zd3XxouB=8C1moT|kHl%(_D*+rJHacgDQyj;v89h%*xSDOqhtB)JdvvH`gg8IF zAm^1Pntg`3Y=#740TE#T00rqJ?u2G>}vFdwO{In!9N~}MLX_xWFqkonccWl(Fwvf}hYDF1RWOB%#C>^N)^ADXO zeEo(hXrW>bT>Wv{oVKvD?emGxTDNOlQ`M0VHcSIsV_SkxZ1GA`IGD1&>|l@&S|&x1WU~X< z3TZt*uj^s0?P1Y7?HP!3QA&~t46(ofC%=ECIV4Q1Z7{*=*y&S#=@baxc0DP_nM+NK z{ug3DDrJvxh;!P8jobpz^x%U|X_L(aNwjz7oiyno$deiSwR)lZ+}a4E%Qy>x?0VC| zWkMDq*Cd*am4f`NP7g{?FqI^+2chPaR;`kwsP<br;CM@cbLJ*p-)qy95k>5v!BL(WpL1+7DCf zP4M%<9)%j089Rpq{i9O(OC-NMrB@wDrk^pr+FFbg$gRDjU90VkRDqs%5E7mV!6k)Q0a(z6WWT+b;u*4z)Vk#$h5X@H0_;n|~f-WN=op zPTG+hb8D$r?H6PMu!6qJ(x#2>CtSR3fN(=}H7pixpraGlt}0Zw7V&M6=ZyQ-ic7lw ztWPq%tX5lFSbuv0ZaqrkpLUklwx29zSg9Cg;)aeD8=__hKD0^i|w$z6TPdV*YE+L6gHf>->Add9en%PFwxXT~m1GPmQXU)iB zPIHfXsJG8?Xtf?}B6$`pyr5wEb*j?bNs`YX#(Jot zGn97fD9d{ocUmR92wTd_{{VQ^F?7+|v`=Y**#LoEE6r|y)<_%F6|C(}J1K41ljS4S zbQP+TosHou?v6THrH1RwjBOyC5Np!D4*YWQPlfLi+FP>F0yisjkzQwh5iVE)cs(lT zhUZvs2It04deW>RR-Kv*RuYCTi>FdIKGX15#oYtN5G$8dmw;7|HP%6NvNmFcTaT9& z@wJ|#J%|@texUKVImqKR>E8@LXbG&my+2=^vhV{nc@=Q&YaLIE#_;uOaCIo%uD#Eo z%$Z@f-vkbKW15mFBq&djj>KpB*FT{6r%3Syy3b{L91)TM=CxIjLITXnbNN>rQf;3; z=}I2!MvO@rkdGs2BL_X{Br&{!UL^T=$sMY+GTXl`G2e`C$5T=XkV&QoemOhZh;o z8O2}Hd|a&RC%NYX?w``CNybhubAqN4@lr_cJn}$e2*xOvbD(c1aCsG(r|NKAF6Emb z^aNGmBy78ZW17n9Gi^SHp5Wu7LQ9tgJb}|Ze=6rZN2IjuWQG8E1d-aeZg1_QVzSCc zeL4!wy}MnEVwj!6x#uMrU3se=_*GG8k&S55St(NqVc3f2{7E62{{SWt&rosAbq3*9 zCp)kY1d&{hw=%w<*ps0+!0AzD)`z=*w=|j2cosB@7Hxy6=hCWrMV3Wr*+1@mam}I~M?;4|XaS)Hp zlHh;`B=)VKxvXy(whpKsDe#BJm~fi0@kF_UXwdfO>mZp@qWQNzEhbGOVG_)vK*KB5xJ=yHW8?^UrgP z7U6v>Fe3#epdQrKiZ$T5-JZCoG;t{0Hxf@R>t2=bqG#5^(dnRvf*GR67#z^Sq#Q;1 z&{8EIBb<(;iVCE?WIvS=YEiS?t9H2MM+7dwPfSvP>KGXN_4K7wK#TJ*T=b)0Ao6fM zX+5mi;d@`8EN2*11obRw%EXX-g(vHZRS_>oImf3;Ao5ESD;$%M!=)C}QK+}Dtr;zX zfD$@^P63n*M5i5TBP2K?PNy4>dRY}&m&{^DdBrcasGCpZ2+cA1VNOO!?^4GZ0Dz*H zi4p*)W|X6rPtdno?FL-dQ#*3xYi;TW2U_w?)X~An{Frpvaa&M{ISe zE*T5E%bU?EMw;ic%S~W%qD;$r?qaraOJNfONl%3wHwBP_ZG-(*rPgJ zP1_jb*Vct8Uqm~*>Ozt#MhmGe*ip85@K!#ZvrlKShXI(Ao_q61;s*iYl&2oF(@E*M zH;uGflG-EStbh@od8K6q@e+a0IjZGIkO4b$*BvUpDXVkDMS&K!w;Aq zbHy?XgD%#VQauGvE1?S};CaR|){>XpWZbk&iJ?XW#TvJ_^`(w7r{{|`G*#yQ3gd8KPxvmcts2?Hxqfz#n(H$fpS2YipMly{)|0 z=3!_Xj*SYeOOjg*NBc&!Qr6_g48eW9>bHgzK92&GW&?I{+vYW=98D`2t-~I9QfW!q z^fXOdLbF2qcE@fGJ@_=pl6E*q7bCIhR_oG7S9Cx0tFda$S5MJ2Jq$a-)9>qJy;LyK}2(>dQFh9{>r zHN>eP8%7v);;X{0Npi<0fu5Bn=vakbPw^b|p){V}M6}fI?#cAoWPtf*+-+lm$F)y! zW>LKG6z8TJy+;I5G=5Q?h6l~XMR9Gl_r~LB>&|miE6LvK=!oj}86z{3wFo)JM{0a< zO@i__8+aM!n3G#Zq`c%3f4kP7B!q=%A9e?Ez^eD8tWj%yJl>M`2c6+eHWwT)8EBW4$KSw00aW-(M#!V(;YhA;O_pss z`Ryf#0Ja9wFFM%;Smy(Xm=(j(pMHds_2njXCfGy)?# z_5tZmy_d|1N`MA>iibAxHW|ssLOI13ySvmZt*Ilv^e4#4J4OE_}w9=r>iZwFlTPBN4cgMFbVcPL*2XTXt7N7#oKll`N99fT57CIvjPX z_iBdSiDUJvgOirVu~NSJoQ|fXUB2Z0E-Bhn5=}44Ivy#Sj?s4GaqHHs=nWXUQh3R( znZI=ElCpL+q10|If6?wC%KG}%`(}ASXww|zoQf`Cx44KB-1=gY$7&`w94Ps7T(4HN z2x|=vqr%=i@ehWt5v(OUK?JEh8uq`3UmLWoZC2A*RgPo9KBm5QAn*g@)}L*2HJgc{ zoQ4?22TJCZH8ppmJiNmu!sB&n((nHO0Q(-^>Ko|RYe1z>JQ3+u;+jz5ZcoGryT`ItdcfkbNYkOp)5TOOW}=OwEMM+=4a!N#MtX%0cb zQPQ!Ld9;$aQiY)IZ5N7IOrB6yBRjLja$4P_ZFb&X(AngJo@=O;2-CwC=s8i|xa~kA z-mTAC7O6dBf7L}OrWB}m+k#$4ig?)u{@JXp@_pm0O(F>HmWbnDd(W4ZHH&gA;xISfyr#RB+g6fnqWT7^D%ff4IAI%^*ma z=X(+fz|SIp(S+C?hqk(1B8<)|~}8asLB&V7?=2dT4^y6$ z8CP!kWGs4h=}kdBwYhOtorlF7LL$u=&UiWLP%J4kGb>}zsr;z7nHMkSei-7XL2kdi zW+Zk{DjRAjcjQ~W$W5BQ+<}3UjP<1ZFPD_=K$d>K`yO2^I3ahA~sz%N)_FpuopGP_M0tZR|De zoRYE(fyk!_8_NMubKiGrYusURyKo&vNJ6{=0IBJkr1`XVCi2jYBWQ>Yqa!#zl)ifr zv&#bqie}NfCC|{D&;)A3_qZA8dsQVE*)p6~qpluo?g`Vq5i>Ui9C1&GLSp&uInM(f zX%vW5`EE-V=qfptxse*nLh6p_JzN%8G6yKP|H5c*`Et*?j5SEUS)#Y3WkjD>D|3Pn4c>-k7nhe6tb= z&OHrOc~$H_W`=<;Na4utYObbbODQm%@%+VTn}}pzEgNsR9cs3-ZyRaO-eY#^eZ^E} z+@hayskG`V_cOdCkPQL`543{W{{X&?T`xQF1VfI5W0P547=qFCI6V1EaNOtpqf^Mh z$YHm*AxD2&n7w^_n#P*3X=O=4isf5z_2g47VojkEJm-wkT1N{4WX|)~EmKO702woo zIp?9FO6tf<-Ib$pmb!eBFWrp*=N)Roq;bdPJV2cN;CQAb)Iv2#;oMIQame?fAxAlO zC~T`b954V{VoB^WJ-xl(EFor&_( zZZV$btE|@%I6hwl^vzqph8b83LcrrYeJZ4o0-q{7OZ3F*Jn<;Yb%(6=YnyH z)?{0$H*Z0X$~x9wzox(kpA76>dE<=KIzFQm{{Xsj-eQiOD@MAbUS4&3ZfnZ~(FJJv z^*mHi8In_&xc4K9St0WjHuK2H0QIP*YiNlQOyGbz9<-vnB+Oz-B=af2fE~Tb6%D>o z*vk%bco?YJ;@$hHiS)>)sf3-)I|8Gn9K5K~;@?TU23vBcw`!$y;bLvbPs_j^>g@7a zv^y1;w_;6GniA2KEOCz2QHs91jtzA<{Y{CxbLHbEr_e(++8ktOnuk~e?Ti6EPg-3W z);qP!A8c1d{sX3Z#oX-J+Z%r^AUPfL)~njbD0BP2m!aTO?dDkG4T5kp%_Y2xET1&TbBXMolhAGzSfpfN$l3Z+c1FYv$2jlnNlMYRkfjJzg`~7Si@-l0 zZd^yE>xjLE{MV;x+P$`^2)WbcN6O>{AmYAGWN4py$U)%dx=#pvM%Mf6(ewTn7<=4+Q6>R~n=& zqYgs@f=H>BQ0JLJQ^-9iX~87-Ftc3?c9#=~nlOuxOw}o^1UCj}fqgr5r@|dhH}Q@! zPM>RhjQo?qs8Dd7kd&HEH_)ej6yiV;ae=^I^tLT5bAu##$MCu7S8bt%;{dVFcqG(~ zVFv6OK`qzi=|h)B*Y*DZ3{=Wl07W~CU_hH(yYj* z$u7_goO7C`qg$j_Xvs73qZsK^Gsd9iW7j6RG*Z*>^E~vFz7fjOgvd}q7#t2NwZ+7$ zxK$jED3xx0L^IpeiL3xUe#)|wd!*sf1}8bwI>!6O`~uHIIa z+4PBh=y(oJOlJe!Q?@=&?(>gRP1=gvmP6K%lpKcV)7pz&+qe7xcVv;I$`8s0c_8AK zYbupcGJ5+`M6s%tSr}yWBAlW!HyH?GI^w12sM2W!JW^V%1-h{##@X`9Cr)_lNET7|BhEXX)QBQ0fafFB^`tV!k^-_5 z>zbEoA*&)~Qu|!s=b@wy;Dz#l+D|y92@o6!4o7Nvk~JKYgVL3>*iUVT%extM=jqm* z1MUaP1QU~*hjM-3?esK$?3^2hP&vS&G3I&_n`DKg2W#V{A~U+}kb%!piePw~q>c0< zmP2k-Y;)I>nk{`Si?!seII|}xqv~o!xwu@cQF4Ee(xDO{Bnb`*_o*z*OCaAP9E^jU z;;tQTj4=uF-RjE`$0l();Pv91sPefY06@lgr=_ejVUV}G6IN~}w6lX`M6-44Nw(J4 zXA_cgvLTb~o~IPm+tYD!!Dx#t zf+Y@Nz$3B!Xo@(cAcY%<=RN8uTu1_$i36r6Mvf^@?+HG_rcrG)X4U$WPO{qo=th09 zO;I#}5aTDl+9NSMgU`v&6?JX&#*bo3!1T^3>&>bMEfUv5KIxlwCJIRy;9{8)JFyO- zMls3iD#oL28m`T+?A1ia6a#CsHhN^$U8i!EsarzAKt5s)HvXcaSQN@xP-7f}Qbv#n zJkv4f)|rUgXg3D~)KKMbLBjl_l$FaYYNy(gH@b6^4n}>bYd94*8L$ZCp2C6lc?Q*) zjt5?uq}7l%uC1yQ_oQM_pbmg?d8W#*C@NcwbjE4XB8FvifsBGrT5z{al1l)4txA(# zL(=ylRT1!sk_Q<*>Ub{Zz>TfcuW_D~){Yp^%F-4f8FV>YbVKt?*$^Q;mMWNrtg zLbkp{bQoihw#0}Y)+-zee4!8BPa>T;MG3~MQtXDY&_Qum(D-mHG29;?4}-c zrwnj1YFwt|YNf9&##~#MaH|j{dXq^6vbG>(1D<`w1}LOfkWV9LuoTu@xH)18>FHNz zdm`_ueTyk^CAK4u1OW9sb5ktwlb3)Dj!tumpc38j<})q{z%^nPvx-0Uj9VOJ@lzEW zXozr8?{Y+F8sU}K<;NYlsIHY#Uy*X8XCTnC*~^AIfzPKIrHP_q8aZ-$0g4)HU+bWh zZ1&ua7z~&ZKmhj@ab|d9@}iYnKX`5Ch!PUO$i(Lv3)-X>cFQo8i2xsz)L>U0ZT% zJu(U5-pmx9a(Kb1WLL3-Zk1%mzgmL&>NimoY*+!_qCaN|fg7_9ptU5VqiY#1?3H8} zExDmZ9dWz8E8EJ)B_mZG&JAZw36QduLC}oU(Ax==nPp+O?t$r5$?q28`-ynxckb7K zya7eN(;nxDXBjy?>SHyeQG}W%C;P>!5fU*k6FULcozk+f_qFa(x$`{6kV3c}jwlLS zc4Jb&aqU)GSnbrXO!M4yq)}xu{h-K0dk!h3%=Rmv`AQFS8is;fAjI+3vTt-7v775f zMaLy;a_$)AkT{U!{{VNbMJ2fa#>Lzo!1G$E+BUX@#%(*M%$++}lI?!V>J~wT!K-eP zOn@>e$6TJZOHt6F4sI=3<9u)`8*P1T-C?}QWgM~ZPmxKkRBGeQxuDC>9MOUjJ~P}? zcTFR2SVlcD#abGKcaSWgWPf=@B8x{tsv9RflT9Y#k(!mt#N0~62!ZXzD!h{#5O8lkJD+ zC*Ks^8B$BtLc|l$irZ)=cFNqW>f(7es+hPV85HEp5X~a538zPTKxC zu5yI%dCxV3pww^B&V;)g05}TeG0jS;Dw0(P&FfJ@Vv$0#whwxdRv_4EKAhsYCCqhR zD_f0`T?)HIzf95;VmA~31*Y6Fwl)M~PlN0o!= znw5lPVOWfQw5VezEX;A&nxy2q3ta}=T;E$TXaQCY*w<^}AB;N2k+RoNK4Jm@Cb+f` z?%uB4^`?<*_&bRQzokopnzKhHCj~z$0eyoT<~{CxmZjbD*0m| za6zdiSs9KZ1B_=PxqS=7`hKGl&1G<82L(pz-Ajd$0~aGa{&mdhxHQk3aQ1G+s9t!^ z#f^QJjz1ceF4#|rB3$PL3eS7E;2`;oLH#OqOL^0JNOwOXv*lXsOID8M&0g{q)7?@4 zTNxxC^~ON6&8ZLI@d+2z}EVE$t#@Wpf$^A`hq^7JlP04x|7nglsO@yzK5fR zR>4W5zp-f}wNm>|-rXv-?eo9LBVGqJUG-~LjRItlFi1J9{Zmu1v$c}y^618aNzQ91 zLtV8wsL^w3+p=9pQ#N+bJo2Ii2a-lB#(pXMSdq)=nnZz)NG=Z_N~7^h;|SCxeJ4n` zV;Ch%Xa4}LUT-YIS29mC7A?m$>d?abIHx6d{{Reqrd5>2j8#gz_Ut<1X|ClnPWfVc z(_%?joS-=BGff)-BsnAU#W>1<1q9@p?PC*NTpD7jhXlMq*lN=kn>8?AZ$j&dS;SsJJ_b;`idEw zfT}sy!y$H)jw&qMH{Otd zImzoz4{oCh+=b(sn>VTsYfDBuYwi21lTKE2Axufvu5(ORiE!Rw03Xhfn84buexT>^ zrk0~kH*1m;FCQo!@sUlJc5$==Q5S$NUCGWk9mOe_*60_z(2-r-g>)N< zz@-dG+9F(MkZQNu0)RuBJlOCFbCP;>qm|z5Ev}`ek;;WTThQj86~v0latL0)bQMfb z7<~M|gU3CpOLr4Y-_jscj;HXv)g$ z7afI9Et+C~3bP+<9cFF@3G0zhn#xCg&@Uu(6&u3@KkC`J9P>*Z!M0%A&pj73YV}0j zbrKNpAKu0o=YUO3CCsrfDxp`mHCpk}rZ*D-ZH3+3FMMY5Y0!Ib@{ge+X9O@%VL{K-eEkG#}I~4t0aYj0I2Cb>oObmoSu3Gtl32=yAnqLTRub~=NPLw{ z;{!gF?Uqh}lfOTEgGjSl!Zt&@2a1kfWqT6pX?4(u+}|J&m_mYZNi^dWvaaO-fIeeS zx|-1smSsM@X{#(Mz(P;Yj;5RUR>Zc|p2ER#93LYl;!nykQ_uFPVcq16b@^MhG2^t2 zgUE8nsik?E-A9%_Qge@5BWu|rA2ejSNMXC47bRiZk-vF`E1v$fI!5x~ouFeF%~!*=5qA;oQzSvqDaZ@zd8IV%bhaVea>cAH z7@{WZo~Ekn=`&eOHVvb1PhG;S8=H0g+)UfJ#tl`~({`ORzCZpQVEqe?vro?<=EDu{7mpf zkdL+a5bg((vKl1nH>5u2AM+He)KYR#W;A0^jzI)yn{mk)^XkUD@gyw(dM_ z@Vejzy3ww!OLs;m6%2QO2dt_u;Zyzq~REF%K%O_V6W$mCXg!4;q; zNL)5KBv!W3TGsM4g-Fgm>n>@okrrtHJ8}W2?&mjBe5f;ywNlmMx0E!XvgbV2i0-T& z>w80m@6Al3CbV5im8rJvaj?lcK60e`9`$Yu$xOuDL&snRRJ@i6u20!wDx;?~vEJ?; zRE^JXY7$mz$fmlY<;;zA3A%|@N8Ra~h8d%2JgFZ8_(>hAdrdyx?0KJRCA+AkmfF!K zF_dif+-h#Nwy4cG^efM4bB*yJW$Tb>@W(45l2;0Ug+)mrlHB}_$8ZfcW>p*l54|?0 z&3A8*DYla-%^{C5xC{@iAeP;e=eHxC)cK$;`=xK8#UEyXDvvRV&mfMKR!v;FH0^S_ zg_VhkdUqz3V7ql8P%-}iWQraLA###PNa{$Z#PKpSK`Zp@OJDNu4ud%AjV3A4YiH<)kRo+*+(6v!0@2St<={n|+f8t+0 z;7{D*nQO1jZhVW_e764a?rVPPNK1fa-JasA&1YqIx;Kos9Fi+Uo7Jzl*Pb(aleF4rYCh&dJG5b5u?Ukp=7WMp4`KaFf z$2sCZFkUgh#(2e5v65KlRzxI&*w&7-;k{A`j$(Hnq*ZGzA5vL^7)S%wx*S(2)z23j zqhvO#s6?@_3m5{Xw*LS}VGw{1dXhT{f~xu9Nnh`DsUy=oweueF3GS+E3AsHC>DGs| zwaeDeDOGHAJmiX*rICS5DCeNN_o;fydLZ{#QR9oRIxt)o}Aa|e` z$`Fpk6UeG@Ye6Q*2@0tw6!X)iM#e|^fx#UxX?MaD<e9TC00v3P{#EZD5BQJa&l$k8>Gy$T+4oCyt_qlXuv)D<{{UZk@p#<36@rzf zwC~X9d`WRET3m=ER|Ik^htsEJ)CM9}JGeQnqg@C4J>FSVt~p>udG@2?y%WQ;z1`i& z%BLgVvyCS|hgalvVClNJR~V+>M0eVkh-@?q7Qen|(NS~3=Da83r^ajV5#7Cpl0w1` z0aIAN6aFk*_`>Yj>GHb38;z&0*11$zai2Gwe8(MY(WQl_MQXJ^qbtg3;L@F4X8!;J z$D2F1n92(`QcXFUT<{mK1bWq0bvOaoZ9Q{R31Tgr=ke)UG?UdH!*1l}Syb-cKJOy} zfYNQ;0`hT;^Htx<4ZV3Io+(7Jfy{*W=|rN_v{7GcLc%kz9AutHwJOOXlE5nr{oGY} zr$T=D$?KXVmN4gQ5`8gGmzmfV*q^qA;X@J! zQ|VHo@350ecPD3?jIbxto`zE(17OI&1o2h8$YlTq$@*fQ<|sQFQcr9ShJ_TJt+7&* z+U19mMjJ2*&poJlq#W#D!mF2z9$1hmM3InU1dnQbzC+taPLC|S0>0l$a+hvcjGW=K zRZOs{$IZaTbJm8MAU1|M6qGLZ7OQqx5A%`$A1*)?2bXD8P)}N_CIsL&80kspsKj|A z)caF$Z&nUhMU;|2Ss50ZS(KcrkVk5+W{464W~2K;72Z!HuQYo;XRtXn8x~BmWUHtn zw=^u04pe{*RhDFB1xXV9%F>0lBRLS4OW-Vd~X=%rCYGJgr+1+wlXQd zaVE!6+Se)}EO6mT&m7h0uS8beY13Kh9sn;0W$ zODZ78W9>-MT}F0!N=I{=YcK#6U@$rnO^)X$1;X- zzQk1-8OW*GqgXbE=efl;7@Kb9C(s&NrLkPj*F;hy#^Ihm0mkD>MbncZkQMB{l`ZYB z?()tsG1aOBA0up(liX6}oSwnWbgWpByvV>r1+nW=TFNa`=8ag9o_kez*#h7u3F<{E z#}eeu85kav=m?e1m=DcTuX|W8?)efy z8?ycINIU^gk_(2D83cM&t7{n4yzvZR=LVx_%+J0dwS6h1lhDo0O6;fw%rCp;89l{6 zSZQX_WD~}fhq19utT`FVdZ9gsuKkW`G>EGH#l}=0A$JHF) zhHYma9=DPhNyvQiKfcwgYp2g}xt&!P*N(ND;ft$Q@b$D3yC^&I!?(`Ww9;v|(FBI{ z$Oz@I+e*skKaJa?rNLo}XDNhWig`coaQ zEv62#x1c7S+?ujUl_vDFD(XH7j@<9q(G$)=rdV3|pHIW-y5zCrw(8WD_U7eBn{ZvR zj2>}OY?=?>tcM4ZF~F-;syL;4-?&{)Hj+)3bpHT}zY}~oyDnKTBRS$w5A>}O@vlJD zVi9<=!HJ!`%M)YyS3Uisa$jY`Wl8D94`*R94Dp;3$jxS>NxSk{`CWAKv4g@;z1p+x zv^q4^{toMHn{7gC7GsP^3jtF90Kx~OYLEW_6#oE=ZKTiL5Ax=?>&**AE?dgaqSZT% z4%9GxGHGLB)G0M?5J|Nry=>R${{Rq;3X51&e>2ek0O3yf+9@}~3>PX#%3_&M^{Uq& z4}3#lg|9Rj5xVCY701|J_^(dl%fxpu`v%CZi%%bXMz&HC5-O{zNZ{i?U1aAdkYj z^ofPjWOKk77^$N0SBss)CX=_0tiV+C0?1vAh$ zK~*JW^n`V)O+O(#0lfQzkn>QNwna>LvkyNMgH-e)r z95KAO^)-ue;hi=l1>M)^b5+|w)4|-V+kHW+_H^Q}ul49@3N+eRlV-HuF43aq+ekzG z(psRC$1_ErCr^O}I0Z#!Nut?80ZCbodUM4`Hk^V@%EhtJ6Vk2_h40I+nX;orEAC&D z$6Bim!C_2v+6NU{e;Vr3CM3B41C9U{PHjBgF4HE^r#Q!2tuB&{Abspu4wLbOZ4RjW zG?K88Uc9*8`NvLptBH6NU?9op*{DCW;tR{4V^&hu1WYK--gS<5cK z2pBx$HD`Q)e2N%)R%{m#=V4+GahkBR!oVG1HnBSpZ>? zj>4-M!w_&lCWW3MjJfBp6`G2cmfS^=E0*1mc=e%Vc0Vxyjt4zzx=#`LS3Gyk26&4G z57V4c%XP5r?yXA?B%>Z-7(E36nX=gcae-CE#B5G-Gw)0GnD7F0JY&+Di*I66YjVm- zGe6xN4CaX#s9m9P*Mn8X#BqxH72c~{KvB~Z14waics#QN)At6 z4H8Wb;0Vdj9MgQ*9N?au=QX5ZEv!mbdK9m0OoY0HEJ4O9Eic6$C-A+`o2FhBBeI^g zbi6H)K_@(#t95M@kA+eWdFHf(YFiaLaH$rjsyY~cKlt2Rn`^s*+O?(GEfM=QSyFM`LGnuX4`mBP5j_dgrY)Naq_sz~iMtXHC0< z6OO#ndC>#8pFY&(3#}EK5_eiM&zSp&1y?;e=|Gh2%!~m&c&dhYK**Dp=qbWjg8_`> zdiAJrNnL|ap=~ZC--pHk#~ta-EAPqClf0;9`G>D+q}M1Ia(eYN#=DFS`6P7btx~#HNLr_I@tw#3k@EV|mym_r^|Gf$ftE1>|GZQM$7+Y5Fa)+Q;e@YYbeJ0GmcHI38IzEVpO+4!18lMZF6u-FhB_CO-7GuqlP^C zpU#>c=5|<r~xVH7)aQ z1GPB(7qPT?o~?)&M#RK}a6Y_Kl$*Ex^opB$mNZ+u5*@FSdx1s8f=MRjBrkEEDW}VI zVK)@7u-WI3A1`vYI&)E$nEczaRF@N3!l7-Ijykca__|yqoW0aZdIYLo6biWG6qc|~#7M*(`kIP4(BX;T zWS)OYa$FT*Ax=Ms+LBJm3ex4=w!$(nK=|$j3^f13_`~Fd$ZpDHL(- zk0c)SwOUxhe)g9Yix$}wfiiumVFjdQlN$#@4mqYr6BpgE^ZHQ98JLL)37$91P+oW+&IG?e*0C{(q)ax`K#%i@l<>)%AOpy%%xAyf;)We zS`Bw-stnUN10<;LO*yxr(xp+o^efEQx_pS?LlSwx?Ni!cMJt(g7>NWOst-zK?ADhG zKFb;Te~UF0t(2GUsSbC8_e*uA)s>nn-Eroby+KJV7FsILJcME1$TpqbS zDTc=W8-Rk}47~>Gj_w!$OfTbOAR#S)yXaunL@(Ka5*NTTZz&j(KyPV&Yc8S z>VV9|AUGr*MLKwNbt|0kD$TsEu?u-4T#n>Y-bT?b1RHzg zQdz@mI_`cPdYX4~j;KxDYw|5Rw2%OTGl9tm6$3_m!IHTi^)gug@U&p#Z*%(6+RGGj z;%I?6>rka-bgo6*dXBcZnio4)XzDqs;ZL*^Ccr%gX&!4SaVrdMJt+HJdkU;&R1Vbn zTZ+(@ukew~(=4Yd6rSKzQzVkG3^#l3=A31YRxSY`F9e#8d}!i9lHK{CN!{oxIJU+# zw*&WZDi5z(uOt^CzIRiTk~3B&duC$tWD-dS(xZ_g4dw%pj&N$A^tHd>l%2YajwhXp zG^#y0>S`J7CW!1<)w%gdHEmwSlXsHcIC`%ktE+R$4-MZ_K{zr#q!#~rDm>YU45nrH?uFjIy;APy-IL6sC+{xiaZu4o_*^w+fs-fg^p=T z5_+U}Q)$IJo2fM9WE9SMVM>$Avg2}$^{m+LqGP$HY_R!=J*f@c4JI71Abh;^tm7W3 z6>UG@8b)VU$Ymg&d8HE-Tr;mc0a@#H4i8c4O(R{yyZ4;>QSV;-prqGRP)#9FH!nfb zk#1cd3R51HoG;P240>^oT41}21O{@{lv|F7ESk{PYlq2PsmS%DHw2IaE(q#PW~J;o z+6xi}IqywtxK|9ti6`!ge6O0;1eLtaHkwcQ>a>kP2^4i1cnE#A8vv8 z5+0rC<-bB@DJ5oTH12XkuQ;YV$~YTvd*-vn+&l0a2fhzljjz<7l@Qu6Z zTxMta!>8hTpi3$M-zgmks*58(L}FusZu1e2&()_0Uf1sd&uF7#B{Sw8gn+ zB}0LpdFfRkcA31mkb|CT$kDF?ZpHx_r^)YasXWlWtQJ{EB&h60XQ%#=}Y~SCJ1)z&O225JFP*^l6JV}x|fld&p6_c%HZcHJqCKxE}w=dPvc5-t^6x~ zbop7(EHC8x*zY z5fDo9b4vWZ2$mt+-7(|PbxDtu6+s8rnwB37UoqJufC2A{*$QEocJ}#?ry{K+kfdrt z9mlT~5^_$~)1j2H54nOoDC!G5y?PHy!Pf!PWiZD10Q%QwtlkS-Hapb$Ccx!X7d@+$1)w*xib_-4*4 zD>&wLVYqNR8Y|hWSSrccF09+Mx}MrRZU>HsrB0K`WCi0NH*wypLvag5k0pT5T=c18 zcq3hk{{S%Qn&fumvPYlGCY6iuByT1rlNdZ=opWv`J8eN>jAWY6S9E|WOWz!*W8WcN8?s*i$ z_FGfrlwt=PsA(%SfjGr`qTA0p7DJt^dBr|PlHVrWsV&qRNN;UCylyzC<(||cgvrlb z(n|d_V~W&~AqF!cb={7}pbBun$&z{v-6>$Vz%FCXdJOiY@?kE@;~wX=S2nKb8@F9O z2wGVqmngtw{Ge0TdyF)46*=!uSGI+=sRg@wQzcfCP|Ugi0C%-C)96+1$*pYWor@}g zft-`ptix`hh`3d5dBMju6{L-E312gA-Z74}(QuaF#>(FLHIu#e^B2af*xRdQlHhqx z6m;a$+*wB&d5d0ibY3I%lmi zYs;tm>yeJ;rkdSCl}W%I{VK4HHw4^Ro}_dFl6<`iT#a)wLFY`Ho(-d}M|yNdNOrIz zXdabmH3u>MomoHtZsR7QmTO(&BDw5H?MqiQyOVbQLz-u1-V|*k8L1)yc(w_FB=@Rv zG%mt5EPZflSrEk-0rQSqoKtaJ$t9?y`ZmiEK_#-5XjOqY1k~^(w`YVwj)tI)>(2l( zoxL%dvu=rh*#nlln$dSawg zBqsoop1jmrPCA&%ZM_(=+0I-dINUm9;*#RV<~C+xgoe*rRNEs05s4?LHDUCH35R(F%=vpIF=Zz_M<6?#UtDY;l34B z)5faU8*oE$_k}uXs?pP`{Rcxzuxq+G4+cDwcz)gwARLJ>N&f(Ct3cRYTjAtX+n>5k zX82D2);|v01>7A&_v7!iUWWR4pE5TCrD~M9c0B~8(9lasW3*ynK#Y0(y4G8)(M`S* zpo72$tUjZ4<+O3WP>w-0ULzZ+%q_dK1Da5FSA9vR8Cl(vMRj#Fg{5K`FC5fY>wc}d zr5jIt)KIm@o=~iZlbW95-_45!8a6!(=8JN+nz5vLV=Fc~*X)-th?oU9<}5XvrIxgiJ^9<&G)$(UpiXQn};;KUzs@m9!T(E4GBO#dUKR`b^5Bs9e-c${Pq* z0CuWPbX06+Vo!2SrKC;eEm4r;wj4Z2_MnIPX>T z^8+861_!^Pt8XkY6%fQSPX{zO-L+#D(rU!^-c(Rx;@lSh0Ct}f!yG0#qg*iVI#Q*` zdwrw^e!`hFD?CaZ0D8AQ>o})vjNZG1cF`-H%B6FV1ya2)Z6@e~W2QYS^__~B^ILaL zq}G1DZ0RloXD5;?NOG~o%bn_1mU-@YD1c*=nrv|l70+IoqSYWs$&j3Or%ISUWN3YI zX{e=b4SAc;clLIs>Ah4H9lfcZVS+8cAm=0+nj7~kw3f$lnx%Q=7c#1_=Oj~#a_A_^ zQg&=tHx2_X!_IiCFhnMVi5YheF`A$mN!kIyrIJXNKI7ONm_ox;M%usuj+{{1ex%F*i~vUmHMz1A%c&lOnwb$$lBYa&sM|uXmY9sj6@tT!13-??J6m!Y-t#FFZkf$T1ATbR2xzD$1AG>E^ePW`yo_sZP<(4xH zf!dZm00WOO^y|B=X>U)vxZ|*(+(ME0LM}&EB-2rSiT3p+9m?(DyCnl;obCC!=}rE` zw_X5JKDA`I&cY8`Hk=*kK=rBR(_($Bwr=Hiu(ePE!nhqpN}6@Jo3in?J7S#vTdxrjlflIc-Ic5^ zdECvs)8>Z~z!Ysiom3>!;~Q8GI&)0ZwPZkTucJ8n^s7^axBcufnHQ+1rMA$RxhH42UP&E> z;G-kCG&JqI=D-AgRF1+~2@!1_z@&~CS$9h3z6A;@D`sk>wz%|=ACN!Z_o$vW3DB0PdO}At<7U1)^4u2|hJ2A;&oO7CLPY^(?q;tv7 zT4;<1+%j@8%`RJ6{{Uas<4)^RWVe_Qrx+BImq5)FWC7S7m6T%S$y{d z6zT%%@sJj55;0kEAd$j|$;sqqyI_=KbI_)gAeGI}2kCQOU95)~9nE?Ly2or43L^pc zfHlr|KT1d})?lrZ)MvGCDy*X{tiI;CX49Uh9Y&=qx1nU+MqBqlV;w5ga6>3r7YIP) z8qbE^3k4ZsI%c$O!18>*DUKJCYZkVDdCx9e+ANUS&vrtMr#u2X8lAMUXC5WFP)G3M zptFYNC&W8|&tK_IzAEpD%LANpDlFS2xhZNSu+wI)zSv0aGo&5SWS#;{=*yR`EP|5|Dk*T4eA;6P0ks-!zg_ zTWTilWSG%wH2(m-j|Uw|sV(JuWGN(L=58r%t|pcv4YCvKlTf(0^U7VO6-Qju@};=- zoNmWG&yxQDCI)zFOPPrI!tmS!N+GxV<2-Z4Bgf{!kr5ysGBH+@a=4?*aj{DvPy`{e zcqH_xadEtf9d@3(O;w6REPzUkfOQzF4?GB=Vui;Xl5CY-t}Fp|2oM_o+WDi>$acBrEn#^>YL z9VtY?n|qdevEqoN(rcm5X0^Vhi(fL@GSN86_4TJAxj-k7s4LD*M4&{!I42pwr^hS| z+lrE;WCoL^d!@Kw;eMwIoN=P9WzrwZp&_G^HdT(;5Ak&d`P>Of_TGm z_|}!w4P|YS0-iERY>`U$mnfv|G?ViwB)0+g#VA4#IXR@cp8jlk*CFzG^c1q*tieOZ z0LS-wQo&{RSw*5}RhK|h^ooA~t<5^6Ic+PG1S zRTZ*>%;wF3>N06A?VvbSw;+y~G^G^v>MKRdRyp3vVo{>opSXI0X|P)Xah!mi2Q^~X zOgFHAsubg?Jt+;GmaVpBR#1Lc4O1IEKLAw|R*NrrHwyp}ym%c5>q!#bLAbC+$mE{Y z9h+&T_RQ_q_(`enEi~wpbW_MOGQf(Ipq;h*j5*ggD=C?-B5la)*PI@eVkeeN$VkW5 zt9_ovEQBoWjz|P%tU(-28pIHd$0MHgTBx$*6y}XPnU|*=0bh8!5-VS1U`){urfhWvL3gqLxAk?nt1lbDi6}bS9oHQI}$?Zt0QU zqZW*KK-nYKw02q#n$J=Tg=m{=ASCp`s3es`?Q_WE6@ExUo=0j)Ak$=v4I3B78O=Dh zucNTkqZW+QgZ{1fAFV@n^F}r~Q@haB(`o=K3mp7R#rp7>Q6yj)2w;M-hQ>yPA`=7X}iHDi@G|zw+n-j+upiJoq~W!Cb{he zlkHp~B-cU$u^W()jy>kd8ZMm_)3{p!D^itUwKk)83j`A>PPGzIz&W(?V6RbV-IC zN8>=;pd*kDd(?5{4>8vn?V3|GFT{X@o=pz&jjYA19s{$2(&L`A(o&v5zfoKm=HR#qzcp&79$B<9Bq(ubt0U125O%ZLaf31pfO(63*8DI(T zOBy7(c93TrW|7i788)Ax?NIGTV$40xDMHdo>O#Ag<$L=yn=KOn$C`GTe?7nYHPni8 z(34X{V+sivADuyUYi}@S0PY;|R?@Mql`NSqp#-s?Iyc;%u~ik@JwO=8UbSORx<_WQ zxZTLY z=BmxB+ft)s8IYg6G1y|PMsS012cD$V3mD)C&m;7!HnBo6yC8v+Q_7>SfA|E>Ph>mE zxX$pSZgW$^EXFYAZu|_=Z%k}dJ9FIirzBCc7g&!T^qOgr&3C9Q(v>BT9{s6SFvMlX z5AhmCjwwD!;$!S-?t^GaBVn{~1xrr$VslJ;W+e=>bmu?Pq>6PX%q|NPlkHF^*@zn= zW1j43QV8Al1n0jeih44A*Qzw_H5p=35!VB#9OkO)da}c0@+knao=K<04XQ$2n36gJ zT(^w%7{h&@HDQl_lvAefWK{?$PV1r1-AvQmysqPxCyKM8+P%f%BAkNVeJYwTCmS$N zeAiXrT^8C>E*m-QFNJZfEo}sG9ASCynzX+#$zVo4U@2|lkx!Pe zoMQu;vjkRgqZv?!>^4q zGt#D8a|)=A7RGrey-b#uW>T?jF0SxIMFu%M(mlzYGagBDIOU+i8G5-NjUq;f5iy4s+h1{p7N53!Xm;j!QSI zG>Uwtv`}xh6HjoUuR&CA(o-t=Bo!wifTwv)g;LlbPvufQtg%DpXCQP0(G;Th*FcQ6 z^DEm%@XB6L8|zDVa?%4H{4dg#O31!CS4;eh; zGzXSR%9rQ9X>E{vc+Cn^s~@_qf5TFzJMV2-E;i^u>pM$`n>^Fux0T1wE(twpxRN#nhkm)K zt*3K0m@TrS)`?wgfsIIHS@4p9o~(OQ?yTVGWDSn>G}e~aSaJ+xayIkLK{b=9*dkz~ zoSJcyYhHw=oU|*)ZmlN8lboI^SxolmBQh>C=}r3t-e8efgP)h)oNZ+pmT5@?_(07z z)7Wxq{)6n6N!XO12i~kt6sqDjm~c7bpo&=IY>Q?sj=d_vNj1!ZUnB+SGAeH?>P6d^ zkt6{kP36llIRKimYkrJAa&w-Bm`0rGu_G+U(411o4Wbfda52#ZClz;d2d;(H0(AyC z0X@Y{9k6B0j0wj%s;q$2&IzkbG;biKT7-F|4~JT4|W6|pcM zEy?k0cMDr+=NRN+PHO2pHq9JXLb(qW->TrrK+A zNo?iGlGVtKM^oOVww`BD9!DH{ZsD~0Yi6=pDo;lRP?0omC-YDu*hxhG7M1XBi64)JdcQ_ zgd7ZHpVFn$wV14~cUxNtNf;r!3bA+^dH&Nas6}J=<;Y*kxj^FlHz zgVL;hoovSMl=0lsTsdfoj@xzz6;Z@ejjXMl@G^SS<#ODeTE51NR~FKs4Yam+$*Q*( zQNrbBi?4O;XoArqQzDY2b|IP3*mf|53a*dwEbgNv-H#ABu=*Gzm?73D@G0(ZE;f6$fd82ns z=k%+7WxF8r9|P%B24svjJ06tAbcHs_ocrdj zNiER5>+W+ND-r}Hh|O~&A+y2vuA9apH&R4L`U>VrU+!a`YpR;I=cNzft20MJ5_$Z3 zbCX>XiGp(Dk)D-<;mB5Njj0(YJR0a^^2QKEat01NR#Lt6IqNm;9mcGmE*ep|j-He+ znK|LW=YnXAKrk8-4}NK082B;5a1X6JHzO4^^<#^On1+;b>DroFQu~%n`ifzOAack@ zJolyj)<{^}>yt!NDc%IKZ&ca82hx@ZUCun^Bd}pf9B9CnOmXt&qjW%bDzML`38>n{ zE3#HrQb3So91%@aAmOA3Jd;Eb!sjw0V?6ciPLs+{lVRX=&uSv?plh-a$l2K&WQ_Bk zl;vpw!@f>B=A(`!CvrwceS3;|NC^M~k1SG$1Ip(7d?ZA_v^`t6{ zI0v4`G>sa8lDP*QQqc)(u;yQxu_Ew#=dCq?35Fp0{V7Z_f&fA?dI3oApiC+@M|0k( zw4^kZh{R=+i3K9Y&e%o^*yoy)?D45AQy#dcx-4L~m7aL!q4Ou9Tj)c1Z{;wQI3x^@ zYPD@}H4AYB#diVg-m8_3{&iA#Ic9b{mGO_(k~?K(Bt~+6xTR>B zPFfxZ99C~cXLqAS@CH9P06#!;)|+$Zl`ZC|Add8q!b4yo&fJE{;-5TGj!b7KwJRso zSJvcGMJ#v%e3RFjnh8pfR&X#rZ+e8p9D%jC!61&6Bp+oG5F$AT7$%+4*mhjH6VG~( z+cTLIagx=+>vtyd{IW3WbCX>sils$_gm|k5ZepIp$y+Fl99Cp4ym7kN)VxwqgW%G7E)1FD`O3F&iEg5UEDTXPe0YT5L zK6B-#meUWZsO;_~w{Qv)G2W!Rof{r>Jf56Ze6o_)ps%QqAZWKVfyq3R=}nS3qXeT5 zo2MPB5o+P{<(x6?=}x(wl|*7PF@c=bYtCF&sU{;_NfHDk9m9j3l=xzrRRU|VjP%Vz zu*?CH6NB8Il{#BQA^~AJ2OoNeXrkrp*2CZIz=+a8k`_YVaJjFQHrjBJ&nuoOI0z6FfwR1Y@;L{hpUhL}(QIj+F~qOJOO5g4sO*r5j&IscGLt z^$~Qto6p_DBK7B*jqWZq;%%n@VEXi@%p?Q%0I5I31wbv{SqYIzKIg3p?P@2c?6;@M z=1vUq;~fC2I;^)douWa3!i;lOE$ya(i>xEpIp&^H;#mtUC+kl|dl~z&oy2IbQUF|q z9Y;MXC=JOtVjBTxE11*+6)eVOUGp(G?M#AX3(wjuu`WGXRL<&UU0o0L165B}RNZfbF zdWE1^APJTucTD%kT4k(FaUh8yBPWb^spivt32~;?%~g+p=_WDva%y{U%`fjR@tkL# zm0fI2q;2%(W)p-PRc2E{z7VkcSBLH0Cm$$t zgZ}$gh=NvqqGb-eVALKP)IxYZ)+nuzHYCdqzv~*EY$9g!qz&$U>Yu$AW2Q2Ew`kIX zRi8?Ugs>x$G0CcLadSMz;GAyhihTb7VJIXKxyNdX-JWT{D0X8zO=P3w5wv36_btb$ z+}aK#1CD*_vq>G?=W~JAIQ6TBO(_P(iSh>`sZMRogxgz?J7$hl)wN6$T7>YVGAv=k zDX9=5#h9ez9&_5Gip_~K$!&)xg(lZigr%khH^^Qxo=gqv$B;;Q!JZ@ zBp#Io+t|%+5jK~{ILN6ittcN82d=`shlhk*iY=W`-EKJ9#6r7hW?XcXI#Z279jhL$jBLs6$3m6%E*0~A^=tU_D zoy!ZHb~Odeflo1ci)Qpz z1e}~^t{3zEtZN3YyO~nSmoYoz9fdmCq(|CZ9FJOAmeMvO?4-AIPq&5{NoBWUG1Ho< zC1Y0PO5n2X3=b7jTWgrhNG4vK3{{Ydq!9}YdiJO;cEW$v9!IS>xU|}1Nu!qWdOT_z zN;w%LHOrFct8y!-@q}oD%m_#$jPt+nrl$ivF|J36_fx^OlFAP+m@F&>w!Y5 zCP<5?YGXKDk0^nYo+x~>*sfV##QTUNGUtv(HFq;|K*9B>)s^`2TOE#SXwWFnkXt>o zQ>xsCnh}~%GG^nxMFp7QmRznn3PT?Jw~}x@`cf!WQo$+3D+fYG^HH#02N*uo=MLx( znxu5=(vUGZW=!Xw62@yZk+o4!vKA(e1Hbl;C^QpMB-h~)Gpg>y@*UD$q? zaM3ZeXBa-U9poQpxFs8@$Q20-6~JZ$FmBbSev#bSB`)ZXYCvl`}B1sYH@-xUI>M$D3qInH^hl1TCkL~?p#)~o855J7HUNY3w2 zDaP^9>^L^%%8qx%nww8Jw@I?2sH}(;*}@}aXOoI`^s6<~H;Yt9JVk-y_o+PIBOj;u-KWK_vJSrM*;@BN=7 zArUsPJW?6wF$hG9j-4j)YeZ64=JK$IPXfyTYCibNkn69+#lwA9Mh6u$12-fxW{_AE!wLraajPl z>xzW=QcwGrz~5vdbtFCP;3ltw|WQ zlzFKeD{?w@tJO3#`6FS8ylrnhp*?u33j`{@V@;BI;-WU3TzbpZbW3C&7oGoLM@E$B@ARl60vW0+&l z)3sI;MfQM+3v<^eHF7OX*eOeNIXV0(y>vv$%c4bwxw(lvyNQP2InSj&&gvq&-STn9 z2U^Yt?QQ4GGFW#!)1!sm@#F+hc|Nt8g0f3b>-uI+5iUeXANlCjryiLUbA*=b zVw1_o0-*3M)zn@UwgTUJu#@op<5rB4+C?62Bj-PGiiat3+pGDOx!STTUqxYIBE=2Z zm=WoWQb7>9Vq*Xuy#b^LPo2buHazk@D#4D}I>~N@aJ>h5ahqKj(vsMvErr5JR#)4R zkVwr~wbEN9mgyIE0Ni>XQ&(-7r#ohWqyS?W?MU{}M+e$-wE0v;<+yHxj`SNBwkl1#6>b5fxw*H0fuA+juTqV* zwD3qm%vc6F_p2jhi?QFUcNHYiO$h=hTP_bE(m|!pPw$pNfyc|0KS1}QC|gL!Z;+0J=2J-(kCNtqG0liYKfovd!+aF#G`1bS3+U)_-slvl{3aEr5_*3t|nG`$(4E7aCslCU|FSW6iJ4&+&B)9~Uc|6nB>Lvh9 zBJereMa{H1!H;S6!KjXsiUXBmPka%Ica868cP64KGnLuM7elgyw-Mz-Hl1N*NvV+J)18~7Um0jYMl*uOm`ii$2$mHe_2c;_; zYjq-QxX0b4d$v7dyOe&*Jkb_J+y|ycD!g#a!J@gGay=^Kmts~aY^5>Z(x^;^2V)`< zMr%km+SGBpwM(g1@Q8SeYaWN%pn~R2#Z1Hu@+hBV@*kCkI+05qyi78RTin&}O{clj zWvBJnc?DRxpLS1iRp%R9@8h1kb5gKqIr6ifIqgz3Y7`O)IO7AoMdkC*SLktmGTuht zH-Vnj%wU2?m;gQfYpU_PA_9*Va(S*>VzT8%dEj)fLJv(@>C;w%M$d)Se9}W?8r+bO z-@AUCbgVB7su>Fe;8xU&7D@K`XPjB;_# zYDAC|lH&x`L}ypltV>QX-9QwK%)qitF^&NhPt8_uy4)W0@3po<#}NY<#wqCa zLUiKGak)|Q$)Bfcd{U@#T1=lxsD?y4wqP1$w?QS|BP3ILJzj#1JMLLzZ!i%rP&G5=hc_Ve)6%72Bs&GbB!3nui5v_|n{)FX1vv;ALmAIvJBobPRwhYm#$7_d z;bv9<@_HKQyjgqY#vl^{bIo)!&m0Ks(GR=9BDigS>29wJd3=sDn%0|7bEgkZ^5%UC zLk-JGT{nZQK4C1+!5)>*T3d-_Rr1a=+Pm)!*a$3_d>_O3)m55G*B&BiM#a=%2va8I z2Y>}zjYBA8Zckceym14G5U3q7)YgryrK_&@OaY4HZQ97;l+;z4Du&B=;TZOGzRe)Jpc&Gl=kRPUF-OQ0;gewC|JK z1Jk{0%V!MqTWH5=GH2DJ^ z1!#SOC|Hi;+pQx;?A$;;QR!6WXW17ib}F@~jl9U@+B<lNxfK`y4R@rXGvTvqzv*YlF1#q76cR9BBPlV97fTW!Ql3&?q+v8 zV~ZT*;)_|@VWt2OKZMqmjPO8#IOnS{=~=pcvQIwO9r~Wttt-K67>*c3 zgz?g*PVV2=nKfKgt!+VIX-R8Y&Rd=ZMJltC71s~j=}4mHB=ZC&HDksq3GSl~8b2_f z;yBGpyVw$PcONB4Og}EHDs{=^5w}@QNY{f~>UX^x=R=713 z?Q%7WDDDHj&hd;87v8l*wsA-1#ei|o9qO9GlK~udeB)+qA)(*-u0VTSAU?b z&0(x0y^y-h4hJKpFqet8D`5KKof|{uu~^Cz?LbLZRW5~rJ;hsgVvoH3i6&9lm%6 z87Cd;OKI*~D7J(X*WQwNmN(3><369Lp)Y#hcttqeY$~9Dlar6VR-w67J0xs+QzH?_ z5qRv#UfJtS2w8l{tvSaB6x5yWyO8X@W5P<#2bqzc!=+xgh2#Z9m;iotPTcK`{iY&5 zgS|~|O8Dj%6gQ7O!&~@AHa&6+Ok%-8f06 z-M8-$wAm+HxWN#djBuimOh@k4-yC%!m7TQTrse(QS1*KOQe;g12TH2z5Cr*Wj+yUQ z8@-OG*~ZLCr7!aN*lzh0U0*zKjgGnLnyDlCubGn=?gdLK*vo1_JqB}*YVFNt%211v z(?gZKs+B>#SR!@mn3iiuBa!VV+~J0#S_hB9qLJu@N?Mdg7!Cf%i07^x~f=K#D?R1DpyY&v#}uWg--gd}K@8 z829y{G@JH$xj6ZO98n;dj$=%Wbq10&lRrFIIPcfu9105IG~;Xru{?pc9R z*i!wPJb$U_-jYp`kUX)_@&z>g>*_lvp)j~p7T+)*Pg;$L0}kAuYFJDW4sFQ<^~Xv{ zC5^L~NF&>fRdT0ya(3uEVB>kf@AA`GS-#|$AoU)U?>%r?7m^1Q)lludmy_64d)CyI zu=IeBnB0PK&mAgLGz6f60Ht%egA==&i6dO@Wc)=rVvQRF9A}O?(raP6MO?6~N`_bG zzC~EmB~`uJvW|Gp-`1-6Y6c^W`OBRJbjt3ru3-GpHDCYb<96mGU8gU;TyoKkVrPo>GBmS)LWbCK!IS+-*vZFU8? z&lL@{XsB6WJBaFgQ{pQdhbfRcj8r6>=0xdda%qw9OSn}ht}3+9N{{l~4o3%VSzsq{ zN@MZjp}mXj{{TAjG2X2{h!n14_=fN7maL0DNe2u^TH_i+G=-i~^B+pv@oo4o=VA-0r0X7+E7^GtnD zdfka50}T-&o27Hj>Ty+%BXz^hTaIRH*T1Nf@A+yHb=0N@&u8KVoAUVCI# zZ&l=C<16XZ(Smm|m0P9cbHzz&S1lZufajBeR3TXB%lUlzW2Hz8DJc0!7{=gvsCv7$ zW~0#-nb`?3TpVM)MK#z|RY&A?9gR3DJb$}FRPmEh2-O=44oZrY?(Vl7Q`w-7=2aV| zn}g6*n>*{aW4QC!VxfKg8rv<&;Pj{4T~A>$%F%8l^dgkq<8rxe9V2nKVo3>SlNs-} zp;&GizjblbxfQFcYSC&cyX}Gz*A+tE(l!KVX(u4!l9ZPE3OihgtfBEM=Z*$D(@m_1 zavMK~O0Wa|pl~z^Zb))tYljD(yJ-n- z#}w-YfZQ8}gDd^gDfg4v%Qwkx0S&_DqD}Qg>fP;eOI|wSOW+lI6{ao9BKbmKMtN*^ zrZi#X+7spXG#h5l#kMRDU}^HDZA0B}Qe z>bE|TD@4wcpa68CzFjUWsLI{OESFwTRg?t-lB?2@wFXr31>-liDI>9Tw<0!XKiw3D z5g*STzS02AN>K|bEr%*x-4MwsUs6X}lH%U(L{xk5cJspL6$qKgJJ8^c0H@pCC9-Zy zUB|egJIQMLb`+yF{nRuxHmXZGk%8z}6(zmo^E#|b7tqpuurjfl$SC*gRlMdhmWDhj zI25Fo=n_v^BW7j0w~x+yg~7%^6&2*sOAwRoM?T#utKM7{#L?hncj-~fESp(GSzOf9 zi%H$rbk)+C6G8CSIuMn=DTgJS7?|P|Q znIy=SxwY7;FFetOZN7weG`?ZjO~j!0#wx7#$>)%Oa@`22f)67qn}=R%trygKA^!ku ziv-7vb@`1+7NF6q9o+h2vVKID<{ODP03MZhPm(C*A14Ix3H>QJ^67C-DJ>PrR#dq^ zJi9U~#5VaJQ%=9{0ZPzW$jV}f7S9SjX<1$Ze{r|eVx}^eLn%A03%2%CGB1^K4l&og zCx~ri8WgPZ50tJ(KiU-x23VOV1oP2NJ6)DhqR3t$)o^qE(5FpL+Qsj$`598z5e<5; z%^05!Y@xXDy|HP8d`NlcKRZ^FeV9mK54#8NW36HM8bY2Kwow-R@8hQ)V^*k=NZ(>x z^=_mb3RZI6zw7+XQg?o3k#0sxOsc0lat{=#3mwTMyUsWwpKElcBDWT~J&rMoc!t|> zkywNM+){JpUYwIOCd* zZda#IB0d>C2kFmnVGzhcU(hx_^W4D)a~_k5*u|!KnB3LtfdyRIa${L zboZxsaF22rB-Abt7@r^>xW!qHTbO=#m!97(NfIndRt4j?(ui&3yPs=E&#~gB&#KUw zO6;$A(oOSyqyi3cii+BKiU{SnIQCvD=BcDyLZkpNSB`3}uw)=crz5T^xt8hlD*7VS zacPDF=Ff>g-9MFMUt26UC8M|pB=d^3G~wjTw(LK`l-WaY;$Sxpq)?r`=I&CwG$}@d#Uwwwh4>uf{3`UemmZC)s}wNF zn2h_m=K`hDM7DCYixSABcN_|;)0HT~{si!r%|D6jeL9WJv!2eKElumaY#WSA@wYjl!y3M8p=^fsVCNYSzE?p>eW$qKGoPl#YDo zkGtBM>vjlLn*@w-dexXh2MR6l2v)I)q&7p;TVRF-EORk6W z_NXo`94h|+r2&q-b*r}$n~5;CdeSW|*`#M4T@F*k#4>qnFMhbL zd3O_mFH_GI(fGlUGM-9~dIMbGjaogy0Q9cPdMll)n&_E7e2t8bxM_j<&{?swBc6Dt#{ddgjNs#e+L7?G zZ7`hr;)|!N3oBU&wrI*;d2^hQNX9BRS8f*Lj+qqZb29Amm}9LG;S_%B03S+HlC_4D zNESB$IiH~9d(^hi8+`7=r(a5rW(0*u3C~lGl(9xs1QGs1nv%W6C3Rv)Dp-Yl4@yF; zTO0V#r7_0CyUQm%0jXAXLxo(NdR0S7e_z*eJ7|cMZpjm1j>J^3#-)B~@qye^Ue05Q zW4GX(=N;-G{ZdGY!R#nnyWDZr>OIL)KYPGD`_Rm*^E(0bq*e^TEN70Oic+fIc?jpB z6q-_7g^=dU0HA^IPDtcP^3sFPaZGZkyHz>tF-{K)qNszBLv7CDNu;y`7s?bkA-WM# zh?+IrB;(jr6R`>pm&oagd@XQ6%pm0QDtV-xkhyO4A1=`0f!qlCRJQ1j!a*>|&&y2; zSwILk5zs9-L=pFxv63@JtrIO#I4njopn;y1YeR@V*GFh)97 zZKV~{`b2XpYAUG;3{Q@8yA?xPyJUd5xEaUgS~t*nIW9AS{64kGc)IUml~u{_&1+35 zPUf^?r6ttobxW7KyJIBT=Z|``;mtBj>-C9e10-i6vyg9mnD{+?tF7>Eillv^lLUI! z^(D&-Y<1O|rwtCK&c!tQb&u@>r#Pp%Ef_Js2dA|%G&l&+jDy~vg&?4WdWz+3H*?NW zznDb>l?5i}jEvOtC+@^Sxjkwa!j}OM;d}a3j3xsh8Rr!`Avs!P;y1Il3oL^j&M5?T zuNifGwm+Rh##IB%P}mt&GZI>K?3CO6H z?ikZ-ksr&YGHd&G&y@hpD?2p*03>LkcY79$fD9SWJ;KurPa(?9lk}>_=0{vd2VX%_ z!EocBBr2Hw0}n6VE3V8*hvS6EP!?N}c49NR!FP=yOey;axCo`ga10 zw;Ljru0GybS}mgFA6_}6fhQ9J%e)@=%`Ldd1|Ssrnv}_L8w9}4J5=5D+)B^g{;pa3 zBa`L%qBZV)DUidaTFz2g%!HGYDwK~jj>UsHV~kY7*%bt!429>KOc4@6t zZ;4YL^%H7y725=;xII9u@FZeOMp$I5Q0b-#N2#d#l=4U9%QzY8K<1-~ zgP$ku2X1&c>s1rWUzzR69V*glF-C?vdl1>~MF}+3ze@?m+ah?cUc>!N!c6ufprw(e zxr=ilPfQLflFK6TBwY3RMNb^_I&CrSRy^jjQGa-HU69E;2{z!I9CW3M;s|E>orZr} zeD`}(XOao*%TWm%8{xGip8aao+8wW@iEb_+xH(5S9CYthr$@kO9D|=uwP2}Ol_ZB5 zJ#kIi%uW*u-7(Ug+gBc>FhwlSiKig?16Qr>Z6I(axDF3o(+WW%Y!Eg;~%Allx5;-+B+zW4Oh}$i+cEvGK7!wFkM+DT2uHj=S2>MaX@2_HB z>gIp;SPEWQKt7)I>uoYMCQ~erd!}OL8{hR7 z2xh=?{{SfH*s1lEOPvO7{1LPhkM@OBlkI8ylHV^v1v^u@kZ3b1AQ%hD>-U9eO(#|@ zKBPu1SEp|4^Dw*{8vg*oDQ7HleZeNWgo+l2FGyk}E>SC~ryg?i3I{P(>6`%c8fDoV7Hpbh}9{-bpnv9?|lRxy@2G@TBJ# zMYf)!y%bWjweS60!XEN>C6Ro^FBI6w=ZY<2hhUB8IVZ5|MHMM)Ym)vOmgcaw5DzBv zIO8OAs`A@Q8VLp1>73$V`%y(^?-^SA z*tl8r>Q|mQnq7}3+;<~2R`Er;h*tQ3M>riQqN*2`=JEa|h~p8oKe)UM-t^{{=E^^+_ZrO~Y$3Cc@X{aJsQ zSuKhevpuxCp?rlW8Sh!wlg)cCnJl1pD@7H$Zr^d=PMmpeMs9>qnB#HNkyT;)OveWA z0DE;5QCg?hulzAdD8o+YHRA-01`MiuXB}&q4isa}{V1Zk==>Ku;*yFtd_53&^0MTC z>BVT>+sO+2?eBmnqOg?Z8Ce|n_w4$ju%1O-%)k@ViipjFwnrK5#S~PlrTuvo4G}6b zNQ9XH=Yfh}C^#|)1a}#tiX5eMf=YF9C9fdO^f@vvf1QOMQQdfQ%TCqX`INP zGaT|dbfP9)03_gdJQ^sh({{L;QJs-GUP!2^_MSZtN*d%U;7Pl1>?op>oRYap32Zvm zFiY>}u*Z5!hH?j*>+C?Hiqb9UX9afH)Wh(NxcgF@IZJIa0o-DWD>pe?ewQ58uVQ4g zNM94k#C0GFah?=nEpxZFMHE)CZukDSM74CA7AR)8lLY6f08l`P1eR>$_(-CPR4&(6tCn(aW+XUCRd&S>0G~w zZRER@Yy^?$D5A8Cq@}0zvC)UMxs2OA3TBx>R=4a?%x9_b5J?#Y`iW2#~f^j`UGY zPD*JaB`XWCu^+t09qC28x@B1I2dETLN*dqR#mn7jK_8ivl5%h{_i6U}W4<4GqKb*l zr*G?^IW;R1ta72jV}Nm-RI$KhLf&xYx{4^Q+}fs^{a5MMf>4+_r$ck^*ti z3P`}d07TsJ$Q>x6qn=*Mz!5$Uc_Xb9 zQ+hS${zg_>F|T#Je)lAv+ehX3jy~=x9;@?5|JfnD BX1o9Z From c7e43fbecf5456453396a7494bd364ed8da3c76f Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Fri, 16 Feb 2024 17:53:35 +0100 Subject: [PATCH 6/9] more cv changes fixes --- .../src/mainwindow.cpp | 139 +++++++++--------- .../src/slam/CIncrementalMapPartitioner.cpp | 4 +- libs/vision/src/CVideoFileWriter.cpp | 5 +- .../hwdrivers/CImageGrabber_FlyCapture2.cpp | 2 - 4 files changed, 76 insertions(+), 74 deletions(-) diff --git a/apps/benchmarking-image-features/src/mainwindow.cpp b/apps/benchmarking-image-features/src/mainwindow.cpp index 3518203efc..13e12cd759 100644 --- a/apps/benchmarking-image-features/src/mainwindow.cpp +++ b/apps/benchmarking-image-features/src/mainwindow.cpp @@ -205,7 +205,7 @@ void MainWindow::on_button_generate_clicked() plot->setPlotGridColor(Scalar(255, 255, 0)); cv::Mat temp1(display.cols, display.rows, display.type()); - cvtColor(display, temp1, CV_RGB2BGR); + cvtColor(display, temp1, cv::COLOR_RGB2BGR); QImage dest1 = QImage( (uchar*)temp1.data, temp1.cols, temp1.rows, temp1.step, @@ -301,9 +301,9 @@ void MainWindow::on_button_generate_clicked() auxImg2.getHeight() * 2, IMG_INTERP_NN); } - cv::Mat cvImg1 = auxImg1.asCvMatRef(); - cv::Mat temp1(cvImg1.cols, cvImg1.rows, cvImg1.type()); - cvtColor(cvImg1, temp1, CV_GRAY2RGB); + cv::Mat cvImg_1 = auxImg1.asCvMatRef(); + cv::Mat temp1(cvImg_1.cols, cvImg_1.rows, cvImg_1.type()); + cvtColor(cvImg_1, temp1, cv::COLOR_GRAY2RGB); QImage dest1 = QImage( (uchar*)temp1.data, temp1.cols, temp1.rows, temp1.step, QImage::Format_RGB888); @@ -318,7 +318,7 @@ void MainWindow::on_button_generate_clicked() { cv::Mat& cvImg2 = auxImg2.asCvMatRef(); cv::Mat temp2(cvImg2.cols, cvImg2.rows, cvImg2.type()); - cvtColor(cvImg2, temp2, CV_GRAY2RGB); + cvtColor(cvImg2, temp2, cv::COLOR_GRAY2RGB); QImage dest2 = QImage( (uchar*)temp2.data, temp2.cols, temp2.rows, temp2.step, QImage::Format_RGB888); @@ -352,23 +352,23 @@ void MainWindow::on_button_generate_clicked() v1 = *ft1.descriptors.LATCH; #ifdef HAVE_OPENCV_PLOT - Mat xData, yData, display; - Ptr plot; - int len; - if (descriptor_selected != 1) len = v1.size(); + Mat xdata, ydata, Display; + Ptr Plot; + int Len; + if (descriptor_selected != 1) Len = v1.size(); else - len = v1_surf.size(); + Len = v1_surf.size(); - xData.create(1, len, CV_64F); // 1 Row, len columns, Double - yData.create(1, len, CV_64F); + xdata.create(1, Len, CV_64F); // 1 Row, len columns, Double + ydata.create(1, Len, CV_64F); - for (int i = 0; i < len; ++i) + for (int i = 0; i < Len; ++i) { - xData.at(i) = i; + xdata.at(i) = i; if (descriptor_selected != 1) - yData.at(i) = v1.at(i); + ydata.at(i) = v1.at(i); else - yData.at(i) = v1_surf.at(i); + ydata.at(i) = v1_surf.at(i); } int max_y, min_y; /// assigned values of the lower and upper limits in the graph @@ -385,18 +385,18 @@ void MainWindow::on_button_generate_clicked() } #if MRPT_OPENCV_VERSION_NUM >= 0x030300 - plot = plot::Plot2d::create(xData, yData); + Plot = plot::Plot2d::create(xdata, ydata); #else plot = plot::createPlot2d(xData, yData); #endif - plot->setPlotSize(len, 1); - plot->setMaxX(len); - plot->setMinX(0); - plot->setMaxY(max_y); - plot->setMinY(min_y); - plot->render(display); - cv::Mat temp1(display.cols, display.rows, display.type()); - cvtColor(display, temp1, CV_RGB2BGR); + Plot->setPlotSize(Len, 1); + Plot->setMaxX(Len); + Plot->setMinX(0); + Plot->setMaxY(max_y); + Plot->setMinY(min_y); + Plot->render(Display); + cv::Mat temp1(Display.cols, Display.rows, Display.type()); + cvtColor(Display, temp1, cv::COLOR_RGB2BGR); QImage dest1 = QImage( (uchar*)temp1.data, temp1.cols, temp1.rows, temp1.step, @@ -423,15 +423,16 @@ void MainWindow::on_button_generate_clicked() Mat xData, yData, display; Ptr plot; - int len; - if (descriptor_selected != 1) len = v2.size(); + int len2; + if (descriptor_selected != 1) len2 = v2.size(); else - len = v2_surf.size(); + len2 = v2_surf.size(); - xData.create(1, len, CV_64F); // 1 Row, len columns, Double - yData.create(1, len, CV_64F); + xData.create( + 1, len2, CV_64F); // 1 Row, len columns, Double + yData.create(1, len2, CV_64F); - for (int i = 0; i < len; ++i) + for (int i = 0; i < len2; ++i) { xData.at(i) = i; if (descriptor_selected != 1) @@ -444,14 +445,14 @@ void MainWindow::on_button_generate_clicked() #else plot = plot::createPlot2d(xData, yData); #endif - plot->setPlotSize(len, 1); - plot->setMaxX(len); + plot->setPlotSize(len2, 1); + plot->setMaxX(len2); plot->setMinX(0); plot->setMaxY(max_y); plot->setMinY(min_y); plot->render(display); cv::Mat temp2(display.cols, display.rows, display.type()); - cvtColor(display, temp2, CV_RGB2BGR); + cvtColor(display, temp2, cv::COLOR_RGB2BGR); QImage dest2 = QImage( (uchar*)temp2.data, temp2.cols, temp2.rows, temp2.step, @@ -1491,9 +1492,9 @@ void MainWindow::on_detector_button_clicked() /// converting to color images to draw markers in correct color cv::Mat temp1(cvImg1.cols, cvImg1.rows, cvImg1.type()); - if (temp1.channels() == 3) cvtColor(cvImg1, temp1, CV_BGR2RGB); + if (temp1.channels() == 3) cvtColor(cvImg1, temp1, cv::COLOR_BGR2RGB); else - cvtColor(cvImg1, temp1, CV_GRAY2RGB); + cvtColor(cvImg1, temp1, cv::COLOR_GRAY2RGB); /// Drawing a marker around key-points for image 1 for (unsigned int i = 0; i < featsImage1.size(); i++) @@ -1529,9 +1530,9 @@ void MainWindow::on_detector_button_clicked() /// converting to color to draw coloured markers cv::Mat temp2(cvImg2.cols, cvImg2.rows, cvImg2.type()); - if (temp2.channels() == 3) cvtColor(cvImg2, temp2, CV_BGR2RGB); + if (temp2.channels() == 3) cvtColor(cvImg2, temp2, cv::COLOR_BGR2RGB); else - cvtColor(cvImg2, temp2, CV_GRAY2RGB); + cvtColor(cvImg2, temp2, cv::COLOR_GRAY2RGB); /// Drawing a marker around key-points for image 2 for (unsigned int i = 0; i < featsImage2.size(); i++) @@ -2051,7 +2052,7 @@ void MainWindow::displayImagesWithoutDetector() resolution_x = img1.getWidth(); resolution_y = img1.getHeight(); - cv::Mat cvImg1 = img1.asCvMatRef(); + cv::Mat cvImg_1 = img1.asCvMatRef(); // fillDetectorInfo(); no need to call /// clearing this is important @@ -2060,11 +2061,11 @@ void MainWindow::displayImagesWithoutDetector() /// converting to color to draw markers in color for both color and /// grayscale images - cv::Mat temp1(cvImg1.cols, cvImg1.rows, cvImg1.type()); + cv::Mat temp1(cvImg_1.cols, cvImg_1.rows, cvImg_1.type()); // cout << "dimensions " << temp1.dims << endl; - if (temp1.channels() == 3) cvtColor(cvImg1, temp1, CV_BGR2RGB); + if (temp1.channels() == 3) cvtColor(cvImg_1, temp1, cv::COLOR_BGR2RGB); else - cvtColor(cvImg1, temp1, CV_GRAY2RGB); + cvtColor(cvImg_1, temp1, cv::COLOR_GRAY2RGB); /// draw a marker for key-points in image 1 for (unsigned int i = 0; i < featsImage1.size(); i++) @@ -2100,9 +2101,9 @@ void MainWindow::displayImagesWithoutDetector() /// grayscale images cv::Mat temp2(cvImg2.cols, cvImg2.rows, cvImg2.type()); - if (temp2.channels() == 3) cvtColor(cvImg2, temp2, CV_BGR2RGB); + if (temp2.channels() == 3) cvtColor(cvImg2, temp2, cv::COLOR_BGR2RGB); else - cvtColor(cvImg2, temp2, CV_GRAY2RGB); + cvtColor(cvImg2, temp2, cv::COLOR_GRAY2RGB); /// draw a marker for key-points in image 2 for (unsigned int i = 0; i < featsImage2.size(); i++) @@ -2159,12 +2160,12 @@ void MainWindow::on_sample_clicked() ReadInputFormat(); img1.loadFromFile(file_path1); - cv::Mat cvImg1 = img1.asCvMatRef(); + cv::Mat cvImg_1 = img1.asCvMatRef(); - cv::Mat temp1(cvImg1.cols, cvImg1.rows, cvImg1.type()); - if (temp1.channels() == 3) cvtColor(cvImg1, temp1, CV_BGR2RGB); + cv::Mat temp1(cvImg_1.cols, cvImg_1.rows, cvImg_1.type()); + if (temp1.channels() == 3) cvtColor(cvImg_1, temp1, cv::COLOR_BGR2RGB); else - cvtColor(cvImg1, temp1, CV_GRAY2RGB); + cvtColor(cvImg_1, temp1, cv::COLOR_GRAY2RGB); QImage disp1 = QImage( (uchar*)temp1.data, temp1.cols, temp1.rows, temp1.step, @@ -2181,9 +2182,9 @@ void MainWindow::on_sample_clicked() cv::Mat cvImg2 = img2.asCvMatRef(); cv::Mat temp2(cvImg2.cols, cvImg2.rows, cvImg2.type()); - if (temp2.channels() == 3) cvtColor(cvImg2, temp2, CV_BGR2RGB); + if (temp2.channels() == 3) cvtColor(cvImg2, temp2, cv::COLOR_BGR2RGB); else - cvtColor(cvImg2, temp2, CV_GRAY2RGB); + cvtColor(cvImg2, temp2, cv::COLOR_GRAY2RGB); QImage disp2 = QImage( (uchar*)temp2.data, temp2.cols, temp2.rows, temp2.step, QImage::Format_RGB888); @@ -2364,7 +2365,7 @@ void MainWindow::on_generateVisualOdometry_clicked() // waitKey(0); cv::Mat temp2(display_VO.cols, display_VO.rows, display_VO.type()); - cvtColor(display_VO, temp2, CV_BGR2RGB); + cvtColor(display_VO, temp2, cv::COLOR_BGR2RGB); QImage dest2 = QImage( (uchar*)temp2.data, temp2.cols, temp2.rows, temp2.step, QImage::Format_RGB888); @@ -2509,11 +2510,11 @@ Point MainWindow::trackKeyPoint( cv::Mat cvImg_test = img_test.asCvMatRef(); Mat cvImg_org_gray, cvImg_test_gray; - cvtColor(cvImg_org, cvImg_org_gray, CV_RGB2GRAY); - cvtColor(cvImg_test, cvImg_test_gray, CV_RGB2GRAY); + cvtColor(cvImg_org, cvImg_org_gray, cv::COLOR_RGB2GRAY); + cvtColor(cvImg_test, cvImg_test_gray, cv::COLOR_RGB2GRAY); - int resolution_x = cvImg_org.rows; - int resolution_y = cvImg_org.cols; + int resolutionX = cvImg_org.rows; + int resolutionY = cvImg_org.cols; /// org_x,org_y belong to the key-point in image_org and the corresponding /// key-point in img_test needs to be computed @@ -2537,8 +2538,8 @@ Point MainWindow::trackKeyPoint( int temp_test_x = temp_x + j; int temp_test_y = temp_y + k; - if (temp_org_x > resolution_x || temp_org_y > resolution_y || - temp_test_x > resolution_x || temp_test_y > resolution_y) + if (temp_org_x > resolutionX || temp_org_y > resolutionY || + temp_test_x > resolutionX || temp_test_y > resolutionY) break; response = response + @@ -2574,14 +2575,14 @@ void MainWindow::on_trackIt_clicked() window_width = tracker_param5_edit->text().toInt(); window_height = tracker_param6_edit->text().toInt(); - cv::Mat cvImg1 = tracker_obj.trackThemAll( + cv::Mat cvImg_1 = tracker_obj.trackThemAll( files_fullpath_tracking, tracking_image_counter, remove_lost_feats, add_new_feats, max_feats, patch_size, window_width, window_height); /// temp1 is always in color due to tracker marks so no need to convert to /// grayscale - cv::Mat temp1(cvImg1.cols, cvImg1.rows, cvImg1.type()); - cvtColor(cvImg1, temp1, CV_BGR2RGB); + cv::Mat temp1(cvImg_1.cols, cvImg_1.rows, cvImg_1.type()); + cvtColor(cvImg_1, temp1, cv::COLOR_BGR2RGB); QImage dest1 = QImage( (uchar*)temp1.data, temp1.cols, temp1.rows, temp1.step, @@ -2799,7 +2800,7 @@ void MainWindow::store_Training_TestingSets() dir = opendir(file_path_temp.c_str()); while ((pdir = readdir(dir))) files.emplace_back(pdir->d_name); - for (unsigned int i = 0, j = 0; i < files.size(); i++) + for (unsigned int i = 0 /*, j = 0*/; i < files.size(); i++) { if (files.at(i).size() > 4) // this removes the . and .. in // linux as all files will have @@ -2809,7 +2810,7 @@ void MainWindow::store_Training_TestingSets() training_files_paths.push_back( file_path_temp + "/" + files.at(i)); // cout << files_fullpath_tracking.at(j) << endl; - j++; + // j++; } } // end of for } @@ -4021,9 +4022,9 @@ void MainWindow::Mouse_Pressed() cv::Mat temp_desc_ref( desc_Ref_img.cols, desc_Ref_img.rows, desc_Ref_img.type()); if (temp_desc_ref.channels() == 3) - cvtColor(desc_Ref_img, temp_desc_ref, CV_BGR2RGB); + cvtColor(desc_Ref_img, temp_desc_ref, cv::COLOR_BGR2RGB); else - cvtColor(desc_Ref_img, temp_desc_ref, CV_GRAY2RGB); + cvtColor(desc_Ref_img, temp_desc_ref, cv::COLOR_GRAY2RGB); /// images1 have all the descriptors if (images_static_sift_surf != nullptr) @@ -4114,9 +4115,10 @@ void MainWindow::Mouse_Pressed() // featsImage2.saveToTextFile("./KeyPoints2.txt"); cv::Mat cvImg2 = img2.asCvMatRef(); cv::Mat temp2(cvImg2.cols, cvImg2.rows, cvImg2.type()); - if (temp2.channels() == 3) cvtColor(cvImg2, temp2, CV_BGR2RGB); + if (temp2.channels() == 3) + cvtColor(cvImg2, temp2, cv::COLOR_BGR2RGB); else - cvtColor(cvImg2, temp2, CV_GRAY2RGB); + cvtColor(cvImg2, temp2, cv::COLOR_GRAY2RGB); /// draw a marker around image 1 keypoints for (unsigned int i = 0; i < featsImage2.size(); i++) @@ -4226,9 +4228,10 @@ void MainWindow::Mouse_Pressed() /// converting to colour image to show markers in color for /// grayscale images too cv::Mat temp2(cvImg2.cols, cvImg2.rows, cvImg2.type()); - if (temp2.channels() == 3) cvtColor(cvImg2, temp2, CV_BGR2RGB); + if (temp2.channels() == 3) + cvtColor(cvImg2, temp2, cv::COLOR_BGR2RGB); else - cvtColor(cvImg2, temp2, CV_GRAY2RGB); + cvtColor(cvImg2, temp2, cv::COLOR_GRAY2RGB); /// draw a marker around image 2 keypoints for (unsigned int i = 0; i < featsImage2.size(); i++) diff --git a/libs/slam/src/slam/CIncrementalMapPartitioner.cpp b/libs/slam/src/slam/CIncrementalMapPartitioner.cpp index 15cf4e66de..7473569d46 100644 --- a/libs/slam/src/slam/CIncrementalMapPartitioner.cpp +++ b/libs/slam/src/slam/CIncrementalMapPartitioner.cpp @@ -405,9 +405,9 @@ void CIncrementalMapPartitioner::getAs3DScene( // Arcs: for (size_t j = i + 1; j < m_individualFrames.size(); j++) { - const auto [j_pdf, j_sf, twist] = m_individualFrames.get(j); + const auto [j_pdf, j_sf, kfTwist] = m_individualFrames.get(j); (void)j_sf; // unused - (void)twist; + (void)kfTwist; CPose3D j_mean; j_pdf->getMean(j_mean); diff --git a/libs/vision/src/CVideoFileWriter.cpp b/libs/vision/src/CVideoFileWriter.cpp index c4f3b830e3..708e99f1d1 100644 --- a/libs/vision/src/CVideoFileWriter.cpp +++ b/libs/vision/src/CVideoFileWriter.cpp @@ -49,11 +49,12 @@ bool CVideoFileWriter::open( if (fourcc.empty()) { - cc = CV_FOURCC('I', 'Y', 'U', 'V'); // Default + cc = cv::VideoWriter::fourcc('I', 'Y', 'U', 'V'); // Default } else if (fourcc.size() == 4) { - cc = CV_FOURCC(fourcc[0], fourcc[1], fourcc[2], fourcc[3]); + cc = + cv::VideoWriter::fourcc(fourcc[0], fourcc[1], fourcc[2], fourcc[3]); } else { diff --git a/python/src/mrpt/hwdrivers/CImageGrabber_FlyCapture2.cpp b/python/src/mrpt/hwdrivers/CImageGrabber_FlyCapture2.cpp index 3cb8f43718..1c52338992 100644 --- a/python/src/mrpt/hwdrivers/CImageGrabber_FlyCapture2.cpp +++ b/python/src/mrpt/hwdrivers/CImageGrabber_FlyCapture2.cpp @@ -91,8 +91,6 @@ void bind_mrpt_hwdrivers_CImageGrabber_FlyCapture2(std::function< pybind11::modu .value("CAMERA_CV_AUTODETECT", mrpt::hwdrivers::CAMERA_CV_AUTODETECT) .value("CAMERA_CV_DC1394", mrpt::hwdrivers::CAMERA_CV_DC1394) .value("CAMERA_CV_VFL", mrpt::hwdrivers::CAMERA_CV_VFL) - .value("CAMERA_CV_VFW", mrpt::hwdrivers::CAMERA_CV_VFW) - .value("CAMERA_CV_MIL", mrpt::hwdrivers::CAMERA_CV_MIL) .value("CAMERA_CV_DSHOW", mrpt::hwdrivers::CAMERA_CV_DSHOW) .export_values(); From f86dc1a86ea4b1b6eb9cb0f49dbf0c9d1fba264b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Fri, 16 Feb 2024 23:41:21 +0100 Subject: [PATCH 7/9] fix doxyrest template --- doc/source/doxyrest-frames/cfamily/compound.rst.in | 14 ++++---------- 1 file changed, 4 insertions(+), 10 deletions(-) diff --git a/doc/source/doxyrest-frames/cfamily/compound.rst.in b/doc/source/doxyrest-frames/cfamily/compound.rst.in index c4d810632b..2e2c8d8f7c 100644 --- a/doc/source/doxyrest-frames/cfamily/compound.rst.in +++ b/doc/source/doxyrest-frames/cfamily/compound.rst.in @@ -24,8 +24,8 @@ if compound.compoundKind == "namespace" or compound.compoundKind == "group" then functionSectionName = "Global Functions" indent = "" else - variableSectionName = "\nFields" - functionSectionName = "\nMethods" + variableSectionName = "Fields" + functionSectionName = "Methods" indent = "\t" end @@ -40,18 +40,12 @@ local compoundStats = prepareCompound(compound) } $(getCompoundTocTree(compound)) -%{ -local hasDetails = - compoundStats.hasDocumentedItems or - compoundStats.hasBriefDocumentation and compoundStats.hasDetailedDocumentation - -if hasDetails then -} +Overview +~~~~~~~~ $(getItemDetailedDocumentation(compound)) %{ -end -- if if #compound.groupArray > 0 or compound.hasGlobalNamespace then local groupTree = "" From 485857b90391998007341500e729c199cec02d6b Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Sat, 17 Feb 2024 09:02:35 +0100 Subject: [PATCH 8/9] relax memory warning level --- apps/RawLogViewer/xRawLogViewerMain.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/apps/RawLogViewer/xRawLogViewerMain.cpp b/apps/RawLogViewer/xRawLogViewerMain.cpp index 5339420b9e..66150b3513 100644 --- a/apps/RawLogViewer/xRawLogViewerMain.cpp +++ b/apps/RawLogViewer/xRawLogViewerMain.cpp @@ -1871,7 +1871,7 @@ void xRawLogViewerFrame::loadRawlogFile(const string& str, int first, int last) progDia.Fit(); wxTheApp->Yield(); // Let the app. process messages - if (memUsg_Mb > 4000 && !alreadyWarnedTooLargeFile) + if (memUsg_Mb > 8000 && !alreadyWarnedTooLargeFile) { alreadyWarnedTooLargeFile = true; string msg; From 824d1310a98d76edb6d1994f647f3be28fe9a726 Mon Sep 17 00:00:00 2001 From: Jose Luis Blanco Claraco Date: Mon, 19 Feb 2024 23:55:10 +0100 Subject: [PATCH 9/9] changelog --- doc/source/doxygen-docs/changelog.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/source/doxygen-docs/changelog.md b/doc/source/doxygen-docs/changelog.md index ee2c33668e..8c8ff78b4b 100644 --- a/doc/source/doxygen-docs/changelog.md +++ b/doc/source/doxygen-docs/changelog.md @@ -1,6 +1,6 @@ \page changelog Change Log -# Version 2.11.10: UNRELEASED +# Version 2.11.10: Relased Feb 19th, 2024 - Changes in libraries: - \ref mrpt_maps_grp: - mrpt::maps::CHeightGridMap2D: now supports integrating any point-cloud observation.