From 78392f786da6d3871590c62d88e6ba323d834e5b Mon Sep 17 00:00:00 2001 From: fegorsch Date: Tue, 15 May 2018 15:43:15 +0200 Subject: [PATCH 01/97] Rename `near` to `zNear` `near` is an illegal variable name on Windows (if `windef.h` is included), because a macro with the same name is defined. Someone else already put your rage into words, see http://lolengine.net/blog/2011/3/4/fuck-you-microsoft-near-far-macros. --- modules/ovis/src/ovis.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/modules/ovis/src/ovis.cpp b/modules/ovis/src/ovis.cpp index 9f43211c5..6ceeec544 100644 --- a/modules/ovis/src/ovis.cpp +++ b/modules/ovis/src/ovis.cpp @@ -97,11 +97,11 @@ static void _setCameraIntrinsics(Camera* cam, InputArray _K, const Size& imsize) Matx33f K = _K.getMat(); - float near = cam->getNearClipDistance(); - float top = near * K(1, 2) / K(1, 1); - float left = -near * K(0, 2) / K(0, 0); - float right = near * (imsize.width - K(0, 2)) / K(0, 0); - float bottom = -near * (imsize.height - K(1, 2)) / K(1, 1); + float zNear = cam->getNearClipDistance(); + float top = zNear * K(1, 2) / K(1, 1); + float left = -zNear * K(0, 2) / K(0, 0); + float right = zNear * (imsize.width - K(0, 2)) / K(0, 0); + float bottom = -zNear * (imsize.height - K(1, 2)) / K(1, 1); // use frustum extents instead of setFrustumOffset as the latter // assumes centered FOV, which is not the case From a7981278376150361896063a49a42858de6d7964 Mon Sep 17 00:00:00 2001 From: LaurentBerger Date: Thu, 17 May 2018 18:37:57 +0200 Subject: [PATCH 02/97] Merge pull request #1634 from LaurentBerger:FD_bug * remove bug when src is vector Point2i in FourierDescriptors * remove unused code and comments --- .../samples/fourier_descriptors_demo.cpp | 4 +- .../samples/fourier_descriptors_demo.py | 169 ++++++++++++++++++ modules/ximgproc/src/fourier_descriptors.cpp | 11 +- .../test/test_fourier_descriptors.cpp | 90 ++++++++++ 4 files changed, 266 insertions(+), 8 deletions(-) create mode 100644 modules/ximgproc/samples/fourier_descriptors_demo.py create mode 100644 modules/ximgproc/test/test_fourier_descriptors.cpp diff --git a/modules/ximgproc/samples/fourier_descriptors_demo.cpp b/modules/ximgproc/samples/fourier_descriptors_demo.cpp index 7347034ac..2afc42d7d 100644 --- a/modules/ximgproc/samples/fourier_descriptors_demo.cpp +++ b/modules/ximgproc/samples/fourier_descriptors_demo.cpp @@ -104,11 +104,11 @@ int main(void) vector ctrRef2d, ctrRot2d; // sampling contour we want 256 points ximgproc::contourSampling(ctrRef, ctrRef2d, 256); // use a mat - ximgproc::contourSampling(ctrNoisyRotateShift, ctrRot2d, 256); // use a vector og point + ximgproc::contourSampling(ctrNoisyRotateShift, ctrRot2d, 256); // use a vector of points fit.setFDSize(16); Mat t; fit.estimateTransformation(ctrRot2d, ctrRef2d, t, &dist, false); - cout << "Transform *********\n "<<"Origin = "<< t.at(0,0)*ctrNoisy.size() <<" expected "<< (p.origin*ctrNoisy.size()) / 100 <<" ("<< ctrNoisy.size()<<")\n"; + cout << "Transform *********\n "<<"Origin = "<< 1-t.at(0,0) <<" expected "<< p.origin/100.0 <<" ("<< ctrNoisy.size()<<")\n"; cout << "Angle = " << t.at(0, 1) * 180 / M_PI << " expected " << p.angle <<"\n"; cout << "Scale = " << t.at(0, 2) << " expected " << p.scale10 / 10.0 << "\n"; Mat dst; diff --git a/modules/ximgproc/samples/fourier_descriptors_demo.py b/modules/ximgproc/samples/fourier_descriptors_demo.py new file mode 100644 index 000000000..5583192fd --- /dev/null +++ b/modules/ximgproc/samples/fourier_descriptors_demo.py @@ -0,0 +1,169 @@ +import numpy as np +import cv2 as cv +import math + +class ThParameters: + def __init__(self): + self.levelNoise=6 + self.angle=45 + self.scale10=5 + self.origin=10 + self.xg=150 + self.yg=150 + self.update=True + +def UpdateShape(x ): + p.update = True + +def union(a,b): + x = min(a[0], b[0]) + y = min(a[1], b[1]) + w = max(a[0]+a[2], b[0]+b[2]) - x + h = max(a[1]+a[3], b[1]+b[3]) - y + return (x, y, w, h) + +def intersection(a,b): + x = max(a[0], b[0]) + y = max(a[1], b[1]) + w = min(a[0]+a[2], b[0]+b[2]) - x + h = min(a[1]+a[3], b[1]+b[3]) - y + if w<0 or h<0: return () # or (0,0,0,0) ? + return (x, y, w, h) + +def NoisyPolygon(pRef,n): +# vector c + p = pRef; +# vector > contour; + p = p+n*np.random.random_sample((p.shape[0],p.shape[1]))-n/2.0 + if (n==0): + return p + c = np.empty(shape=[0, 2]) + minX = p[0][0] + maxX = p[0][0] + minY = p[0][1] + maxY = p[0][1] + for i in range( 0,p.shape[0]): + next = i + 1; + if (next == p.shape[0]): + next = 0; + u = p[next] - p[i] + d = int(cv.norm(u)) + a = np.arctan2(u[1], u[0]) + step = 1 + if (n != 0): + step = d // n + for j in range( 1,int(d),int(max(step, 1))): + while True: + pAct = (u*j) / (d) + r = n*np.random.random_sample() + theta = a + 2*math.pi*np.random.random_sample() +# pNew = Point(Point2d(r*cos(theta) + pAct.x + p[i].x, r*sin(theta) + pAct.y + p[i].y)); + pNew = np.array([(r*np.cos(theta) + pAct[0] + p[i][0], r*np.sin(theta) + pAct[1] + p[i][1])]) + if (pNew[0][0]>=0 and pNew[0][1]>=0): + break + if (pNew[0][0]maxX): + maxX = pNew[0][0] + if (pNew[0][1]maxY): + maxY = pNew[0][1] + c = np.append(c,pNew,axis = 0) + return c + +#static vector NoisyPolygon(vector pRef, double n); +#static void UpdateShape(int , void *r); +#static void AddSlider(String sliderName, String windowName, int minSlider, int maxSlider, int valDefault, int *valSlider, void(*f)(int, void *), void *r); +def AddSlider(sliderName,windowName,minSlider,maxSlider,valDefault, update): + cv.createTrackbar(sliderName, windowName, valDefault,maxSlider-minSlider+1, update) + cv.setTrackbarMin(sliderName, windowName, minSlider) + cv.setTrackbarMax(sliderName, windowName, maxSlider) + cv.setTrackbarPos(sliderName, windowName, valDefault) + +# vector ctrRef; +# vector ctrRotate, ctrNoisy, ctrNoisyRotate, ctrNoisyRotateShift; +# // build a shape with 5 vertex +ctrRef = np.array([(250,250),(400, 250),(400, 300),(250, 300),(180, 270)]) +cg = np.mean(ctrRef,axis=0) +p=ThParameters() +cv.namedWindow("FD Curve matching"); +# A rotation with center at (150,150) of angle 45 degrees and a scaling of 5/10 +AddSlider("Noise", "FD Curve matching", 0, 20, p.levelNoise, UpdateShape) +AddSlider("Angle", "FD Curve matching", 0, 359, p.angle, UpdateShape) +AddSlider("Scale", "FD Curve matching", 5, 100, p.scale10, UpdateShape) +AddSlider("Origin", "FD Curve matching", 0, 100, p.origin, UpdateShape) +AddSlider("Xg", "FD Curve matching", 150, 450, p.xg, UpdateShape) +AddSlider("Yg", "FD Curve matching", 150, 450, p.yg, UpdateShape) +code = 0 +img = np.zeros((300,512,3), np.uint8) +print ("******************** PRESS g TO MATCH CURVES *************\n") + +while (code!=27): + code = cv.waitKey(60) + if p.update: + p.levelNoise=cv.getTrackbarPos('Noise','FD Curve matching') + p.angle=cv.getTrackbarPos('Angle','FD Curve matching') + p.scale10=cv.getTrackbarPos('Scale','FD Curve matching') + p.origin=cv.getTrackbarPos('Origin','FD Curve matching') + p.xg=cv.getTrackbarPos('Xg','FD Curve matching') + p.yg=cv.getTrackbarPos('Yg','FD Curve matching') + + r = cv.getRotationMatrix2D((p.xg, p.yg), angle=p.angle, scale=10.0/ p.scale10); + ctrNoisy= NoisyPolygon(ctrRef,p.levelNoise) + ctrNoisy1 = np.reshape(ctrNoisy,(ctrNoisy.shape[0],1,2)) + ctrNoisyRotate = cv.transform(ctrNoisy1,r) + ctrNoisyRotateShift = np.empty([ctrNoisyRotate.shape[0],1,2],dtype=np.int32) + for i in range(0,ctrNoisy.shape[0]): + k=(i+(p.origin*ctrNoisy.shape[0])//100)% ctrNoisyRotate.shape[0] + ctrNoisyRotateShift[i] = ctrNoisyRotate[k] +# To draw contour using drawcontours + cc= np.reshape(ctrNoisyRotateShift,[ctrNoisyRotateShift.shape[0],2]) + c = [ ctrRef,cc] + p.update = False; + rglobal =(0,0,0,0) + for i in range(0,2): + r = cv.boundingRect(c[i]) + rglobal = union(rglobal,r) + r = list(rglobal) + r[2] = r[2]+10 + r[3] = r[3]+10 + rglobal = tuple(r) + img = np.zeros((2 * rglobal[3], 2 * rglobal[2], 3), np.uint8) + cv.drawContours(img, c, 0, (255,0,0),1); + cv.drawContours(img, c, 1, (0, 255, 0),1); + cv.circle(img, tuple(c[0][0]), 5, (255, 0, 0),3); + cv.circle(img, tuple(c[1][0]), 5, (0, 255, 0),3); + cv.imshow("FD Curve matching", img); + if code == ord('d') : + cv.destroyWindow("FD Curve matching"); + cv.namedWindow("FD Curve matching"); +# A rotation with center at (150,150) of angle 45 degrees and a scaling of 5/10 + AddSlider("Noise", "FD Curve matching", 0, 20, p.levelNoise, UpdateShape) + AddSlider("Angle", "FD Curve matching", 0, 359, p.angle, UpdateShape) + AddSlider("Scale", "FD Curve matching", 5, 100, p.scale10, UpdateShape) + AddSlider("Origin%%", "FD Curve matching", 0, 100, p.origin, UpdateShape) + AddSlider("Xg", "FD Curve matching", 150, 450, p.xg, UpdateShape) + AddSlider("Yg", "FD Curve matching", 150, 450, p.yg, UpdateShape) + if code == ord('g'): + fit = cv.ximgproc.createContourFitting(1024,16); +# sampling contour we want 256 points + cn= np.reshape(ctrRef,[ctrRef.shape[0],1,2]) + + ctrRef2d = cv.ximgproc.contourSampling(cn, 256) + ctrRot2d = cv.ximgproc.contourSampling(ctrNoisyRotateShift, 256) + fit.setFDSize(16) + c1 = ctrRef2d + c2 = ctrRot2d + alphaPhiST, dist = fit.estimateTransformation(ctrRot2d, ctrRef2d) + print( "Transform *********\n Origin = ", 1-alphaPhiST[0,0] ," expected ", p.origin / 100. ,"\n") + print( "Angle = ", alphaPhiST[0,1] * 180 / math.pi ," expected " , p.angle,"\n") + print( "Scale = " ,alphaPhiST[0,2] ," expected " , p.scale10 / 10.0 , "\n") + dst = cv.ximgproc.transformFD(ctrRot2d, alphaPhiST,cn, False); + ctmp= np.reshape(dst,[dst.shape[0],2]) + cdst=ctmp.astype(int) + + c = [ ctrRef,cc,cdst] + cv.drawContours(img, c, 2, (0,0,255),1); + cv.circle(img, (int(c[2][0][0]),int(c[2][0][1])), 5, (0, 0, 255),5); + cv.imshow("FD Curve matching", img); diff --git a/modules/ximgproc/src/fourier_descriptors.cpp b/modules/ximgproc/src/fourier_descriptors.cpp index a06c29f0d..a1d8201f6 100644 --- a/modules/ximgproc/src/fourier_descriptors.cpp +++ b/modules/ximgproc/src/fourier_descriptors.cpp @@ -5,7 +5,6 @@ #include "precomp.hpp" #include #include -#include /* If you use this code please cite this @cite BergerRaghunathan1998 @@ -107,7 +106,7 @@ void ContourFitting::estimateTransformation(InputArray _src, InputArray _ref, Ou void ContourFitting::estimateTransformation(InputArray _src, InputArray _ref, OutputArray _alphaPhiST,double *distFin, bool fdContour) { if (!fdContour) - CV_Assert( _src.kind() == _InputArray::STD_VECTOR && _ref.kind() == _InputArray::STD_VECTOR); + CV_Assert( (_src.kind() == _InputArray::STD_VECTOR || _src.kind() == _InputArray::MAT) && (_ref.kind() == _InputArray::STD_VECTOR || _ref.kind() == _InputArray::MAT)); else CV_Assert(fdContour && _src.kind() == _InputArray::MAT && _ref.kind() == _InputArray::MAT); CV_Assert(_src.channels() == 2 && _ref.channels() == 2); @@ -220,6 +219,8 @@ void fourierDescriptor(InputArray _src, OutputArray _dst, int nbElt, int nbFD) Mat Z; if (z.rows*z.cols!=nbElt) contourSampling(_src, z,nbElt); + else if (_src.depth() == CV_32S) + z.convertTo(z, CV_32F); dft(z, Z, DFT_SCALE | DFT_REAL_OUTPUT); if (nbFD == -1) { @@ -250,13 +251,12 @@ void contourSampling(InputArray _src, OutputArray _out, int nbElt) } CV_Assert(ctr.rows==1 || ctr.cols==1); double l1 = 0, l2, p, d, s; - // AutoBuffer _buf(nbElt); Mat r; if (ctr.rows==1) ctr=ctr.t(); int j = 0; int nb = ctr.rows; - p = arcLength(_src, true); + p = arcLength(ctr, true); l2 = norm(ctr.row(j) - ctr.row(j + 1)) / p; for (int i = 0; i(0,0)); } } r.copyTo(_out); @@ -284,7 +283,7 @@ void contourSampling(InputArray _src, OutputArray _out, int nbElt) void transformFD(InputArray _src, InputArray _t,OutputArray _dst, bool fdContour) { if (!fdContour) - CV_Assert(_src.kind() == _InputArray::STD_VECTOR); + CV_Assert(_src.kind() == _InputArray::STD_VECTOR || _src.kind() == _InputArray::MAT); else CV_Assert( _src.kind() == _InputArray::MAT ); CV_Assert(_src.channels() == 2); diff --git a/modules/ximgproc/test/test_fourier_descriptors.cpp b/modules/ximgproc/test/test_fourier_descriptors.cpp new file mode 100644 index 000000000..61f6b8771 --- /dev/null +++ b/modules/ximgproc/test/test_fourier_descriptors.cpp @@ -0,0 +1,90 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. + +#include "test_precomp.hpp" + +namespace opencv_test { namespace { + + +TEST(ximpgroc_fourierdescriptors,test_FD_AND_FIT) +{ + Mat fd; + vector ctr(16); + float Rx = 100, Ry = 100; + Point2f g(0, 0); + float angleOri = 0; + for (int i = 0; i < static_cast(ctr.size()); i++) + { + float theta = static_cast(2 * CV_PI / static_cast(ctr.size()) * i + angleOri); + ctr[i] = Point2f(Rx * cos(theta) + g.x, Ry * sin(theta) + g.y); + + } + ximgproc::fourierDescriptor(ctr, fd); + CV_Assert(cv::norm(fd.at(0, 0)) < ctr.size() * FLT_EPSILON && cv::norm(fd.at(0, 1) - Vec2f(Rx, 0)) < ctr.size() * FLT_EPSILON); + Rx = 100, Ry = 50; + g = Point2f(50, 20); + for (int i = 0; i < static_cast(ctr.size()); i++) + { + float theta = static_cast(2 * CV_PI / static_cast(ctr.size()) * i + angleOri); + ctr[i] = Point2f(Rx * cos(theta) + g.x, Ry * sin(theta) + g.y); + } + ximgproc::fourierDescriptor(ctr, fd); + CV_Assert(cv::norm(fd.at(0, 0) - Vec2f(g)) < 1 && + fabs(fd.at(0, 1)[0] + fd.at(0, static_cast(ctr.size()) - 1)[0] - Rx) < 1 && + fabs(fd.at(0, 1)[0] - fd.at(0, static_cast(ctr.size()) - 1)[0] - Ry) < 1); + Rx = 70, Ry = 100; + g = Point2f(30, 100); + angleOri = static_cast(CV_PI / 4); + for (int i = 0; i < static_cast(ctr.size()); i++) + { + float theta = static_cast(2 * CV_PI / static_cast(ctr.size()) * i + CV_PI / 4); + ctr[i] = Point2f(Rx * cos(theta) + g.x, Ry * sin(theta) + g.y); + } + ximgproc::fourierDescriptor(ctr, fd); + CV_Assert(cv::norm(fd.at(0, 0) - Vec2f(g)) < 1); + CV_Assert(cv::norm(Vec2f((Rx + Ry)*cos(angleOri) / 2, (Rx + Ry)*sin(angleOri) / 2) - fd.at(0, 1)) < 1); + CV_Assert(cv::norm(Vec2f((Rx - Ry)*cos(angleOri) / 2, -(Rx - Ry)*sin(angleOri) / 2) - fd.at(0, static_cast(ctr.size()) - 1)) < 1); + + RNG rAlea; + g.x = 0; g.y = 0; + ctr.resize(256); + for (int i = 0; i < static_cast(ctr.size()); i++) + { + ctr[i] = Point2f(rAlea.uniform(0.0F, 1.0F), rAlea.uniform(0.0F, 1.0F)); + g += ctr[i]; + } + g.x = g.x / ctr.size(); + g.y = g.y / ctr.size(); + double rotAngle = 35; + double s = 0.1515; + Mat r = getRotationMatrix2D(g, rotAngle, 0.1515); + vector unknownCtr; + vector ctrShift; + int valShift = 170; + for (int i = 0; i < static_cast(ctr.size()); i++) + ctrShift.push_back(ctr[(i + valShift) % ctr.size()]); + cv::transform(ctrShift, unknownCtr, r); + ximgproc::ContourFitting fit; + fit.setFDSize(16); + Mat t; + double dist; + fit.estimateTransformation(unknownCtr, ctr, t, &dist, false); + CV_Assert(fabs(t.at(0, 0)*ctr.size() + valShift) < 10 || fabs((1 - t.at(0, 0))*ctr.size() - valShift) < 10); + CV_Assert(fabs(t.at(0, 1) - rotAngle / 180.*CV_PI) < 0.1); + CV_Assert(fabs(t.at(0, 2) - 1 / s) < 0.1); + ctr.resize(4); + ctr[0] = Point2f(0, 0); + ctr[1] = Point2f(16, 0); + ctr[2] = Point2f(16, 16); + ctr[3] = Point2f(0, 16); + double squareArea = contourArea(ctr), lengthSquare = arcLength(ctr, true); + Mat ctrs; + ximgproc::contourSampling(ctr, ctrs, 64); + CV_Assert(fabs(squareArea - contourArea(ctrs)) < FLT_EPSILON); + CV_Assert(fabs(lengthSquare - arcLength(ctrs, true)) < FLT_EPSILON); +} + + + +}} // namespace From 9757b7180654eaa36b6ac2c9157f9372e3491e17 Mon Sep 17 00:00:00 2001 From: Unknown Date: Mon, 21 May 2018 17:57:07 -0700 Subject: [PATCH 03/97] minor fix to allow learn_color_balance.py to work with python 3+ map object returns an iterator, not a list, in python 3. fix: list(map()) is still compatible with python 2 --- modules/xphoto/samples/learn_color_balance.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/xphoto/samples/learn_color_balance.py b/modules/xphoto/samples/learn_color_balance.py index 6b2160985..bd67611e8 100644 --- a/modules/xphoto/samples/learn_color_balance.py +++ b/modules/xphoto/samples/learn_color_balance.py @@ -221,7 +221,7 @@ if __name__ == '__main__': "specify the -g parameter")) sys.exit(1) - img_range = map(int,parse_sequence(args.range)) + img_range = list(map(int,parse_sequence(args.range))) if len(img_range)!=2: print("Error: Please specify the -r parameter in form ,") sys.exit(1) From 42a889ef4f204ce308ce88c98040d71307df0556 Mon Sep 17 00:00:00 2001 From: Rostislav Vasilikhin Date: Thu, 31 May 2018 14:18:25 +0300 Subject: [PATCH 04/97] KinectFusion implemented (#1627) * empty kinfu module created * KinFu: skeleton is done * some intermediate state fixed * fixed normal calculation * bilinear depth interp: fixing missing data * TSDF integration optimized * TSDF: adding constness * utils: isNaN; Intr::Projector const reference fixed * TSDF raycast: quality improvements * TSDF fetchCloud is done * render() added * ICP implemented * debug code moved to demo.cpp * less TODOs * partial refactoring * TSDF: fetchPoints() and fetchNormals() rewritten in parallel manner * platform choose added * reordered * data types isolated off the platform * minor fixes * ScopeTime added * fixed iterations gathering * volume::integrate() parallelized but works slow (big overhead for * raycast is done in parallel * got rid of kftype and p3type * fetchNormals() fixed * less code duplication * nan check reduced, interpolate() refactored to fetchVoxel() * ICP: optimizations * TSDF: bilinear specialized * TSDF: voxelSizeInv pushed away * TSDF: interpolation optimized * TSDF::integrate: parallel_for now works fast * Frame::render: pow -> float ipow(x) * ICP::getAb: parallel_for * ICP::getAb: time print disabled * ICP::getAb::bilinear: 2 calls joined * refactored, extra functions removed * optimized to use only 27 elems * ICP::getAb: better optimized * Points and Normals data type expanded to 4 channels * ICP optimized (doesn't work) * ICP::getAb is on intrinsics and it works * NaN check is faster * ICP::getAB: minors * added non-SIMD code as fallback * TSDF::fetchVoxel and interpolation: got rid of coord check * TSDF::fetchVoxel: refactor * TSDF::raycast: local copies of members * TSDF::interpolate: refactored for simplier vectorization * TSDF::getNormal: refactored for simplier vectorization * minor * include "intrin.hpp" moved to precomp.hpp * TSDF::coords shifts moved to class body * TSDF::getNormal vectorized * TSDF::getNormal: little improvements * TSDF::interpolate: little improvements * TSDF::raycast vectorized * more to precomp.hpp * TSDF: minor optimizations * TSDF::raycast cycles optimized * TSDF::fetchPointsNormals instead of separate p and n * TSDF::bilinearInterpolate: little speedup * TSDF::interpolate: speed up * TSDF::interpolate: more compact code * TSDF::getNormal and raycast main cycle made faster * ICP: few improvements * Frame: a lot of parts parallelized * TSDF::fetchPointsNormals minor improvements * TSDF::integrate and bilinear vectorized * TSDF::interpolate and getNormal: interpolation vectorized * ICP: minor changes * gradientDeltaFactor removed, coarseParams() added * TSDF::raycast: fixed bug with tmin/tmax * minors * baseZ fixed * ICP: interpolation fixed, non-parallelized code fixed * TSDF::interpolate: bilinear fixed, less artifacts * TSDF: minor refactoring * TSDF: some members moved to parent class * added tests for KinFu * KinFu documented * docs fixed * warnings fixed * license added, overrides added * minors * ScopeTime moved to separate file * less memory allocations * demo improved, java binding disabled * viz module made optional * fix to demo * frameGenerator interface: got rid of refs to cv::Ptr * demo made interactive * trying to fix build * trying to fix warnings * warning fixed * demo fixed * raycast_step_factor tuned * legal info added * don't reset if ICP failed * refactoring: KinFu::operator() => update() * KinFu::KinFuParams => ::Params * get/setParams * fetch => get * all src moved to cv::kinfu namespace * struct Intr made internal * kinfu_module merged into rgbd module * License preambule updated * minors * frame.* renamed to kinfu_frame.* * warnings fixed * more warnings fixed * RGBD normals: a fix against Inf/Nan values * FastICP: fixed transformation direction * RGBD Odometry tests: added epsilon for id transform; minors * RGBD Odometry tests enabled * modules list fixed --- modules/README.md | 2 +- modules/rgbd/CMakeLists.txt | 2 +- modules/rgbd/LICENSE_KinectFusion.md | 27 + modules/rgbd/LICENSE_WillowGarage.md | 31 + modules/rgbd/README.md | 15 +- modules/rgbd/doc/rgbd.bib | 18 + modules/rgbd/include/opencv2/rgbd.hpp | 1072 +-------------- modules/rgbd/include/opencv2/rgbd/depth.hpp | 1173 ++++++++++++++++ modules/rgbd/include/opencv2/rgbd/kinfu.hpp | 211 +++ modules/rgbd/include/opencv2/rgbd/linemod.hpp | 53 +- modules/rgbd/samples/CMakeLists.txt | 9 - modules/rgbd/samples/kinfu_demo.cpp | 235 ++++ modules/rgbd/samples/linemod.cpp | 6 + modules/rgbd/samples/odometry_evaluation.cpp | 41 +- modules/rgbd/src/depth_cleaner.cpp | 39 +- modules/rgbd/src/depth_registration.cpp | 47 +- modules/rgbd/src/depth_to_3d.cpp | 50 +- .../src/{depth_to_3d.h => depth_to_3d.hpp} | 46 +- modules/rgbd/src/fast_icp.cpp | 519 +++++++ modules/rgbd/src/fast_icp.hpp | 39 + modules/rgbd/src/kinfu.cpp | 319 +++++ modules/rgbd/src/kinfu_frame.cpp | 459 +++++++ modules/rgbd/src/kinfu_frame.hpp | 122 ++ modules/rgbd/src/linemod.cpp | 46 +- modules/rgbd/src/normal.cpp | 50 +- modules/rgbd/src/normal_lut.i | 402 +++++- modules/rgbd/src/odometry.cpp | 170 ++- modules/rgbd/src/plane.cpp | 39 +- modules/rgbd/src/precomp.hpp | 56 +- modules/rgbd/src/tsdf.cpp | 1218 +++++++++++++++++ modules/rgbd/src/tsdf.hpp | 47 + modules/rgbd/src/utils.cpp | 84 +- modules/rgbd/src/utils.h | 81 -- modules/rgbd/src/utils.hpp | 153 +++ modules/rgbd/test/test_kinfu.cpp | 343 +++++ modules/rgbd/test/test_main.cpp | 7 +- modules/rgbd/test/test_normal.cpp | 39 +- modules/rgbd/test/test_odometry.cpp | 74 +- modules/rgbd/test/test_precomp.hpp | 7 +- modules/rgbd/test/test_registration.cpp | 46 +- modules/rgbd/test/test_utils.cpp | 7 +- 41 files changed, 5656 insertions(+), 1748 deletions(-) create mode 100644 modules/rgbd/LICENSE_KinectFusion.md create mode 100644 modules/rgbd/LICENSE_WillowGarage.md create mode 100644 modules/rgbd/doc/rgbd.bib create mode 100755 modules/rgbd/include/opencv2/rgbd/depth.hpp create mode 100644 modules/rgbd/include/opencv2/rgbd/kinfu.hpp delete mode 100644 modules/rgbd/samples/CMakeLists.txt create mode 100644 modules/rgbd/samples/kinfu_demo.cpp rename modules/rgbd/src/{depth_to_3d.h => depth_to_3d.hpp} (57%) create mode 100644 modules/rgbd/src/fast_icp.cpp create mode 100644 modules/rgbd/src/fast_icp.hpp create mode 100644 modules/rgbd/src/kinfu.cpp create mode 100644 modules/rgbd/src/kinfu_frame.cpp create mode 100644 modules/rgbd/src/kinfu_frame.hpp create mode 100644 modules/rgbd/src/tsdf.cpp create mode 100644 modules/rgbd/src/tsdf.hpp delete mode 100644 modules/rgbd/src/utils.h create mode 100644 modules/rgbd/src/utils.hpp create mode 100644 modules/rgbd/test/test_kinfu.cpp diff --git a/modules/README.md b/modules/README.md index 6d51a4db4..02db5a8f5 100644 --- a/modules/README.md +++ b/modules/README.md @@ -48,7 +48,7 @@ $ cmake -D OPENCV_EXTRA_MODULES_PATH=/modules -D BUILD_opencv_ -#include /** @defgroup rgbd RGB-Depth Processing */ -namespace cv -{ -namespace rgbd -{ - -//! @addtogroup rgbd -//! @{ - - /** Checks if the value is a valid depth. For CV_16U or CV_16S, the convention is to be invalid if it is - * a limit. For a float/double, we just check if it is a NaN - * @param depth the depth to check for validity - */ - CV_EXPORTS - inline bool - isValidDepth(const float & depth) - { - return !cvIsNaN(depth); - } - CV_EXPORTS - inline bool - isValidDepth(const double & depth) - { - return !cvIsNaN(depth); - } - CV_EXPORTS - inline bool - isValidDepth(const short int & depth) - { - return (depth != std::numeric_limits::min()) && (depth != std::numeric_limits::max()); - } - CV_EXPORTS - inline bool - isValidDepth(const unsigned short int & depth) - { - return (depth != std::numeric_limits::min()) - && (depth != std::numeric_limits::max()); - } - CV_EXPORTS - inline bool - isValidDepth(const int & depth) - { - return (depth != std::numeric_limits::min()) && (depth != std::numeric_limits::max()); - } - CV_EXPORTS - inline bool - isValidDepth(const unsigned int & depth) - { - return (depth != std::numeric_limits::min()) && (depth != std::numeric_limits::max()); - } - - /** Object that can compute the normals in an image. - * It is an object as it can cache data for speed efficiency - * The implemented methods are either: - * - FALS (the fastest) and SRI from - * ``Fast and Accurate Computation of Surface Normals from Range Images`` - * by H. Badino, D. Huber, Y. Park and T. Kanade - * - the normals with bilateral filtering on a depth image from - * ``Gradient Response Maps for Real-Time Detection of Texture-Less Objects`` - * by S. Hinterstoisser, C. Cagniart, S. Ilic, P. Sturm, N. Navab, P. Fua, and V. Lepetit - */ - class CV_EXPORTS_W RgbdNormals: public Algorithm - { - public: - enum RGBD_NORMALS_METHOD - { - RGBD_NORMALS_METHOD_FALS = 0, - RGBD_NORMALS_METHOD_LINEMOD = 1, - RGBD_NORMALS_METHOD_SRI = 2 - }; - - RgbdNormals() - : - rows_(0), - cols_(0), - depth_(0), - K_(Mat()), - window_size_(0), - method_(RGBD_NORMALS_METHOD_FALS), - rgbd_normals_impl_(0) - { - } - - /** Constructor - * @param rows the number of rows of the depth image normals will be computed on - * @param cols the number of cols of the depth image normals will be computed on - * @param depth the depth of the normals (only CV_32F or CV_64F) - * @param K the calibration matrix to use - * @param window_size the window size to compute the normals: can only be 1,3,5 or 7 - * @param method one of the methods to use: RGBD_NORMALS_METHOD_SRI, RGBD_NORMALS_METHOD_FALS - */ - RgbdNormals(int rows, int cols, int depth, InputArray K, int window_size = 5, int method = - RgbdNormals::RGBD_NORMALS_METHOD_FALS); - - ~RgbdNormals(); - - CV_WRAP static Ptr create(int rows, int cols, int depth, InputArray K, int window_size = 5, int method = - RgbdNormals::RGBD_NORMALS_METHOD_FALS); - - /** Given a set of 3d points in a depth image, compute the normals at each point. - * @param points a rows x cols x 3 matrix of CV_32F/CV64F or a rows x cols x 1 CV_U16S - * @param normals a rows x cols x 3 matrix - */ - void - operator()(InputArray points, OutputArray normals) const; - - /** Initializes some data that is cached for later computation - * If that function is not called, it will be called the first time normals are computed - */ - CV_WRAP void - initialize() const; - - CV_WRAP int getRows() const - { - return rows_; - } - CV_WRAP void setRows(int val) - { - rows_ = val; - } - CV_WRAP int getCols() const - { - return cols_; - } - CV_WRAP void setCols(int val) - { - cols_ = val; - } - CV_WRAP int getWindowSize() const - { - return window_size_; - } - CV_WRAP void setWindowSize(int val) - { - window_size_ = val; - } - CV_WRAP int getDepth() const - { - return depth_; - } - CV_WRAP void setDepth(int val) - { - depth_ = val; - } - CV_WRAP cv::Mat getK() const - { - return K_; - } - CV_WRAP void setK(const cv::Mat &val) - { - K_ = val; - } - CV_WRAP int getMethod() const - { - return method_; - } - CV_WRAP void setMethod(int val) - { - method_ = val; - } - - protected: - void - initialize_normals_impl(int rows, int cols, int depth, const Mat & K, int window_size, int method) const; - - int rows_, cols_, depth_; - Mat K_; - int window_size_; - int method_; - mutable void* rgbd_normals_impl_; - }; - - /** Object that can clean a noisy depth image - */ - class CV_EXPORTS_W DepthCleaner: public Algorithm - { - public: - /** NIL method is from - * ``Modeling Kinect Sensor Noise for Improved 3d Reconstruction and Tracking`` - * by C. Nguyen, S. Izadi, D. Lovel - */ - enum DEPTH_CLEANER_METHOD - { - DEPTH_CLEANER_NIL - }; - - DepthCleaner() - : - depth_(0), - window_size_(0), - method_(DEPTH_CLEANER_NIL), - depth_cleaner_impl_(0) - { - } - - /** Constructor - * @param depth the depth of the normals (only CV_32F or CV_64F) - * @param window_size the window size to compute the normals: can only be 1,3,5 or 7 - * @param method one of the methods to use: RGBD_NORMALS_METHOD_SRI, RGBD_NORMALS_METHOD_FALS - */ - DepthCleaner(int depth, int window_size = 5, int method = DepthCleaner::DEPTH_CLEANER_NIL); - - ~DepthCleaner(); - - CV_WRAP static Ptr create(int depth, int window_size = 5, int method = DepthCleaner::DEPTH_CLEANER_NIL); - - /** Given a set of 3d points in a depth image, compute the normals at each point. - * @param points a rows x cols x 3 matrix of CV_32F/CV64F or a rows x cols x 1 CV_U16S - * @param depth a rows x cols matrix of the cleaned up depth - */ - void - operator()(InputArray points, OutputArray depth) const; - - /** Initializes some data that is cached for later computation - * If that function is not called, it will be called the first time normals are computed - */ - CV_WRAP void - initialize() const; - - CV_WRAP int getWindowSize() const - { - return window_size_; - } - CV_WRAP void setWindowSize(int val) - { - window_size_ = val; - } - CV_WRAP int getDepth() const - { - return depth_; - } - CV_WRAP void setDepth(int val) - { - depth_ = val; - } - CV_WRAP int getMethod() const - { - return method_; - } - CV_WRAP void setMethod(int val) - { - method_ = val; - } - - protected: - void - initialize_cleaner_impl() const; - - int depth_; - int window_size_; - int method_; - mutable void* depth_cleaner_impl_; - }; - - - /** Registers depth data to an external camera - * Registration is performed by creating a depth cloud, transforming the cloud by - * the rigid body transformation between the cameras, and then projecting the - * transformed points into the RGB camera. - * - * uv_rgb = K_rgb * [R | t] * z * inv(K_ir) * uv_ir - * - * Currently does not check for negative depth values. - * - * @param unregisteredCameraMatrix the camera matrix of the depth camera - * @param registeredCameraMatrix the camera matrix of the external camera - * @param registeredDistCoeffs the distortion coefficients of the external camera - * @param Rt the rigid body transform between the cameras. Transforms points from depth camera frame to external camera frame. - * @param unregisteredDepth the input depth data - * @param outputImagePlaneSize the image plane dimensions of the external camera (width, height) - * @param registeredDepth the result of transforming the depth into the external camera - * @param depthDilation whether or not the depth is dilated to avoid holes and occlusion errors (optional) - */ - CV_EXPORTS_W - void - registerDepth(InputArray unregisteredCameraMatrix, InputArray registeredCameraMatrix, InputArray registeredDistCoeffs, - InputArray Rt, InputArray unregisteredDepth, const Size& outputImagePlaneSize, - OutputArray registeredDepth, bool depthDilation=false); - - /** - * @param depth the depth image - * @param in_K - * @param in_points the list of xy coordinates - * @param points3d the resulting 3d points - */ - CV_EXPORTS_W - void - depthTo3dSparse(InputArray depth, InputArray in_K, InputArray in_points, OutputArray points3d); - - /** Converts a depth image to an organized set of 3d points. - * The coordinate system is x pointing left, y down and z away from the camera - * @param depth the depth image (if given as short int CV_U, it is assumed to be the depth in millimeters - * (as done with the Microsoft Kinect), otherwise, if given as CV_32F or CV_64F, it is assumed in meters) - * @param K The calibration matrix - * @param points3d the resulting 3d points. They are of depth the same as `depth` if it is CV_32F or CV_64F, and the - * depth of `K` if `depth` is of depth CV_U - * @param mask the mask of the points to consider (can be empty) - */ - CV_EXPORTS_W - void - depthTo3d(InputArray depth, InputArray K, OutputArray points3d, InputArray mask = noArray()); - - /** If the input image is of type CV_16UC1 (like the Kinect one), the image is converted to floats, divided - * by 1000 to get a depth in meters, and the values 0 are converted to std::numeric_limits::quiet_NaN() - * Otherwise, the image is simply converted to floats - * @param in the depth image (if given as short int CV_U, it is assumed to be the depth in millimeters - * (as done with the Microsoft Kinect), it is assumed in meters) - * @param depth the desired output depth (floats or double) - * @param out The rescaled float depth image - */ - CV_EXPORTS_W - void - rescaleDepth(InputArray in, int depth, OutputArray out); - - /** Object that can compute planes in an image - */ - class CV_EXPORTS_W RgbdPlane: public Algorithm - { - public: - enum RGBD_PLANE_METHOD - { - RGBD_PLANE_METHOD_DEFAULT - }; - - RgbdPlane(int method = RgbdPlane::RGBD_PLANE_METHOD_DEFAULT) - : - method_(method), - block_size_(40), - min_size_(block_size_*block_size_), - threshold_(0.01), - sensor_error_a_(0), - sensor_error_b_(0), - sensor_error_c_(0) - { - } - - /** Find The planes in a depth image - * @param points3d the 3d points organized like the depth image: rows x cols with 3 channels - * @param normals the normals for every point in the depth image - * @param mask An image where each pixel is labeled with the plane it belongs to - * and 255 if it does not belong to any plane - * @param plane_coefficients the coefficients of the corresponding planes (a,b,c,d) such that ax+by+cz+d=0, norm(a,b,c)=1 - * and c < 0 (so that the normal points towards the camera) - */ - void - operator()(InputArray points3d, InputArray normals, OutputArray mask, - OutputArray plane_coefficients); - - /** Find The planes in a depth image but without doing a normal check, which is faster but less accurate - * @param points3d the 3d points organized like the depth image: rows x cols with 3 channels - * @param mask An image where each pixel is labeled with the plane it belongs to - * and 255 if it does not belong to any plane - * @param plane_coefficients the coefficients of the corresponding planes (a,b,c,d) such that ax+by+cz+d=0 - */ - void - operator()(InputArray points3d, OutputArray mask, OutputArray plane_coefficients); - - CV_WRAP int getBlockSize() const - { - return block_size_; - } - CV_WRAP void setBlockSize(int val) - { - block_size_ = val; - } - CV_WRAP int getMinSize() const - { - return min_size_; - } - CV_WRAP void setMinSize(int val) - { - min_size_ = val; - } - CV_WRAP int getMethod() const - { - return method_; - } - CV_WRAP void setMethod(int val) - { - method_ = val; - } - CV_WRAP double getThreshold() const - { - return threshold_; - } - CV_WRAP void setThreshold(double val) - { - threshold_ = val; - } - CV_WRAP double getSensorErrorA() const - { - return sensor_error_a_; - } - CV_WRAP void setSensorErrorA(double val) - { - sensor_error_a_ = val; - } - CV_WRAP double getSensorErrorB() const - { - return sensor_error_b_; - } - CV_WRAP void setSensorErrorB(double val) - { - sensor_error_b_ = val; - } - CV_WRAP double getSensorErrorC() const - { - return sensor_error_c_; - } - CV_WRAP void setSensorErrorC(double val) - { - sensor_error_c_ = val; - } - - private: - /** The method to use to compute the planes */ - int method_; - /** The size of the blocks to look at for a stable MSE */ - int block_size_; - /** The minimum size of a cluster to be considered a plane */ - int min_size_; - /** How far a point can be from a plane to belong to it (in meters) */ - double threshold_; - /** coefficient of the sensor error with respect to the. All 0 by default but you want a=0.0075 for a Kinect */ - double sensor_error_a_, sensor_error_b_, sensor_error_c_; - }; - - /** Object that contains a frame data. - */ - struct CV_EXPORTS_W RgbdFrame - { - RgbdFrame(); - RgbdFrame(const Mat& image, const Mat& depth, const Mat& mask=Mat(), const Mat& normals=Mat(), int ID=-1); - virtual ~RgbdFrame(); - - CV_WRAP static Ptr create(const Mat& image=Mat(), const Mat& depth=Mat(), const Mat& mask=Mat(), const Mat& normals=Mat(), int ID=-1); - - CV_WRAP virtual void - release(); - - CV_PROP int ID; - CV_PROP Mat image; - CV_PROP Mat depth; - CV_PROP Mat mask; - CV_PROP Mat normals; - }; - - /** Object that contains a frame data that is possibly needed for the Odometry. - * It's used for the efficiency (to pass precomputed/cached data of the frame that participates - * in the Odometry processing several times). - */ - struct CV_EXPORTS_W OdometryFrame : public RgbdFrame - { - /** These constants are used to set a type of cache which has to be prepared depending on the frame role: - * srcFrame or dstFrame (see compute method of the Odometry class). For the srcFrame and dstFrame different cache data may be required, - * some part of a cache may be common for both frame roles. - * @param CACHE_SRC The cache data for the srcFrame will be prepared. - * @param CACHE_DST The cache data for the dstFrame will be prepared. - * @param CACHE_ALL The cache data for both srcFrame and dstFrame roles will be computed. - */ - enum - { - CACHE_SRC = 1, CACHE_DST = 2, CACHE_ALL = CACHE_SRC + CACHE_DST - }; - - OdometryFrame(); - OdometryFrame(const Mat& image, const Mat& depth, const Mat& mask=Mat(), const Mat& normals=Mat(), int ID=-1); - - CV_WRAP static Ptr create(const Mat& image=Mat(), const Mat& depth=Mat(), const Mat& mask=Mat(), const Mat& normals=Mat(), int ID=-1); - - CV_WRAP virtual void - release() CV_OVERRIDE; - - CV_WRAP void - releasePyramids(); - - CV_PROP std::vector pyramidImage; - CV_PROP std::vector pyramidDepth; - CV_PROP std::vector pyramidMask; - - CV_PROP std::vector pyramidCloud; - - CV_PROP std::vector pyramid_dI_dx; - CV_PROP std::vector pyramid_dI_dy; - CV_PROP std::vector pyramidTexturedMask; - - CV_PROP std::vector pyramidNormals; - CV_PROP std::vector pyramidNormalsMask; - }; - - /** Base class for computation of odometry. - */ - class CV_EXPORTS_W Odometry: public Algorithm - { - public: - - /** A class of transformation*/ - enum - { - ROTATION = 1, TRANSLATION = 2, RIGID_BODY_MOTION = 4 - }; - - CV_WRAP static inline float - DEFAULT_MIN_DEPTH() - { - return 0.f; // in meters - } - CV_WRAP static inline float - DEFAULT_MAX_DEPTH() - { - return 4.f; // in meters - } - CV_WRAP static inline float - DEFAULT_MAX_DEPTH_DIFF() - { - return 0.07f; // in meters - } - CV_WRAP static inline float - DEFAULT_MAX_POINTS_PART() - { - return 0.07f; // in [0, 1] - } - CV_WRAP static inline float - DEFAULT_MAX_TRANSLATION() - { - return 0.15f; // in meters - } - CV_WRAP static inline float - DEFAULT_MAX_ROTATION() - { - return 15; // in degrees - } - - /** Method to compute a transformation from the source frame to the destination one. - * Some odometry algorithms do not used some data of frames (eg. ICP does not use images). - * In such case corresponding arguments can be set as empty Mat. - * The method returns true if all internal computions were possible (e.g. there were enough correspondences, - * system of equations has a solution, etc) and resulting transformation satisfies some test if it's provided - * by the Odometry inheritor implementation (e.g. thresholds for maximum translation and rotation). - * @param srcImage Image data of the source frame (CV_8UC1) - * @param srcDepth Depth data of the source frame (CV_32FC1, in meters) - * @param srcMask Mask that sets which pixels have to be used from the source frame (CV_8UC1) - * @param dstImage Image data of the destination frame (CV_8UC1) - * @param dstDepth Depth data of the destination frame (CV_32FC1, in meters) - * @param dstMask Mask that sets which pixels have to be used from the destination frame (CV_8UC1) - * @param Rt Resulting transformation from the source frame to the destination one (rigid body motion): - dst_p = Rt * src_p, where dst_p is a homogeneous point in the destination frame and src_p is - homogeneous point in the source frame, - Rt is 4x4 matrix of CV_64FC1 type. - * @param initRt Initial transformation from the source frame to the destination one (optional) - */ - CV_WRAP bool - compute(const Mat& srcImage, const Mat& srcDepth, const Mat& srcMask, const Mat& dstImage, const Mat& dstDepth, - const Mat& dstMask, OutputArray Rt, const Mat& initRt = Mat()) const; - - /** One more method to compute a transformation from the source frame to the destination one. - * It is designed to save on computing the frame data (image pyramids, normals, etc.). - */ - CV_WRAP_AS(compute2) bool - compute(Ptr& srcFrame, Ptr& dstFrame, OutputArray Rt, const Mat& initRt = Mat()) const; - - /** Prepare a cache for the frame. The function checks the precomputed/passed data (throws the error if this data - * does not satisfy) and computes all remaining cache data needed for the frame. Returned size is a resolution - * of the prepared frame. - * @param frame The odometry which will process the frame. - * @param cacheType The cache type: CACHE_SRC, CACHE_DST or CACHE_ALL. - */ - CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const; - - CV_WRAP static Ptr create(const String & odometryType); - - /** @see setCameraMatrix */ - CV_WRAP virtual cv::Mat getCameraMatrix() const = 0; - /** @copybrief getCameraMatrix @see getCameraMatrix */ - CV_WRAP virtual void setCameraMatrix(const cv::Mat &val) = 0; - /** @see setTransformType */ - CV_WRAP virtual int getTransformType() const = 0; - /** @copybrief getTransformType @see getTransformType */ - CV_WRAP virtual void setTransformType(int val) = 0; - - protected: - virtual void - checkParams() const = 0; - - virtual bool - computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, - const Mat& initRt) const = 0; - }; - - /** Odometry based on the paper "Real-Time Visual Odometry from Dense RGB-D Images", - * F. Steinbucker, J. Strum, D. Cremers, ICCV, 2011. - */ - class CV_EXPORTS_W RgbdOdometry: public Odometry - { - public: - RgbdOdometry(); - /** Constructor. - * @param cameraMatrix Camera matrix - * @param minDepth Pixels with depth less than minDepth will not be used (in meters) - * @param maxDepth Pixels with depth larger than maxDepth will not be used (in meters) - * @param maxDepthDiff Correspondences between pixels of two given frames will be filtered out - * if their depth difference is larger than maxDepthDiff (in meters) - * @param iterCounts Count of iterations on each pyramid level. - * @param minGradientMagnitudes For each pyramid level the pixels will be filtered out - * if they have gradient magnitude less than minGradientMagnitudes[level]. - * @param maxPointsPart The method uses a random pixels subset of size frameWidth x frameHeight x pointsPart - * @param transformType Class of transformation - */ - RgbdOdometry(const Mat& cameraMatrix, float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), - float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), const std::vector& iterCounts = std::vector(), - const std::vector& minGradientMagnitudes = std::vector(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), - int transformType = Odometry::RIGID_BODY_MOTION); - - CV_WRAP static Ptr create(const Mat& cameraMatrix = Mat(), float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), - float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), const std::vector& iterCounts = std::vector(), - const std::vector& minGradientMagnitudes = std::vector(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), - int transformType = Odometry::RIGID_BODY_MOTION); - - CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const CV_OVERRIDE; - - CV_WRAP cv::Mat getCameraMatrix() const CV_OVERRIDE - { - return cameraMatrix; - } - CV_WRAP void setCameraMatrix(const cv::Mat &val) CV_OVERRIDE - { - cameraMatrix = val; - } - CV_WRAP double getMinDepth() const - { - return minDepth; - } - CV_WRAP void setMinDepth(double val) - { - minDepth = val; - } - CV_WRAP double getMaxDepth() const - { - return maxDepth; - } - CV_WRAP void setMaxDepth(double val) - { - maxDepth = val; - } - CV_WRAP double getMaxDepthDiff() const - { - return maxDepthDiff; - } - CV_WRAP void setMaxDepthDiff(double val) - { - maxDepthDiff = val; - } - CV_WRAP cv::Mat getIterationCounts() const - { - return iterCounts; - } - CV_WRAP void setIterationCounts(const cv::Mat &val) - { - iterCounts = val; - } - CV_WRAP cv::Mat getMinGradientMagnitudes() const - { - return minGradientMagnitudes; - } - CV_WRAP void setMinGradientMagnitudes(const cv::Mat &val) - { - minGradientMagnitudes = val; - } - CV_WRAP double getMaxPointsPart() const - { - return maxPointsPart; - } - CV_WRAP void setMaxPointsPart(double val) - { - maxPointsPart = val; - } - CV_WRAP int getTransformType() const CV_OVERRIDE - { - return transformType; - } - CV_WRAP void setTransformType(int val) CV_OVERRIDE - { - transformType = val; - } - CV_WRAP double getMaxTranslation() const - { - return maxTranslation; - } - CV_WRAP void setMaxTranslation(double val) - { - maxTranslation = val; - } - CV_WRAP double getMaxRotation() const - { - return maxRotation; - } - CV_WRAP void setMaxRotation(double val) - { - maxRotation = val; - } - - protected: - virtual void - checkParams() const CV_OVERRIDE; - - virtual bool - computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, - const Mat& initRt) const CV_OVERRIDE; - - // Some params have commented desired type. It's due to AlgorithmInfo::addParams does not support it now. - /*float*/ - double minDepth, maxDepth, maxDepthDiff; - /*vector*/ - Mat iterCounts; - /*vector*/ - Mat minGradientMagnitudes; - double maxPointsPart; - - Mat cameraMatrix; - int transformType; - - double maxTranslation, maxRotation; - }; - - /** Odometry based on the paper "KinectFusion: Real-Time Dense Surface Mapping and Tracking", - * Richard A. Newcombe, Andrew Fitzgibbon, at al, SIGGRAPH, 2011. - */ - class CV_EXPORTS_W ICPOdometry: public Odometry - { - public: - ICPOdometry(); - /** Constructor. - * @param cameraMatrix Camera matrix - * @param minDepth Pixels with depth less than minDepth will not be used - * @param maxDepth Pixels with depth larger than maxDepth will not be used - * @param maxDepthDiff Correspondences between pixels of two given frames will be filtered out - * if their depth difference is larger than maxDepthDiff - * @param maxPointsPart The method uses a random pixels subset of size frameWidth x frameHeight x pointsPart - * @param iterCounts Count of iterations on each pyramid level. - * @param transformType Class of trasformation - */ - ICPOdometry(const Mat& cameraMatrix, float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), - float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), - const std::vector& iterCounts = std::vector(), int transformType = Odometry::RIGID_BODY_MOTION); - - CV_WRAP static Ptr create(const Mat& cameraMatrix = Mat(), float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), - float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), - const std::vector& iterCounts = std::vector(), int transformType = Odometry::RIGID_BODY_MOTION); - - CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const CV_OVERRIDE; - - CV_WRAP cv::Mat getCameraMatrix() const CV_OVERRIDE - { - return cameraMatrix; - } - CV_WRAP void setCameraMatrix(const cv::Mat &val) CV_OVERRIDE - { - cameraMatrix = val; - } - CV_WRAP double getMinDepth() const - { - return minDepth; - } - CV_WRAP void setMinDepth(double val) - { - minDepth = val; - } - CV_WRAP double getMaxDepth() const - { - return maxDepth; - } - CV_WRAP void setMaxDepth(double val) - { - maxDepth = val; - } - CV_WRAP double getMaxDepthDiff() const - { - return maxDepthDiff; - } - CV_WRAP void setMaxDepthDiff(double val) - { - maxDepthDiff = val; - } - CV_WRAP cv::Mat getIterationCounts() const - { - return iterCounts; - } - CV_WRAP void setIterationCounts(const cv::Mat &val) - { - iterCounts = val; - } - CV_WRAP double getMaxPointsPart() const - { - return maxPointsPart; - } - CV_WRAP void setMaxPointsPart(double val) - { - maxPointsPart = val; - } - CV_WRAP int getTransformType() const CV_OVERRIDE - { - return transformType; - } - CV_WRAP void setTransformType(int val) CV_OVERRIDE - { - transformType = val; - } - CV_WRAP double getMaxTranslation() const - { - return maxTranslation; - } - CV_WRAP void setMaxTranslation(double val) - { - maxTranslation = val; - } - CV_WRAP double getMaxRotation() const - { - return maxRotation; - } - CV_WRAP void setMaxRotation(double val) - { - maxRotation = val; - } - CV_WRAP Ptr getNormalsComputer() const - { - return normalsComputer; - } - - protected: - virtual void - checkParams() const CV_OVERRIDE; - - virtual bool - computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, - const Mat& initRt) const CV_OVERRIDE; - - // Some params have commented desired type. It's due to AlgorithmInfo::addParams does not support it now. - /*float*/ - double minDepth, maxDepth, maxDepthDiff; - /*float*/ - double maxPointsPart; - /*vector*/ - Mat iterCounts; - - Mat cameraMatrix; - int transformType; - - double maxTranslation, maxRotation; - - mutable Ptr normalsComputer; - }; - - /** Odometry that merges RgbdOdometry and ICPOdometry by minimize sum of their energy functions. - */ - - class CV_EXPORTS_W RgbdICPOdometry: public Odometry - { - public: - RgbdICPOdometry(); - /** Constructor. - * @param cameraMatrix Camera matrix - * @param minDepth Pixels with depth less than minDepth will not be used - * @param maxDepth Pixels with depth larger than maxDepth will not be used - * @param maxDepthDiff Correspondences between pixels of two given frames will be filtered out - * if their depth difference is larger than maxDepthDiff - * @param maxPointsPart The method uses a random pixels subset of size frameWidth x frameHeight x pointsPart - * @param iterCounts Count of iterations on each pyramid level. - * @param minGradientMagnitudes For each pyramid level the pixels will be filtered out - * if they have gradient magnitude less than minGradientMagnitudes[level]. - * @param transformType Class of trasformation - */ - RgbdICPOdometry(const Mat& cameraMatrix, float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), - float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), - const std::vector& iterCounts = std::vector(), - const std::vector& minGradientMagnitudes = std::vector(), - int transformType = Odometry::RIGID_BODY_MOTION); - - CV_WRAP static Ptr create(const Mat& cameraMatrix = Mat(), float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), - float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), - const std::vector& iterCounts = std::vector(), - const std::vector& minGradientMagnitudes = std::vector(), - int transformType = Odometry::RIGID_BODY_MOTION); - - CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const CV_OVERRIDE; - - CV_WRAP cv::Mat getCameraMatrix() const CV_OVERRIDE - { - return cameraMatrix; - } - CV_WRAP void setCameraMatrix(const cv::Mat &val) CV_OVERRIDE - { - cameraMatrix = val; - } - CV_WRAP double getMinDepth() const - { - return minDepth; - } - CV_WRAP void setMinDepth(double val) - { - minDepth = val; - } - CV_WRAP double getMaxDepth() const - { - return maxDepth; - } - CV_WRAP void setMaxDepth(double val) - { - maxDepth = val; - } - CV_WRAP double getMaxDepthDiff() const - { - return maxDepthDiff; - } - CV_WRAP void setMaxDepthDiff(double val) - { - maxDepthDiff = val; - } - CV_WRAP double getMaxPointsPart() const - { - return maxPointsPart; - } - CV_WRAP void setMaxPointsPart(double val) - { - maxPointsPart = val; - } - CV_WRAP cv::Mat getIterationCounts() const - { - return iterCounts; - } - CV_WRAP void setIterationCounts(const cv::Mat &val) - { - iterCounts = val; - } - CV_WRAP cv::Mat getMinGradientMagnitudes() const - { - return minGradientMagnitudes; - } - CV_WRAP void setMinGradientMagnitudes(const cv::Mat &val) - { - minGradientMagnitudes = val; - } - CV_WRAP int getTransformType() const CV_OVERRIDE - { - return transformType; - } - CV_WRAP void setTransformType(int val) CV_OVERRIDE - { - transformType = val; - } - CV_WRAP double getMaxTranslation() const - { - return maxTranslation; - } - CV_WRAP void setMaxTranslation(double val) - { - maxTranslation = val; - } - CV_WRAP double getMaxRotation() const - { - return maxRotation; - } - CV_WRAP void setMaxRotation(double val) - { - maxRotation = val; - } - CV_WRAP Ptr getNormalsComputer() const - { - return normalsComputer; - } - - protected: - virtual void - checkParams() const CV_OVERRIDE; - - virtual bool - computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, - const Mat& initRt) const CV_OVERRIDE; - - // Some params have commented desired type. It's due to AlgorithmInfo::addParams does not support it now. - /*float*/ - double minDepth, maxDepth, maxDepthDiff; - /*float*/ - double maxPointsPart; - /*vector*/ - Mat iterCounts; - /*vector*/ - Mat minGradientMagnitudes; - - Mat cameraMatrix; - int transformType; - - double maxTranslation, maxRotation; - - mutable Ptr normalsComputer; - }; - - /** Warp the image: compute 3d points from the depth, transform them using given transformation, - * then project color point cloud to an image plane. - * This function can be used to visualize results of the Odometry algorithm. - * @param image The image (of CV_8UC1 or CV_8UC3 type) - * @param depth The depth (of type used in depthTo3d fuction) - * @param mask The mask of used pixels (of CV_8UC1), it can be empty - * @param Rt The transformation that will be applied to the 3d points computed from the depth - * @param cameraMatrix Camera matrix - * @param distCoeff Distortion coefficients - * @param warpedImage The warped image. - * @param warpedDepth The warped depth. - * @param warpedMask The warped mask. - */ - CV_EXPORTS_W - void - warpFrame(const Mat& image, const Mat& depth, const Mat& mask, const Mat& Rt, const Mat& cameraMatrix, - const Mat& distCoeff, OutputArray warpedImage, OutputArray warpedDepth = noArray(), OutputArray warpedMask = noArray()); - -// TODO Depth interpolation -// Curvature -// Get rescaleDepth return dubles if asked for - -//! @} - -} /* namespace rgbd */ -} /* namespace cv */ - -#include "opencv2/rgbd/linemod.hpp" - -#endif /* __cplusplus */ #endif /* End of file. */ diff --git a/modules/rgbd/include/opencv2/rgbd/depth.hpp b/modules/rgbd/include/opencv2/rgbd/depth.hpp new file mode 100755 index 000000000..2f1917617 --- /dev/null +++ b/modules/rgbd/include/opencv2/rgbd/depth.hpp @@ -0,0 +1,1173 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + +#ifndef __OPENCV_RGBD_DEPTH_HPP__ +#define __OPENCV_RGBD_DEPTH_HPP__ + +#include +#include + +namespace cv +{ +namespace rgbd +{ + +//! @addtogroup rgbd +//! @{ + + /** Checks if the value is a valid depth. For CV_16U or CV_16S, the convention is to be invalid if it is + * a limit. For a float/double, we just check if it is a NaN + * @param depth the depth to check for validity + */ + CV_EXPORTS + inline bool + isValidDepth(const float & depth) + { + return !cvIsNaN(depth); + } + CV_EXPORTS + inline bool + isValidDepth(const double & depth) + { + return !cvIsNaN(depth); + } + CV_EXPORTS + inline bool + isValidDepth(const short int & depth) + { + return (depth != std::numeric_limits::min()) && (depth != std::numeric_limits::max()); + } + CV_EXPORTS + inline bool + isValidDepth(const unsigned short int & depth) + { + return (depth != std::numeric_limits::min()) + && (depth != std::numeric_limits::max()); + } + CV_EXPORTS + inline bool + isValidDepth(const int & depth) + { + return (depth != std::numeric_limits::min()) && (depth != std::numeric_limits::max()); + } + CV_EXPORTS + inline bool + isValidDepth(const unsigned int & depth) + { + return (depth != std::numeric_limits::min()) && (depth != std::numeric_limits::max()); + } + + /** Object that can compute the normals in an image. + * It is an object as it can cache data for speed efficiency + * The implemented methods are either: + * - FALS (the fastest) and SRI from + * ``Fast and Accurate Computation of Surface Normals from Range Images`` + * by H. Badino, D. Huber, Y. Park and T. Kanade + * - the normals with bilateral filtering on a depth image from + * ``Gradient Response Maps for Real-Time Detection of Texture-Less Objects`` + * by S. Hinterstoisser, C. Cagniart, S. Ilic, P. Sturm, N. Navab, P. Fua, and V. Lepetit + */ + class CV_EXPORTS_W RgbdNormals: public Algorithm + { + public: + enum RGBD_NORMALS_METHOD + { + RGBD_NORMALS_METHOD_FALS = 0, + RGBD_NORMALS_METHOD_LINEMOD = 1, + RGBD_NORMALS_METHOD_SRI = 2 + }; + + RgbdNormals() + : + rows_(0), + cols_(0), + depth_(0), + K_(Mat()), + window_size_(0), + method_(RGBD_NORMALS_METHOD_FALS), + rgbd_normals_impl_(0) + { + } + + /** Constructor + * @param rows the number of rows of the depth image normals will be computed on + * @param cols the number of cols of the depth image normals will be computed on + * @param depth the depth of the normals (only CV_32F or CV_64F) + * @param K the calibration matrix to use + * @param window_size the window size to compute the normals: can only be 1,3,5 or 7 + * @param method one of the methods to use: RGBD_NORMALS_METHOD_SRI, RGBD_NORMALS_METHOD_FALS + */ + RgbdNormals(int rows, int cols, int depth, InputArray K, int window_size = 5, int method = + RgbdNormals::RGBD_NORMALS_METHOD_FALS); + + ~RgbdNormals(); + + CV_WRAP static Ptr create(int rows, int cols, int depth, InputArray K, int window_size = 5, int method = + RgbdNormals::RGBD_NORMALS_METHOD_FALS); + + /** Given a set of 3d points in a depth image, compute the normals at each point. + * @param points a rows x cols x 3 matrix of CV_32F/CV64F or a rows x cols x 1 CV_U16S + * @param normals a rows x cols x 3 matrix + */ + void + operator()(InputArray points, OutputArray normals) const; + + /** Initializes some data that is cached for later computation + * If that function is not called, it will be called the first time normals are computed + */ + CV_WRAP void + initialize() const; + + CV_WRAP int getRows() const + { + return rows_; + } + CV_WRAP void setRows(int val) + { + rows_ = val; + } + CV_WRAP int getCols() const + { + return cols_; + } + CV_WRAP void setCols(int val) + { + cols_ = val; + } + CV_WRAP int getWindowSize() const + { + return window_size_; + } + CV_WRAP void setWindowSize(int val) + { + window_size_ = val; + } + CV_WRAP int getDepth() const + { + return depth_; + } + CV_WRAP void setDepth(int val) + { + depth_ = val; + } + CV_WRAP cv::Mat getK() const + { + return K_; + } + CV_WRAP void setK(const cv::Mat &val) + { + K_ = val; + } + CV_WRAP int getMethod() const + { + return method_; + } + CV_WRAP void setMethod(int val) + { + method_ = val; + } + + protected: + void + initialize_normals_impl(int rows, int cols, int depth, const Mat & K, int window_size, int method) const; + + int rows_, cols_, depth_; + Mat K_; + int window_size_; + int method_; + mutable void* rgbd_normals_impl_; + }; + + /** Object that can clean a noisy depth image + */ + class CV_EXPORTS_W DepthCleaner: public Algorithm + { + public: + /** NIL method is from + * ``Modeling Kinect Sensor Noise for Improved 3d Reconstruction and Tracking`` + * by C. Nguyen, S. Izadi, D. Lovel + */ + enum DEPTH_CLEANER_METHOD + { + DEPTH_CLEANER_NIL + }; + + DepthCleaner() + : + depth_(0), + window_size_(0), + method_(DEPTH_CLEANER_NIL), + depth_cleaner_impl_(0) + { + } + + /** Constructor + * @param depth the depth of the normals (only CV_32F or CV_64F) + * @param window_size the window size to compute the normals: can only be 1,3,5 or 7 + * @param method one of the methods to use: RGBD_NORMALS_METHOD_SRI, RGBD_NORMALS_METHOD_FALS + */ + DepthCleaner(int depth, int window_size = 5, int method = DepthCleaner::DEPTH_CLEANER_NIL); + + ~DepthCleaner(); + + CV_WRAP static Ptr create(int depth, int window_size = 5, int method = DepthCleaner::DEPTH_CLEANER_NIL); + + /** Given a set of 3d points in a depth image, compute the normals at each point. + * @param points a rows x cols x 3 matrix of CV_32F/CV64F or a rows x cols x 1 CV_U16S + * @param depth a rows x cols matrix of the cleaned up depth + */ + void + operator()(InputArray points, OutputArray depth) const; + + /** Initializes some data that is cached for later computation + * If that function is not called, it will be called the first time normals are computed + */ + CV_WRAP void + initialize() const; + + CV_WRAP int getWindowSize() const + { + return window_size_; + } + CV_WRAP void setWindowSize(int val) + { + window_size_ = val; + } + CV_WRAP int getDepth() const + { + return depth_; + } + CV_WRAP void setDepth(int val) + { + depth_ = val; + } + CV_WRAP int getMethod() const + { + return method_; + } + CV_WRAP void setMethod(int val) + { + method_ = val; + } + + protected: + void + initialize_cleaner_impl() const; + + int depth_; + int window_size_; + int method_; + mutable void* depth_cleaner_impl_; + }; + + + /** Registers depth data to an external camera + * Registration is performed by creating a depth cloud, transforming the cloud by + * the rigid body transformation between the cameras, and then projecting the + * transformed points into the RGB camera. + * + * uv_rgb = K_rgb * [R | t] * z * inv(K_ir) * uv_ir + * + * Currently does not check for negative depth values. + * + * @param unregisteredCameraMatrix the camera matrix of the depth camera + * @param registeredCameraMatrix the camera matrix of the external camera + * @param registeredDistCoeffs the distortion coefficients of the external camera + * @param Rt the rigid body transform between the cameras. Transforms points from depth camera frame to external camera frame. + * @param unregisteredDepth the input depth data + * @param outputImagePlaneSize the image plane dimensions of the external camera (width, height) + * @param registeredDepth the result of transforming the depth into the external camera + * @param depthDilation whether or not the depth is dilated to avoid holes and occlusion errors (optional) + */ + CV_EXPORTS_W + void + registerDepth(InputArray unregisteredCameraMatrix, InputArray registeredCameraMatrix, InputArray registeredDistCoeffs, + InputArray Rt, InputArray unregisteredDepth, const Size& outputImagePlaneSize, + OutputArray registeredDepth, bool depthDilation=false); + + /** + * @param depth the depth image + * @param in_K + * @param in_points the list of xy coordinates + * @param points3d the resulting 3d points + */ + CV_EXPORTS_W + void + depthTo3dSparse(InputArray depth, InputArray in_K, InputArray in_points, OutputArray points3d); + + /** Converts a depth image to an organized set of 3d points. + * The coordinate system is x pointing left, y down and z away from the camera + * @param depth the depth image (if given as short int CV_U, it is assumed to be the depth in millimeters + * (as done with the Microsoft Kinect), otherwise, if given as CV_32F or CV_64F, it is assumed in meters) + * @param K The calibration matrix + * @param points3d the resulting 3d points. They are of depth the same as `depth` if it is CV_32F or CV_64F, and the + * depth of `K` if `depth` is of depth CV_U + * @param mask the mask of the points to consider (can be empty) + */ + CV_EXPORTS_W + void + depthTo3d(InputArray depth, InputArray K, OutputArray points3d, InputArray mask = noArray()); + + /** If the input image is of type CV_16UC1 (like the Kinect one), the image is converted to floats, divided + * by 1000 to get a depth in meters, and the values 0 are converted to std::numeric_limits::quiet_NaN() + * Otherwise, the image is simply converted to floats + * @param in the depth image (if given as short int CV_U, it is assumed to be the depth in millimeters + * (as done with the Microsoft Kinect), it is assumed in meters) + * @param depth the desired output depth (floats or double) + * @param out The rescaled float depth image + */ + CV_EXPORTS_W + void + rescaleDepth(InputArray in, int depth, OutputArray out); + + /** Object that can compute planes in an image + */ + class CV_EXPORTS_W RgbdPlane: public Algorithm + { + public: + enum RGBD_PLANE_METHOD + { + RGBD_PLANE_METHOD_DEFAULT + }; + + RgbdPlane(int method = RgbdPlane::RGBD_PLANE_METHOD_DEFAULT) + : + method_(method), + block_size_(40), + min_size_(block_size_*block_size_), + threshold_(0.01), + sensor_error_a_(0), + sensor_error_b_(0), + sensor_error_c_(0) + { + } + + /** Find The planes in a depth image + * @param points3d the 3d points organized like the depth image: rows x cols with 3 channels + * @param normals the normals for every point in the depth image + * @param mask An image where each pixel is labeled with the plane it belongs to + * and 255 if it does not belong to any plane + * @param plane_coefficients the coefficients of the corresponding planes (a,b,c,d) such that ax+by+cz+d=0, norm(a,b,c)=1 + * and c < 0 (so that the normal points towards the camera) + */ + void + operator()(InputArray points3d, InputArray normals, OutputArray mask, + OutputArray plane_coefficients); + + /** Find The planes in a depth image but without doing a normal check, which is faster but less accurate + * @param points3d the 3d points organized like the depth image: rows x cols with 3 channels + * @param mask An image where each pixel is labeled with the plane it belongs to + * and 255 if it does not belong to any plane + * @param plane_coefficients the coefficients of the corresponding planes (a,b,c,d) such that ax+by+cz+d=0 + */ + void + operator()(InputArray points3d, OutputArray mask, OutputArray plane_coefficients); + + CV_WRAP int getBlockSize() const + { + return block_size_; + } + CV_WRAP void setBlockSize(int val) + { + block_size_ = val; + } + CV_WRAP int getMinSize() const + { + return min_size_; + } + CV_WRAP void setMinSize(int val) + { + min_size_ = val; + } + CV_WRAP int getMethod() const + { + return method_; + } + CV_WRAP void setMethod(int val) + { + method_ = val; + } + CV_WRAP double getThreshold() const + { + return threshold_; + } + CV_WRAP void setThreshold(double val) + { + threshold_ = val; + } + CV_WRAP double getSensorErrorA() const + { + return sensor_error_a_; + } + CV_WRAP void setSensorErrorA(double val) + { + sensor_error_a_ = val; + } + CV_WRAP double getSensorErrorB() const + { + return sensor_error_b_; + } + CV_WRAP void setSensorErrorB(double val) + { + sensor_error_b_ = val; + } + CV_WRAP double getSensorErrorC() const + { + return sensor_error_c_; + } + CV_WRAP void setSensorErrorC(double val) + { + sensor_error_c_ = val; + } + + private: + /** The method to use to compute the planes */ + int method_; + /** The size of the blocks to look at for a stable MSE */ + int block_size_; + /** The minimum size of a cluster to be considered a plane */ + int min_size_; + /** How far a point can be from a plane to belong to it (in meters) */ + double threshold_; + /** coefficient of the sensor error with respect to the. All 0 by default but you want a=0.0075 for a Kinect */ + double sensor_error_a_, sensor_error_b_, sensor_error_c_; + }; + + /** Object that contains a frame data. + */ + struct CV_EXPORTS_W RgbdFrame + { + RgbdFrame(); + RgbdFrame(const Mat& image, const Mat& depth, const Mat& mask=Mat(), const Mat& normals=Mat(), int ID=-1); + virtual ~RgbdFrame(); + + CV_WRAP static Ptr create(const Mat& image=Mat(), const Mat& depth=Mat(), const Mat& mask=Mat(), const Mat& normals=Mat(), int ID=-1); + + CV_WRAP virtual void + release(); + + CV_PROP int ID; + CV_PROP Mat image; + CV_PROP Mat depth; + CV_PROP Mat mask; + CV_PROP Mat normals; + }; + + /** Object that contains a frame data that is possibly needed for the Odometry. + * It's used for the efficiency (to pass precomputed/cached data of the frame that participates + * in the Odometry processing several times). + */ + struct CV_EXPORTS_W OdometryFrame : public RgbdFrame + { + /** These constants are used to set a type of cache which has to be prepared depending on the frame role: + * srcFrame or dstFrame (see compute method of the Odometry class). For the srcFrame and dstFrame different cache data may be required, + * some part of a cache may be common for both frame roles. + * @param CACHE_SRC The cache data for the srcFrame will be prepared. + * @param CACHE_DST The cache data for the dstFrame will be prepared. + * @param CACHE_ALL The cache data for both srcFrame and dstFrame roles will be computed. + */ + enum + { + CACHE_SRC = 1, CACHE_DST = 2, CACHE_ALL = CACHE_SRC + CACHE_DST + }; + + OdometryFrame(); + OdometryFrame(const Mat& image, const Mat& depth, const Mat& mask=Mat(), const Mat& normals=Mat(), int ID=-1); + + CV_WRAP static Ptr create(const Mat& image=Mat(), const Mat& depth=Mat(), const Mat& mask=Mat(), const Mat& normals=Mat(), int ID=-1); + + CV_WRAP virtual void + release() CV_OVERRIDE; + + CV_WRAP void + releasePyramids(); + + CV_PROP std::vector pyramidImage; + CV_PROP std::vector pyramidDepth; + CV_PROP std::vector pyramidMask; + + CV_PROP std::vector pyramidCloud; + + CV_PROP std::vector pyramid_dI_dx; + CV_PROP std::vector pyramid_dI_dy; + CV_PROP std::vector pyramidTexturedMask; + + CV_PROP std::vector pyramidNormals; + CV_PROP std::vector pyramidNormalsMask; + }; + + /** Base class for computation of odometry. + */ + class CV_EXPORTS_W Odometry: public Algorithm + { + public: + + /** A class of transformation*/ + enum + { + ROTATION = 1, TRANSLATION = 2, RIGID_BODY_MOTION = 4 + }; + + CV_WRAP static inline float + DEFAULT_MIN_DEPTH() + { + return 0.f; // in meters + } + CV_WRAP static inline float + DEFAULT_MAX_DEPTH() + { + return 4.f; // in meters + } + CV_WRAP static inline float + DEFAULT_MAX_DEPTH_DIFF() + { + return 0.07f; // in meters + } + CV_WRAP static inline float + DEFAULT_MAX_POINTS_PART() + { + return 0.07f; // in [0, 1] + } + CV_WRAP static inline float + DEFAULT_MAX_TRANSLATION() + { + return 0.15f; // in meters + } + CV_WRAP static inline float + DEFAULT_MAX_ROTATION() + { + return 15; // in degrees + } + + /** Method to compute a transformation from the source frame to the destination one. + * Some odometry algorithms do not used some data of frames (eg. ICP does not use images). + * In such case corresponding arguments can be set as empty Mat. + * The method returns true if all internal computions were possible (e.g. there were enough correspondences, + * system of equations has a solution, etc) and resulting transformation satisfies some test if it's provided + * by the Odometry inheritor implementation (e.g. thresholds for maximum translation and rotation). + * @param srcImage Image data of the source frame (CV_8UC1) + * @param srcDepth Depth data of the source frame (CV_32FC1, in meters) + * @param srcMask Mask that sets which pixels have to be used from the source frame (CV_8UC1) + * @param dstImage Image data of the destination frame (CV_8UC1) + * @param dstDepth Depth data of the destination frame (CV_32FC1, in meters) + * @param dstMask Mask that sets which pixels have to be used from the destination frame (CV_8UC1) + * @param Rt Resulting transformation from the source frame to the destination one (rigid body motion): + dst_p = Rt * src_p, where dst_p is a homogeneous point in the destination frame and src_p is + homogeneous point in the source frame, + Rt is 4x4 matrix of CV_64FC1 type. + * @param initRt Initial transformation from the source frame to the destination one (optional) + */ + CV_WRAP bool + compute(const Mat& srcImage, const Mat& srcDepth, const Mat& srcMask, const Mat& dstImage, const Mat& dstDepth, + const Mat& dstMask, OutputArray Rt, const Mat& initRt = Mat()) const; + + /** One more method to compute a transformation from the source frame to the destination one. + * It is designed to save on computing the frame data (image pyramids, normals, etc.). + */ + CV_WRAP_AS(compute2) bool + compute(Ptr& srcFrame, Ptr& dstFrame, OutputArray Rt, const Mat& initRt = Mat()) const; + + /** Prepare a cache for the frame. The function checks the precomputed/passed data (throws the error if this data + * does not satisfy) and computes all remaining cache data needed for the frame. Returned size is a resolution + * of the prepared frame. + * @param frame The odometry which will process the frame. + * @param cacheType The cache type: CACHE_SRC, CACHE_DST or CACHE_ALL. + */ + CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const; + + CV_WRAP static Ptr create(const String & odometryType); + + /** @see setCameraMatrix */ + CV_WRAP virtual cv::Mat getCameraMatrix() const = 0; + /** @copybrief getCameraMatrix @see getCameraMatrix */ + CV_WRAP virtual void setCameraMatrix(const cv::Mat &val) = 0; + /** @see setTransformType */ + CV_WRAP virtual int getTransformType() const = 0; + /** @copybrief getTransformType @see getTransformType */ + CV_WRAP virtual void setTransformType(int val) = 0; + + protected: + virtual void + checkParams() const = 0; + + virtual bool + computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, + const Mat& initRt) const = 0; + }; + + /** Odometry based on the paper "Real-Time Visual Odometry from Dense RGB-D Images", + * F. Steinbucker, J. Strum, D. Cremers, ICCV, 2011. + */ + class CV_EXPORTS_W RgbdOdometry: public Odometry + { + public: + RgbdOdometry(); + /** Constructor. + * @param cameraMatrix Camera matrix + * @param minDepth Pixels with depth less than minDepth will not be used (in meters) + * @param maxDepth Pixels with depth larger than maxDepth will not be used (in meters) + * @param maxDepthDiff Correspondences between pixels of two given frames will be filtered out + * if their depth difference is larger than maxDepthDiff (in meters) + * @param iterCounts Count of iterations on each pyramid level. + * @param minGradientMagnitudes For each pyramid level the pixels will be filtered out + * if they have gradient magnitude less than minGradientMagnitudes[level]. + * @param maxPointsPart The method uses a random pixels subset of size frameWidth x frameHeight x pointsPart + * @param transformType Class of transformation + */ + RgbdOdometry(const Mat& cameraMatrix, float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), + float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), const std::vector& iterCounts = std::vector(), + const std::vector& minGradientMagnitudes = std::vector(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), + int transformType = Odometry::RIGID_BODY_MOTION); + + CV_WRAP static Ptr create(const Mat& cameraMatrix = Mat(), float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), + float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), const std::vector& iterCounts = std::vector(), + const std::vector& minGradientMagnitudes = std::vector(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), + int transformType = Odometry::RIGID_BODY_MOTION); + + CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const CV_OVERRIDE; + + CV_WRAP cv::Mat getCameraMatrix() const CV_OVERRIDE + { + return cameraMatrix; + } + CV_WRAP void setCameraMatrix(const cv::Mat &val) CV_OVERRIDE + { + cameraMatrix = val; + } + CV_WRAP double getMinDepth() const + { + return minDepth; + } + CV_WRAP void setMinDepth(double val) + { + minDepth = val; + } + CV_WRAP double getMaxDepth() const + { + return maxDepth; + } + CV_WRAP void setMaxDepth(double val) + { + maxDepth = val; + } + CV_WRAP double getMaxDepthDiff() const + { + return maxDepthDiff; + } + CV_WRAP void setMaxDepthDiff(double val) + { + maxDepthDiff = val; + } + CV_WRAP cv::Mat getIterationCounts() const + { + return iterCounts; + } + CV_WRAP void setIterationCounts(const cv::Mat &val) + { + iterCounts = val; + } + CV_WRAP cv::Mat getMinGradientMagnitudes() const + { + return minGradientMagnitudes; + } + CV_WRAP void setMinGradientMagnitudes(const cv::Mat &val) + { + minGradientMagnitudes = val; + } + CV_WRAP double getMaxPointsPart() const + { + return maxPointsPart; + } + CV_WRAP void setMaxPointsPart(double val) + { + maxPointsPart = val; + } + CV_WRAP int getTransformType() const CV_OVERRIDE + { + return transformType; + } + CV_WRAP void setTransformType(int val) CV_OVERRIDE + { + transformType = val; + } + CV_WRAP double getMaxTranslation() const + { + return maxTranslation; + } + CV_WRAP void setMaxTranslation(double val) + { + maxTranslation = val; + } + CV_WRAP double getMaxRotation() const + { + return maxRotation; + } + CV_WRAP void setMaxRotation(double val) + { + maxRotation = val; + } + + protected: + virtual void + checkParams() const CV_OVERRIDE; + + virtual bool + computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, + const Mat& initRt) const CV_OVERRIDE; + + // Some params have commented desired type. It's due to AlgorithmInfo::addParams does not support it now. + /*float*/ + double minDepth, maxDepth, maxDepthDiff; + /*vector*/ + Mat iterCounts; + /*vector*/ + Mat minGradientMagnitudes; + double maxPointsPart; + + Mat cameraMatrix; + int transformType; + + double maxTranslation, maxRotation; + }; + + /** Odometry based on the paper "KinectFusion: Real-Time Dense Surface Mapping and Tracking", + * Richard A. Newcombe, Andrew Fitzgibbon, at al, SIGGRAPH, 2011. + */ + class CV_EXPORTS_W ICPOdometry: public Odometry + { + public: + ICPOdometry(); + /** Constructor. + * @param cameraMatrix Camera matrix + * @param minDepth Pixels with depth less than minDepth will not be used + * @param maxDepth Pixels with depth larger than maxDepth will not be used + * @param maxDepthDiff Correspondences between pixels of two given frames will be filtered out + * if their depth difference is larger than maxDepthDiff + * @param maxPointsPart The method uses a random pixels subset of size frameWidth x frameHeight x pointsPart + * @param iterCounts Count of iterations on each pyramid level. + * @param transformType Class of trasformation + */ + ICPOdometry(const Mat& cameraMatrix, float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), + float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), + const std::vector& iterCounts = std::vector(), int transformType = Odometry::RIGID_BODY_MOTION); + + CV_WRAP static Ptr create(const Mat& cameraMatrix = Mat(), float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), + float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), + const std::vector& iterCounts = std::vector(), int transformType = Odometry::RIGID_BODY_MOTION); + + CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const CV_OVERRIDE; + + CV_WRAP cv::Mat getCameraMatrix() const CV_OVERRIDE + { + return cameraMatrix; + } + CV_WRAP void setCameraMatrix(const cv::Mat &val) CV_OVERRIDE + { + cameraMatrix = val; + } + CV_WRAP double getMinDepth() const + { + return minDepth; + } + CV_WRAP void setMinDepth(double val) + { + minDepth = val; + } + CV_WRAP double getMaxDepth() const + { + return maxDepth; + } + CV_WRAP void setMaxDepth(double val) + { + maxDepth = val; + } + CV_WRAP double getMaxDepthDiff() const + { + return maxDepthDiff; + } + CV_WRAP void setMaxDepthDiff(double val) + { + maxDepthDiff = val; + } + CV_WRAP cv::Mat getIterationCounts() const + { + return iterCounts; + } + CV_WRAP void setIterationCounts(const cv::Mat &val) + { + iterCounts = val; + } + CV_WRAP double getMaxPointsPart() const + { + return maxPointsPart; + } + CV_WRAP void setMaxPointsPart(double val) + { + maxPointsPart = val; + } + CV_WRAP int getTransformType() const CV_OVERRIDE + { + return transformType; + } + CV_WRAP void setTransformType(int val) CV_OVERRIDE + { + transformType = val; + } + CV_WRAP double getMaxTranslation() const + { + return maxTranslation; + } + CV_WRAP void setMaxTranslation(double val) + { + maxTranslation = val; + } + CV_WRAP double getMaxRotation() const + { + return maxRotation; + } + CV_WRAP void setMaxRotation(double val) + { + maxRotation = val; + } + CV_WRAP Ptr getNormalsComputer() const + { + return normalsComputer; + } + + protected: + virtual void + checkParams() const CV_OVERRIDE; + + virtual bool + computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, + const Mat& initRt) const CV_OVERRIDE; + + // Some params have commented desired type. It's due to AlgorithmInfo::addParams does not support it now. + /*float*/ + double minDepth, maxDepth, maxDepthDiff; + /*float*/ + double maxPointsPart; + /*vector*/ + Mat iterCounts; + + Mat cameraMatrix; + int transformType; + + double maxTranslation, maxRotation; + + mutable Ptr normalsComputer; + }; + + /** Odometry that merges RgbdOdometry and ICPOdometry by minimize sum of their energy functions. + */ + + class CV_EXPORTS_W RgbdICPOdometry: public Odometry + { + public: + RgbdICPOdometry(); + /** Constructor. + * @param cameraMatrix Camera matrix + * @param minDepth Pixels with depth less than minDepth will not be used + * @param maxDepth Pixels with depth larger than maxDepth will not be used + * @param maxDepthDiff Correspondences between pixels of two given frames will be filtered out + * if their depth difference is larger than maxDepthDiff + * @param maxPointsPart The method uses a random pixels subset of size frameWidth x frameHeight x pointsPart + * @param iterCounts Count of iterations on each pyramid level. + * @param minGradientMagnitudes For each pyramid level the pixels will be filtered out + * if they have gradient magnitude less than minGradientMagnitudes[level]. + * @param transformType Class of trasformation + */ + RgbdICPOdometry(const Mat& cameraMatrix, float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), + float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), + const std::vector& iterCounts = std::vector(), + const std::vector& minGradientMagnitudes = std::vector(), + int transformType = Odometry::RIGID_BODY_MOTION); + + CV_WRAP static Ptr create(const Mat& cameraMatrix = Mat(), float minDepth = Odometry::DEFAULT_MIN_DEPTH(), float maxDepth = Odometry::DEFAULT_MAX_DEPTH(), + float maxDepthDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), float maxPointsPart = Odometry::DEFAULT_MAX_POINTS_PART(), + const std::vector& iterCounts = std::vector(), + const std::vector& minGradientMagnitudes = std::vector(), + int transformType = Odometry::RIGID_BODY_MOTION); + + CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const CV_OVERRIDE; + + CV_WRAP cv::Mat getCameraMatrix() const CV_OVERRIDE + { + return cameraMatrix; + } + CV_WRAP void setCameraMatrix(const cv::Mat &val) CV_OVERRIDE + { + cameraMatrix = val; + } + CV_WRAP double getMinDepth() const + { + return minDepth; + } + CV_WRAP void setMinDepth(double val) + { + minDepth = val; + } + CV_WRAP double getMaxDepth() const + { + return maxDepth; + } + CV_WRAP void setMaxDepth(double val) + { + maxDepth = val; + } + CV_WRAP double getMaxDepthDiff() const + { + return maxDepthDiff; + } + CV_WRAP void setMaxDepthDiff(double val) + { + maxDepthDiff = val; + } + CV_WRAP double getMaxPointsPart() const + { + return maxPointsPart; + } + CV_WRAP void setMaxPointsPart(double val) + { + maxPointsPart = val; + } + CV_WRAP cv::Mat getIterationCounts() const + { + return iterCounts; + } + CV_WRAP void setIterationCounts(const cv::Mat &val) + { + iterCounts = val; + } + CV_WRAP cv::Mat getMinGradientMagnitudes() const + { + return minGradientMagnitudes; + } + CV_WRAP void setMinGradientMagnitudes(const cv::Mat &val) + { + minGradientMagnitudes = val; + } + CV_WRAP int getTransformType() const CV_OVERRIDE + { + return transformType; + } + CV_WRAP void setTransformType(int val) CV_OVERRIDE + { + transformType = val; + } + CV_WRAP double getMaxTranslation() const + { + return maxTranslation; + } + CV_WRAP void setMaxTranslation(double val) + { + maxTranslation = val; + } + CV_WRAP double getMaxRotation() const + { + return maxRotation; + } + CV_WRAP void setMaxRotation(double val) + { + maxRotation = val; + } + CV_WRAP Ptr getNormalsComputer() const + { + return normalsComputer; + } + + protected: + virtual void + checkParams() const CV_OVERRIDE; + + virtual bool + computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, + const Mat& initRt) const CV_OVERRIDE; + + // Some params have commented desired type. It's due to AlgorithmInfo::addParams does not support it now. + /*float*/ + double minDepth, maxDepth, maxDepthDiff; + /*float*/ + double maxPointsPart; + /*vector*/ + Mat iterCounts; + /*vector*/ + Mat minGradientMagnitudes; + + Mat cameraMatrix; + int transformType; + + double maxTranslation, maxRotation; + + mutable Ptr normalsComputer; + }; + + /** A faster version of ICPOdometry which is used in KinectFusion implementation + * Partial list of differences: + * - Works in parallel + * - Written in universal intrinsics + * - Filters points by angle + * - Interpolates points and normals + * - Doesn't use masks or min/max depth filtering + * - Doesn't use random subsets of points + * - Supports only Rt transform type + * - Supports only 4-float vectors as input type + */ + class CV_EXPORTS_W FastICPOdometry: public Odometry + { + public: + FastICPOdometry(); + /** Constructor. + * @param cameraMatrix Camera matrix + * @param maxDistDiff Correspondences between pixels of two given frames will be filtered out + * if their depth difference is larger than maxDepthDiff + * @param angleThreshold Correspondence will be filtered out + * if an angle between their normals is bigger than threshold + * @param sigmaDepth Depth sigma in meters for bilateral smooth + * @param sigmaSpatial Spatial sigma in pixels for bilateral smooth + * @param kernelSize Kernel size in pixels for bilateral smooth + * @param iterCounts Count of iterations on each pyramid level + */ + FastICPOdometry(const Mat& cameraMatrix, + float maxDistDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), + float angleThreshold = (float)(30. * CV_PI / 180.), + float sigmaDepth = 0.04f, + float sigmaSpatial = 4.5f, + int kernelSize = 7, + const std::vector& iterCounts = std::vector()); + + CV_WRAP static Ptr create(const Mat& cameraMatrix, + float maxDistDiff = Odometry::DEFAULT_MAX_DEPTH_DIFF(), + float angleThreshold = (float)(30. * CV_PI / 180.), + float sigmaDepth = 0.04f, + float sigmaSpatial = 4.5f, + int kernelSize = 7, + const std::vector& iterCounts = std::vector()); + + CV_WRAP virtual Size prepareFrameCache(Ptr& frame, int cacheType) const CV_OVERRIDE; + + CV_WRAP cv::Mat getCameraMatrix() const CV_OVERRIDE + { + return cameraMatrix; + } + CV_WRAP void setCameraMatrix(const cv::Mat &val) CV_OVERRIDE + { + cameraMatrix = val; + } + CV_WRAP double getMaxDistDiff() const + { + return maxDistDiff; + } + CV_WRAP void setMaxDistDiff(float val) + { + maxDistDiff = val; + } + CV_WRAP float getAngleThreshold() const + { + return angleThreshold; + } + CV_WRAP void setAngleThreshold(float f) + { + angleThreshold = f; + } + CV_WRAP float getSigmaDepth() const + { + return sigmaDepth; + } + CV_WRAP void setSigmaDepth(float f) + { + sigmaDepth = f; + } + CV_WRAP float getSigmaSpatial() const + { + return sigmaSpatial; + } + CV_WRAP void setSigmaSpatial(float f) + { + sigmaSpatial = f; + } + CV_WRAP int getKernelSize() const + { + return kernelSize; + } + CV_WRAP void setKernelSize(int f) + { + kernelSize = f; + } + CV_WRAP cv::Mat getIterationCounts() const + { + return iterCounts; + } + CV_WRAP void setIterationCounts(const cv::Mat &val) + { + iterCounts = val; + } + CV_WRAP int getTransformType() const CV_OVERRIDE + { + return Odometry::RIGID_BODY_MOTION; + } + CV_WRAP void setTransformType(int val) CV_OVERRIDE + { + if(val != Odometry::RIGID_BODY_MOTION) + throw std::runtime_error("Rigid Body Motion is the only accepted transformation type" + " for this odometry method"); + } + + protected: + virtual void + checkParams() const CV_OVERRIDE; + + virtual bool + computeImpl(const Ptr& srcFrame, const Ptr& dstFrame, OutputArray Rt, + const Mat& initRt) const CV_OVERRIDE; + + // Some params have commented desired type. It's due to AlgorithmInfo::addParams does not support it now. + float maxDistDiff; + + float angleThreshold; + + float sigmaDepth; + + float sigmaSpatial; + + int kernelSize; + + /*vector*/ + Mat iterCounts; + + Mat cameraMatrix; + }; + + /** Warp the image: compute 3d points from the depth, transform them using given transformation, + * then project color point cloud to an image plane. + * This function can be used to visualize results of the Odometry algorithm. + * @param image The image (of CV_8UC1 or CV_8UC3 type) + * @param depth The depth (of type used in depthTo3d fuction) + * @param mask The mask of used pixels (of CV_8UC1), it can be empty + * @param Rt The transformation that will be applied to the 3d points computed from the depth + * @param cameraMatrix Camera matrix + * @param distCoeff Distortion coefficients + * @param warpedImage The warped image. + * @param warpedDepth The warped depth. + * @param warpedMask The warped mask. + */ + CV_EXPORTS_W + void + warpFrame(const Mat& image, const Mat& depth, const Mat& mask, const Mat& Rt, const Mat& cameraMatrix, + const Mat& distCoeff, OutputArray warpedImage, OutputArray warpedDepth = noArray(), OutputArray warpedMask = noArray()); + +// TODO Depth interpolation +// Curvature +// Get rescaleDepth return dubles if asked for + +//! @} + +} /* namespace rgbd */ +} /* namespace cv */ + +#endif + +/* End of file. */ diff --git a/modules/rgbd/include/opencv2/rgbd/kinfu.hpp b/modules/rgbd/include/opencv2/rgbd/kinfu.hpp new file mode 100644 index 000000000..02af753ce --- /dev/null +++ b/modules/rgbd/include/opencv2/rgbd/kinfu.hpp @@ -0,0 +1,211 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#ifndef __OPENCV_RGBD_KINFU_HPP__ +#define __OPENCV_RGBD_KINFU_HPP__ + +#include "opencv2/core.hpp" +#include "opencv2/core/affine.hpp" + +namespace cv { +namespace kinfu { +//! @addtogroup kinect_fusion +//! @{ + +/** @brief KinectFusion implementation + + This class implements a 3d reconstruction algorithm described in + @cite kinectfusion paper. + + It takes a sequence of depth images taken from depth sensor + (or any depth images source such as stereo camera matching algorithm or even raymarching renderer). + The output can be obtained as a vector of points and their normals + or can be Phong-rendered from given camera pose. + + An internal representation of a model is a voxel cube that keeps TSDF values + which are a sort of distances to the surface (for details read the @cite kinectfusion article about TSDF). + There is no interface to that representation yet. + + This implementation is based on (kinfu-remake)[https://github.com/Nerei/kinfu_remake]. +*/ +class CV_EXPORTS KinFu +{ +public: + struct CV_EXPORTS Params + { + /** @brief Default parameters + A set of parameters which provides better model quality, can be very slow. + */ + static Params defaultParams(); + + /** @brief Coarse parameters + A set of parameters which provides better speed, can fail to match frames + in case of rapid sensor motion. + */ + static Params coarseParams(); + + enum PlatformType + { + + PLATFORM_CPU, PLATFORM_GPU + }; + + /** @brief A platform on which to run the algorithm. + * + Currently KinFu supports only one platform which is a CPU. + GPU platform is to be implemented in the future. + */ + PlatformType platform; + + /** @brief frame size in pixels */ + Size frameSize; + + /** @brief camera intrinsics */ + Matx33f intr; + + /** @brief pre-scale per 1 meter for input values + + Typical values are: + * 5000 per 1 meter for the 16-bit PNG files of TUM database + * 1 per 1 meter for the 32-bit float images in the ROS bag files + */ + float depthFactor; + + /** @brief Depth sigma in meters for bilateral smooth */ + float bilateral_sigma_depth; + /** @brief Spatial sigma in pixels for bilateral smooth */ + float bilateral_sigma_spatial; + /** @brief Kernel size in pixels for bilateral smooth */ + int bilateral_kernel_size; + + /** @brief Number of pyramid levels for ICP */ + int pyramidLevels; + + /** @brief Resolution of voxel cube + + Number of voxels in each cube edge. + */ + int volumeDims; + /** @brief Size of voxel cube side in meters */ + float volumeSize; + + /** @brief Minimal camera movement in meters + + Integrate new depth frame only if camera movement exceeds this value. + */ + float tsdf_min_camera_movement; + + /** @brief initial volume pose in meters */ + Affine3f volumePose; + + /** @brief distance to truncate in meters + + Distances that exceed this value will be truncated in voxel cube values. + */ + float tsdf_trunc_dist; + + /** @brief max number of frames per voxel + + Each voxel keeps running average of distances no longer than this value. + */ + int tsdf_max_weight; + + /** @brief A length of one raycast step + + How much voxel sizes we skip each raycast step + */ + float raycast_step_factor; + + // gradient delta in voxel sizes + // fixed at 1.0f + // float gradient_delta_factor; + + /** @brief light pose for rendering in meters */ + Vec3f lightPose; + + /** @brief distance theshold for ICP in meters */ + float icpDistThresh; + /** angle threshold for ICP in radians */ + float icpAngleThresh; + /** number of ICP iterations for each pyramid level */ + std::vector icpIterations; + + // depth truncation is not used by default + // float icp_truncate_depth_dist; //meters + }; + + KinFu(const Params& _params); + virtual ~KinFu(); + + /** @brief Get current parameters */ + const Params& getParams() const; + void setParams(const Params&); + + /** @brief Renders a volume into an image + + Renders a 0-surface of TSDF using Phong shading into a CV_8UC3 Mat. + Light pose is fixed in KinFu params. + + @param image resulting image + @param cameraPose pose of camera to render from. If empty then render from current pose + which is a last frame camera pose. + */ + + void render(OutputArray image, const Affine3f cameraPose = Affine3f::Identity()) const; + + /** @brief Gets points and normals of current 3d mesh + + The order of normals corresponds to order of points. + The order of points is undefined. + + @param points vector of points which are 4-float vectors + @param normals vector of normals which are 4-float vectors + */ + void getCloud(OutputArray points, OutputArray normals) const; + + /** @brief Gets points of current 3d mesh + + The order of points is undefined. + + @param points vector of points which are 4-float vectors + */ + void getPoints(OutputArray points) const; + + /** @brief Calculates normals for given points + @param points input vector of points which are 4-float vectors + @param normals output vector of corresponding normals which are 4-float vectors + */ + void getNormals(InputArray points, OutputArray normals) const; + + /** @brief Resets the algorithm + + Clears current model and resets a pose. + */ + void reset(); + + /** @brief Get current pose in voxel cube space */ + const Affine3f getPose() const; + + /** @brief Process next depth frame + + Integrates depth into voxel cube with respect to its ICP-calculated pose. + Input image is converted to CV_32F internally if has another type. + + @param depth one-channel image which size and depth scale is described in algorithm's parameters + @return true if succeded to align new frame with current scene, false if opposite + */ + bool update(InputArray depth); + +private: + + class KinFuImpl; + cv::Ptr impl; +}; + +//! @} +} +} +#endif diff --git a/modules/rgbd/include/opencv2/rgbd/linemod.hpp b/modules/rgbd/include/opencv2/rgbd/linemod.hpp index f229e5864..c3ace1ea8 100644 --- a/modules/rgbd/include/opencv2/rgbd/linemod.hpp +++ b/modules/rgbd/include/opencv2/rgbd/linemod.hpp @@ -1,48 +1,11 @@ -/*M/////////////////////////////////////////////////////////////////////////////////////// -// -// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. -// -// By downloading, copying, installing or using the software you agree to this license. -// If you do not agree to this license, do not download, install, -// copy or use the software. -// -// -// License Agreement -// For Open Source Computer Vision Library -// -// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. -// Copyright (C) 2009, Willow Garage Inc., all rights reserved. -// Copyright (C) 2013, OpenCV Foundation, all rights reserved. -// Third party copyrights are property of their respective owners. -// -// Redistribution and use in source and binary forms, with or without modification, -// are permitted provided that the following conditions are met: -// -// * Redistribution's of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// * Redistribution's in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// * The name of the copyright holders may not be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// This software is provided by the copyright holders and contributors "as is" and -// any express or implied warranties, including, but not limited to, the implied -// warranties of merchantability and fitness for a particular purpose are disclaimed. -// In no event shall the Intel Corporation or contributors be liable for any direct, -// indirect, incidental, special, exemplary, or consequential damages -// (including, but not limited to, procurement of substitute goods or services; -// loss of use, data, or profits; or business interruption) however caused -// and on any theory of liability, whether in contract, strict liability, -// or tort (including negligence or otherwise) arising in any way out of -// the use of this software, even if advised of the possibility of such damage. -// -//M*/ - -#ifndef __OPENCV_OBJDETECT_LINEMOD_HPP__ -#define __OPENCV_OBJDETECT_LINEMOD_HPP__ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + +#ifndef __OPENCV_RGBD_LINEMOD_HPP__ +#define __OPENCV_RGBD_LINEMOD_HPP__ #include "opencv2/core.hpp" #include diff --git a/modules/rgbd/samples/CMakeLists.txt b/modules/rgbd/samples/CMakeLists.txt deleted file mode 100644 index 1f7390679..000000000 --- a/modules/rgbd/samples/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -cmake_minimum_required(VERSION 2.8) -project(map_test) -find_package(OpenCV REQUIRED) - -set(SOURCES odometry_evaluation.cpp) - -include_directories(${OpenCV_INCLUDE_DIRS}) -add_executable(odometry_evaluation ${SOURCES} ${HEADERS}) -target_link_libraries(odometry_evaluation ${OpenCV_LIBS}) diff --git a/modules/rgbd/samples/kinfu_demo.cpp b/modules/rgbd/samples/kinfu_demo.cpp new file mode 100644 index 000000000..0abb9f165 --- /dev/null +++ b/modules/rgbd/samples/kinfu_demo.cpp @@ -0,0 +1,235 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#include +#include +#include +#include +#include + +#ifdef HAVE_OPENCV_VIZ + +#include + +using namespace cv; +using namespace cv::kinfu; +using namespace std; + +static vector readDepth(std::string fileList); + +static vector readDepth(std::string fileList) +{ + vector v; + + fstream file(fileList); + if(!file.is_open()) + throw std::runtime_error("Failed to open file"); + + std::string dir; + size_t slashIdx = fileList.rfind('/'); + slashIdx = slashIdx != std::string::npos ? slashIdx : fileList.rfind('\\'); + dir = fileList.substr(0, slashIdx); + + while(!file.eof()) + { + std::string s, imgPath; + std::getline(file, s); + if(s.empty() || s[0] == '#') continue; + std::stringstream ss; + ss << s; + double thumb; + ss >> thumb >> imgPath; + v.push_back(dir+'/'+imgPath); + } + + return v; +} + +const std::string vizWindowName = "cloud"; + +struct PauseCallbackArgs +{ + PauseCallbackArgs(KinFu& _kf) : kf(_kf) + { } + + KinFu& kf; +}; + +void pauseCallback(const viz::MouseEvent& me, void* args); +void pauseCallback(const viz::MouseEvent& me, void* args) +{ + if(me.type == viz::MouseEvent::Type::MouseMove || + me.type == viz::MouseEvent::Type::MouseScrollDown || + me.type == viz::MouseEvent::Type::MouseScrollUp) + { + PauseCallbackArgs pca = *((PauseCallbackArgs*)(args)); + viz::Viz3d window(vizWindowName); + Mat rendered; + pca.kf.render(rendered, window.getViewerPose()); + imshow("render", rendered); + waitKey(1); + } +} + +static const char* keys = +{ + "{help h usage ? | | print this message }" + "{@depth || Path to depth.txt file listing a set of depth images }" + "{coarse | | Run on coarse settings (fast but ugly) or on default (slow but looks better)," + " in coarse mode points and normals are displayed }" +}; + +static const std::string message = + "\nThis demo uses RGB-D dataset taken from" + "\nhttps://vision.in.tum.de/data/datasets/rgbd-dataset" + "\nto demonstrate KinectFusion implementation \n"; + + +int main(int argc, char **argv) +{ + bool coarse = false; + + CommandLineParser parser(argc, argv, keys); + parser.about(message); + if(parser.has("help")) + { + parser.printMessage(); + return 0; + } + if(parser.has("coarse")) + { + coarse = true; + } + + String depthPath = parser.get(0); + + if(!parser.check()) + { + parser.printMessage(); + parser.printErrors(); + return -1; + } + + vector depthFileList = readDepth(depthPath); + + KinFu::Params params; + if(coarse) + params = KinFu::Params::coarseParams(); + else + params = KinFu::Params::defaultParams(); + + // scene-specific params should be tuned for each scene individually + params.volumePose = params.volumePose.translate(Vec3f(0.f, 0.f, 0.5f)); + params.tsdf_max_weight = 16; + + KinFu kf(params); + + cv::viz::Viz3d window(vizWindowName); + window.setViewerPose(Affine3f::Identity()); + + // TODO: can we use UMats for that? + Mat rendered; + Mat points; + Mat normals; + + double prevTime = getTickCount(); + + bool pause = false; + + for(size_t nFrame = 0; nFrame < depthFileList.size(); nFrame++) + { + if(pause) + { + kf.getCloud(points, normals); + viz::WCloud cloudWidget(points, viz::Color::white()); + viz::WCloudNormals cloudNormals(points, normals, /*level*/1, /*scale*/0.05, viz::Color::gray()); + window.showWidget("cloud", cloudWidget); + window.showWidget("normals", cloudNormals); + + window.showWidget("cube", viz::WCube(Vec3d::all(0), + Vec3d::all(kf.getParams().volumeSize)), + kf.getParams().volumePose); + PauseCallbackArgs pca(kf); + window.registerMouseCallback(pauseCallback, (void*)&pca); + window.showWidget("text", viz::WText(cv::String("Move camera in this window. " + "Close the window or press Q to resume"), Point())); + window.spin(); + window.removeWidget("text"); + window.registerMouseCallback(0); + + pause = false; + } + else + { + Mat frame = cv::imread(depthFileList[nFrame], IMREAD_ANYDEPTH); + if(frame.empty()) + throw std::runtime_error("Matrix is empty"); + + // 5000 for typical per-meter coefficient of PNG files + Mat cvt8; + convertScaleAbs(frame, cvt8, 0.25/5000.*256.); + imshow("depth", cvt8); + + if(!kf.update(frame)) + { + kf.reset(); + std::cout << "reset" << std::endl; + } + else + { + if(coarse) + { + kf.getCloud(points, normals); + viz::WCloud cloudWidget(points, viz::Color::white()); + viz::WCloudNormals cloudNormals(points, normals, /*level*/1, /*scale*/0.05, viz::Color::gray()); + window.showWidget("cloud", cloudWidget); + window.showWidget("normals", cloudNormals); + } + + //window.showWidget("worldAxes", viz::WCoordinateSystem()); + window.showWidget("cube", viz::WCube(Vec3d::all(0), + Vec3d::all(kf.getParams().volumeSize)), + kf.getParams().volumePose); + window.setViewerPose(kf.getPose()); + window.spinOnce(1, true); + } + + kf.render(rendered); + } + + double newTime = getTickCount(); + putText(rendered, cv::format("FPS: %2d press R to reset, P to pause, Q to quit", (int)(getTickFrequency()/(newTime - prevTime))), + Point(0, rendered.rows-1), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 255, 255)); + prevTime = newTime; + + imshow("render", rendered); + + int c = waitKey(1); + switch (c) + { + case 'r': + kf.reset(); + break; + case 'q': + return 0; + case 'p': + pause = true; + default: + break; + } + } + + return 0; +} + +#else + +int main(int /* argc */, char ** /* argv */) +{ + std::cout << "This demo requires viz module" << std::endl; + return 0; +} +#endif diff --git a/modules/rgbd/samples/linemod.cpp b/modules/rgbd/samples/linemod.cpp index 19100b4fe..4cc0da3a2 100644 --- a/modules/rgbd/samples/linemod.cpp +++ b/modules/rgbd/samples/linemod.cpp @@ -1,3 +1,9 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + #include #include #include // cvFindContours diff --git a/modules/rgbd/samples/odometry_evaluation.cpp b/modules/rgbd/samples/odometry_evaluation.cpp index 121acfc5a..b6d6605c6 100644 --- a/modules/rgbd/samples/odometry_evaluation.cpp +++ b/modules/rgbd/samples/odometry_evaluation.cpp @@ -1,37 +1,8 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include @@ -135,7 +106,7 @@ int main(int argc, char** argv) { if(argc != 4) { - cout << "Format: file_with_rgb_depth_pairs trajectory_file odometry_name [Rgbd or ICP or RgbdICP]" << endl; + cout << "Format: file_with_rgb_depth_pairs trajectory_file odometry_name [Rgbd or ICP or RgbdICP or FastICP]" << endl; return -1; } diff --git a/modules/rgbd/src/depth_cleaner.cpp b/modules/rgbd/src/depth_cleaner.cpp index ca6ba9d55..4c505d3e1 100644 --- a/modules/rgbd/src/depth_cleaner.cpp +++ b/modules/rgbd/src/depth_cleaner.cpp @@ -1,37 +1,8 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include "precomp.hpp" diff --git a/modules/rgbd/src/depth_registration.cpp b/modules/rgbd/src/depth_registration.cpp index f6bcf7d74..5739ec7d6 100644 --- a/modules/rgbd/src/depth_registration.cpp +++ b/modules/rgbd/src/depth_registration.cpp @@ -1,50 +1,11 @@ -/*M/////////////////////////////////////////////////////////////////////////////////////// -// -// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. -// -// By downloading, copying, installing or using the software you agree to this license. -// If you do not agree to this license, do not download, install, -// copy or use the software. -// -// -// License Agreement -// For Open Source Computer Vision Library -// -// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. -// Copyright (C) 2009, Willow Garage Inc., all rights reserved. -// Copyright (C) 2014, OpenCV Foundation, all rights reserved. -// Third party copyrights are property of their respective owners. -// -// Redistribution and use in source and binary forms, with or without modification, -// are permitted provided that the following conditions are met: -// -// * Redistribution's of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// * Redistribution's in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// * The name of the copyright holders may not be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// This software is provided by the copyright holders and contributors "as is" and -// any express or implied warranties, including, but not limited to, the implied -// warranties of merchantability and fitness for a particular purpose are disclaimed. -// In no event shall the Intel Corporation or contributors be liable for any direct, -// indirect, incidental, special, exemplary, or consequential damages -// (including, but not limited to, procurement of substitute goods or services; -// loss of use, data, or profits; or business interruption) however caused -// and on any theory of liability, whether in contract, strict liability, -// or tort (including negligence or otherwise) arising in any way out of -// the use of this software, even if advised of the possibility of such damage. -// -//M*/ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include "precomp.hpp" - namespace cv { namespace rgbd diff --git a/modules/rgbd/src/depth_to_3d.cpp b/modules/rgbd/src/depth_to_3d.cpp index cdcc4ea48..b57cca4d7 100644 --- a/modules/rgbd/src/depth_to_3d.cpp +++ b/modules/rgbd/src/depth_to_3d.cpp @@ -1,42 +1,14 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ - -#include - -#include "depth_to_3d.h" -#include "utils.h" +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + + +#include "precomp.hpp" + +#include "depth_to_3d.hpp" +#include "utils.hpp" namespace cv { diff --git a/modules/rgbd/src/depth_to_3d.h b/modules/rgbd/src/depth_to_3d.hpp similarity index 57% rename from modules/rgbd/src/depth_to_3d.h rename to modules/rgbd/src/depth_to_3d.hpp index 97e786730..055f1ec40 100644 --- a/modules/rgbd/src/depth_to_3d.h +++ b/modules/rgbd/src/depth_to_3d.hpp @@ -1,45 +1,13 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #ifndef __OPENCV_RGBD_DEPTH_TO_3D_HPP__ #define __OPENCV_RGBD_DEPTH_TO_3D_HPP__ -#ifdef __cplusplus - -#include -#include +#include "precomp.hpp" namespace cv { @@ -122,8 +90,6 @@ convertDepthToFloat(const cv::Mat& depth, float scale, const cv::Mat &uv_mat, cv } } -#endif /* __cplusplus */ - #endif /* End of file. */ diff --git a/modules/rgbd/src/fast_icp.cpp b/modules/rgbd/src/fast_icp.cpp new file mode 100644 index 000000000..342170b27 --- /dev/null +++ b/modules/rgbd/src/fast_icp.cpp @@ -0,0 +1,519 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#include "precomp.hpp" +#include "fast_icp.hpp" + +using namespace std; + +namespace cv { +namespace kinfu { + + +ICP::ICP(const Intr _intrinsics, const std::vector& _iterations, float _angleThreshold, float _distanceThreshold) : + iterations(_iterations), angleThreshold(_angleThreshold), distanceThreshold(_distanceThreshold), + intrinsics(_intrinsics) +{ } + +///////// CPU implementation ///////// + +class ICPCPU : public ICP +{ +public: + ICPCPU(const cv::kinfu::Intr _intrinsics, const std::vector &_iterations, float _angleThreshold, float _distanceThreshold); + + virtual bool estimateTransform(cv::Affine3f& transform, cv::Ptr oldFrame, cv::Ptr newFrame) const override; + + virtual ~ICPCPU() { } + +private: + void getAb(const Points &oldPts, const Normals &oldNrm, const Points &newPts, const Normals &newNrm, + cv::Affine3f pose, int level, cv::Matx66f& A, cv::Vec6f& b) const; +}; + + +ICPCPU::ICPCPU(const Intr _intrinsics, const std::vector &_iterations, float _angleThreshold, float _distanceThreshold) : + ICP(_intrinsics, _iterations, _angleThreshold, _distanceThreshold) +{ } + +bool ICPCPU::estimateTransform(cv::Affine3f& transform, cv::Ptr _oldFrame, cv::Ptr _newFrame) const +{ + ScopeTime st("icp"); + + cv::Ptr oldFrame = _oldFrame.dynamicCast(); + cv::Ptr newFrame = _newFrame.dynamicCast(); + + const std::vector& oldPoints = oldFrame->points; + const std::vector& oldNormals = oldFrame->normals; + const std::vector& newPoints = newFrame->points; + const std::vector& newNormals = newFrame->normals; + + transform = Affine3f::Identity(); + for(size_t l = 0; l < iterations.size(); l++) + { + size_t level = iterations.size() - 1 - l; + + Points oldPts = oldPoints [level], newPts = newPoints [level]; + Normals oldNrm = oldNormals[level], newNrm = newNormals[level]; + + for(int iter = 0; iter < iterations[level]; iter++) + { + Matx66f A; + Vec6f b; + + getAb(oldPts, oldNrm, newPts, newNrm, transform, (int)level, A, b); + + double det = cv::determinant(A); + + if (abs (det) < 1e-15 || cvIsNaN(det)) + return false; + + Vec6f x; + // theoretically, any method of solving is applicable + // since there are usual least square matrices + solve(A, b, x, DECOMP_SVD); + Affine3f tinc(Vec3f(x.val), Vec3f(x.val+3)); + transform = tinc * transform; + } + } + + return true; +} + +// 1 any coord to check is enough since we know the generation + + +#if CV_SIMD128 +static inline bool fastCheck(const v_float32x4& p0, const v_float32x4& p1) +{ + float check = (p0.get0() + p1.get0()); + return !cvIsNaN(check); +} + +static inline void getCrossPerm(const v_float32x4& a, v_float32x4& yzx, v_float32x4& zxy) +{ + v_uint32x4 aa = v_reinterpret_as_u32(a); + v_uint32x4 yz00 = v_extract<1>(aa, v_setzero_u32()); + v_uint32x4 x0y0, tmp; + v_zip(aa, v_setzero_u32(), x0y0, tmp); + v_uint32x4 yzx0 = v_combine_low(yz00, x0y0); + v_uint32x4 y000 = v_extract<2>(x0y0, v_setzero_u32()); + v_uint32x4 zx00 = v_extract<1>(yzx0, v_setzero_u32()); + zxy = v_reinterpret_as_f32(v_combine_low(zx00, y000)); + yzx = v_reinterpret_as_f32(yzx0); +} + +static inline v_float32x4 crossProduct(const v_float32x4& a, const v_float32x4& b) +{ + v_float32x4 ayzx, azxy, byzx, bzxy; + getCrossPerm(a, ayzx, azxy); + getCrossPerm(b, byzx, bzxy); + return ayzx*bzxy - azxy*byzx; +} +#else +static inline bool fastCheck(const Point3f& p) +{ + return !cvIsNaN(p.x); +} + +#endif + +typedef Matx ABtype; + +struct GetAbInvoker : ParallelLoopBody +{ + enum + { + UTSIZE = 27 + }; + + GetAbInvoker(ABtype& _globalAb, Mutex& _mtx, + const Points& _oldPts, const Normals& _oldNrm, const Points& _newPts, const Normals& _newNrm, + Affine3f _pose, Intr::Projector _proj, float _sqDistanceThresh, float _minCos) : + ParallelLoopBody(), + globalSumAb(_globalAb), mtx(_mtx), + oldPts(_oldPts), oldNrm(_oldNrm), newPts(_newPts), newNrm(_newNrm), pose(_pose), + proj(_proj), sqDistanceThresh(_sqDistanceThresh), minCos(_minCos) + { } + + virtual void operator ()(const Range& range) const override + { +#if CV_SIMD128 + CV_Assert(ptype::channels == 4); + + const size_t utBufferSize = 9; + float CV_DECL_ALIGNED(16) upperTriangle[utBufferSize*4]; + for(size_t i = 0; i < utBufferSize*4; i++) + upperTriangle[i] = 0; + // how values are kept in upperTriangle + const int NA = 0; + const size_t utPos[] = + { + 0, 1, 2, 4, 5, 6, 3, + NA, 9, 10, 12, 13, 14, 11, + NA, NA, 18, 20, 21, 22, 19, + NA, NA, NA, 24, 28, 30, 32, + NA, NA, NA, NA, 25, 29, 33, + NA, NA, NA, NA, NA, 26, 34 + }; + + const float (&pm)[16] = pose.matrix.val; + v_float32x4 poseRot0(pm[0], pm[4], pm[ 8], 0); + v_float32x4 poseRot1(pm[1], pm[5], pm[ 9], 0); + v_float32x4 poseRot2(pm[2], pm[6], pm[10], 0); + v_float32x4 poseTrans(pm[3], pm[7], pm[11], 0); + + v_float32x4 vfxy(proj.fx, proj.fy, 0, 0), vcxy(proj.cx, proj.cy, 0, 0); + v_float32x4 vframe((float)(oldPts.cols - 1), (float)(oldPts.rows - 1), 1.f, 1.f); + + float sqThresh = sqDistanceThresh; + float cosThresh = minCos; + + for(int y = range.start; y < range.end; y++) + { + const CV_DECL_ALIGNED(16) float* newPtsRow = (const float*)newPts[y]; + const CV_DECL_ALIGNED(16) float* newNrmRow = (const float*)newNrm[y]; + + for(int x = 0; x < newPts.cols; x++) + { + v_float32x4 newP = v_load_aligned(newPtsRow + x*4); + v_float32x4 newN = v_load_aligned(newNrmRow + x*4); + + if(!fastCheck(newP, newN)) + continue; + + //transform to old coord system + newP = v_matmuladd(newP, poseRot0, poseRot1, poseRot2, poseTrans); + newN = v_matmuladd(newN, poseRot0, poseRot1, poseRot2, v_setzero_f32()); + + //find correspondence by projecting the point + v_float32x4 oldCoords; + float pz = (v_reinterpret_as_f32(v_rotate_right<2>(v_reinterpret_as_u32(newP))).get0()); + // x, y, 0, 0 + oldCoords = v_muladd(newP/v_setall_f32(pz), vfxy, vcxy); + + if(!v_check_all((oldCoords >= v_setzero_f32()) & (oldCoords < vframe))) + continue; + + // bilinearly interpolate oldPts and oldNrm under oldCoords point + v_float32x4 oldP; + v_float32x4 oldN; + { + v_int32x4 ixy = v_floor(oldCoords); + v_float32x4 txy = oldCoords - v_cvt_f32(ixy); + int xi = ixy.get0(); + int yi = v_rotate_right<1>(ixy).get0(); + v_float32x4 tx = v_setall_f32(txy.get0()); + txy = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(txy))); + v_float32x4 ty = v_setall_f32(txy.get0()); + + const float* prow0 = (const float*)oldPts[yi+0]; + const float* prow1 = (const float*)oldPts[yi+1]; + + v_float32x4 p00 = v_load(prow0 + (xi+0)*4); + v_float32x4 p01 = v_load(prow0 + (xi+1)*4); + v_float32x4 p10 = v_load(prow1 + (xi+0)*4); + v_float32x4 p11 = v_load(prow1 + (xi+1)*4); + + // do not fix missing data + // NaN check is done later + + const float* nrow0 = (const float*)oldNrm[yi+0]; + const float* nrow1 = (const float*)oldNrm[yi+1]; + + v_float32x4 n00 = v_load(nrow0 + (xi+0)*4); + v_float32x4 n01 = v_load(nrow0 + (xi+1)*4); + v_float32x4 n10 = v_load(nrow1 + (xi+0)*4); + v_float32x4 n11 = v_load(nrow1 + (xi+1)*4); + + // NaN check is done later + + v_float32x4 p0 = p00 + tx*(p01 - p00); + v_float32x4 p1 = p10 + tx*(p11 - p10); + oldP = p0 + ty*(p1 - p0); + + v_float32x4 n0 = n00 + tx*(n01 - n00); + v_float32x4 n1 = n10 + tx*(n11 - n10); + oldN = n0 + ty*(n1 - n0); + } + + bool oldPNcheck = fastCheck(oldP, oldN); + + //filter by distance + v_float32x4 diff = newP - oldP; + bool distCheck = !(v_reduce_sum(diff*diff) > sqThresh); + + //filter by angle + bool angleCheck = !(abs(v_reduce_sum(newN*oldN)) < cosThresh); + + if(!(oldPNcheck && distCheck && angleCheck)) + continue; + + // build point-wise vector ab = [ A | b ] + + v_float32x4 VxNv = crossProduct(newP, oldN); + Point3f VxN; + VxN.x = VxNv.get0(); + VxN.y = v_reinterpret_as_f32(v_extract<1>(v_reinterpret_as_u32(VxNv), v_setzero_u32())).get0(); + VxN.z = v_reinterpret_as_f32(v_extract<2>(v_reinterpret_as_u32(VxNv), v_setzero_u32())).get0(); + + float dotp = -v_reduce_sum(oldN*diff); + + // build point-wise upper-triangle matrix [ab^T * ab] w/o last row + // which is [A^T*A | A^T*b] + // and gather sum + + v_float32x4 vd = VxNv | v_float32x4(0, 0, 0, dotp); + v_float32x4 n = oldN; + v_float32x4 nyzx; + { + v_uint32x4 aa = v_reinterpret_as_u32(n); + v_uint32x4 yz00 = v_extract<1>(aa, v_setzero_u32()); + v_uint32x4 x0y0, tmp; + v_zip(aa, v_setzero_u32(), x0y0, tmp); + nyzx = v_reinterpret_as_f32(v_combine_low(yz00, x0y0)); + } + + v_float32x4 vutg[utBufferSize]; + for(size_t i = 0; i < utBufferSize; i++) + vutg[i] = v_load_aligned(upperTriangle + i*4); + + int p = 0; + v_float32x4 v; + // vx * vd, vx * n + v = v_setall_f32(VxN.x); + v_store_aligned(upperTriangle + p*4, v_muladd(v, vd, vutg[p])); p++; + v_store_aligned(upperTriangle + p*4, v_muladd(v, n, vutg[p])); p++; + // vy * vd, vy * n + v = v_setall_f32(VxN.y); + v_store_aligned(upperTriangle + p*4, v_muladd(v, vd, vutg[p])); p++; + v_store_aligned(upperTriangle + p*4, v_muladd(v, n, vutg[p])); p++; + // vz * vd, vz * n + v = v_setall_f32(VxN.z); + v_store_aligned(upperTriangle + p*4, v_muladd(v, vd, vutg[p])); p++; + v_store_aligned(upperTriangle + p*4, v_muladd(v, n, vutg[p])); p++; + // nx^2, ny^2, nz^2 + v_store_aligned(upperTriangle + p*4, v_muladd(n, n, vutg[p])); p++; + // nx*ny, ny*nz, nx*nz + v_store_aligned(upperTriangle + p*4, v_muladd(n, nyzx, vutg[p])); p++; + // nx*d, ny*d, nz*d + v = v_setall_f32(dotp); + v_store_aligned(upperTriangle + p*4, v_muladd(n, v, vutg[p])); p++; + } + } + + ABtype sumAB = ABtype::zeros(); + for(int i = 0; i < 6; i++) + { + for(int j = i; j < 7; j++) + { + size_t p = utPos[i*7+j]; + sumAB(i, j) = upperTriangle[p]; + } + } + +#else + + float upperTriangle[UTSIZE]; + for(int i = 0; i < UTSIZE; i++) + upperTriangle[i] = 0; + + for(int y = range.start; y < range.end; y++) + { + const ptype* newPtsRow = newPts[y]; + const ptype* newNrmRow = newNrm[y]; + + for(int x = 0; x < newPts.cols; x++) + { + Point3f newP = fromPtype(newPtsRow[x]); + Point3f newN = fromPtype(newNrmRow[x]); + + Point3f oldP(nan3), oldN(nan3); + + if(!(fastCheck(newP) && fastCheck(newN))) + continue; + + //transform to old coord system + newP = pose * newP; + newN = pose.rotation() * newN; + + //find correspondence by projecting the point + Point2f oldCoords = proj(newP); + if(!(oldCoords.x >= 0 && oldCoords.x < oldPts.cols - 1 && + oldCoords.y >= 0 && oldCoords.y < oldPts.rows - 1)) + continue; + + // bilinearly interpolate oldPts and oldNrm under oldCoords point + int xi = cvFloor(oldCoords.x), yi = cvFloor(oldCoords.y); + float tx = oldCoords.x - xi, ty = oldCoords.y - yi; + + const ptype* prow0 = oldPts[yi+0]; + const ptype* prow1 = oldPts[yi+1]; + + Point3f p00 = fromPtype(prow0[xi+0]); + Point3f p01 = fromPtype(prow0[xi+1]); + Point3f p10 = fromPtype(prow1[xi+0]); + Point3f p11 = fromPtype(prow1[xi+1]); + + //do not fix missing data + if(!(fastCheck(p00) && fastCheck(p01) && + fastCheck(p10) && fastCheck(p11))) + continue; + + const ptype* nrow0 = oldNrm[yi+0]; + const ptype* nrow1 = oldNrm[yi+1]; + + Point3f n00 = fromPtype(nrow0[xi+0]); + Point3f n01 = fromPtype(nrow0[xi+1]); + Point3f n10 = fromPtype(nrow1[xi+0]); + Point3f n11 = fromPtype(nrow1[xi+1]); + + if(!(fastCheck(n00) && fastCheck(n01) && + fastCheck(n10) && fastCheck(n11))) + continue; + + Point3f p0 = p00 + tx*(p01 - p00); + Point3f p1 = p10 + tx*(p11 - p10); + oldP = p0 + ty*(p1 - p0); + + Point3f n0 = n00 + tx*(n01 - n00); + Point3f n1 = n10 + tx*(n11 - n10); + oldN = n0 + ty*(n1 - n0); + + if(!(fastCheck(oldP) && fastCheck(oldN))) + continue; + + //filter by distance + Point3f diff = newP - oldP; + if(diff.dot(diff) > sqDistanceThresh) + { + continue; + } + + //filter by angle + if(abs(newN.dot(oldN)) < minCos) + { + continue; + } + + // build point-wise vector ab = [ A | b ] + + //try to optimize + Point3f VxN = newP.cross(oldN); + float ab[7] = {VxN.x, VxN.y, VxN.z, oldN.x, oldN.y, oldN.z, oldN.dot(-diff)}; + + // build point-wise upper-triangle matrix [ab^T * ab] w/o last row + // which is [A^T*A | A^T*b] + // and gather sum + int pos = 0; + for(int i = 0; i < 6; i++) + { + for(int j = i; j < 7; j++) + { + upperTriangle[pos++] += ab[i]*ab[j]; + } + } + } + } + + ABtype sumAB = ABtype::zeros(); + int pos = 0; + for(int i = 0; i < 6; i++) + { + for(int j = i; j < 7; j++) + { + sumAB(i, j) = upperTriangle[pos++]; + } + } +#endif + + AutoLock al(mtx); + globalSumAb += sumAB; + } + + ABtype& globalSumAb; + Mutex& mtx; + const Points& oldPts; + const Normals& oldNrm; + const Points& newPts; + const Normals& newNrm; + Affine3f pose; + const Intr::Projector proj; + float sqDistanceThresh; + float minCos; +}; + + +void ICPCPU::getAb(const Points& oldPts, const Normals& oldNrm, const Points& newPts, const Normals& newNrm, + Affine3f pose, int level, Matx66f &A, Vec6f &b) const +{ + ScopeTime st("icp: get ab", false); + + CV_Assert(oldPts.size() == oldNrm.size()); + CV_Assert(newPts.size() == newNrm.size()); + + ABtype sumAB = ABtype::zeros(); + + Mutex mutex; + GetAbInvoker invoker(sumAB, mutex, oldPts, oldNrm, newPts, newNrm, pose, + intrinsics.scale(level).makeProjector(), + distanceThreshold*distanceThreshold, cos(angleThreshold)); + Range range(0, newPts.rows); + const int nstripes = -1; + parallel_for_(range, invoker, nstripes); + + // splitting AB matrix to A and b + for(int i = 0; i < 6; i++) + { + // augment lower triangle of A by symmetry + for(int j = i; j < 6; j++) + { + A(i, j) = A(j, i) = sumAB(i, j); + } + + b(i) = sumAB(i, 6); + } +} + +///////// GPU implementation ///////// + +class ICPGPU : public ICP +{ +public: + ICPGPU(const cv::kinfu::Intr _intrinsics, const std::vector &_iterations, float _angleThreshold, float _distanceThreshold); + + virtual bool estimateTransform(cv::Affine3f& transform, cv::Ptr oldFrame, cv::Ptr newFrame) const override; + + virtual ~ICPGPU() { } +}; + +ICPGPU::ICPGPU(const Intr _intrinsics, const std::vector &_iterations, float _angleThreshold, float _distanceThreshold) : + ICP(_intrinsics, _iterations, _angleThreshold, _distanceThreshold) +{ } + + +bool ICPGPU::estimateTransform(cv::Affine3f& /*transform*/, cv::Ptr /*_oldFrame*/, cv::Ptr /*newFrame*/) const +{ + throw std::runtime_error("Not implemented"); +} + +cv::Ptr makeICP(cv::kinfu::KinFu::Params::PlatformType t, + const cv::kinfu::Intr _intrinsics, const std::vector &_iterations, + float _angleThreshold, float _distanceThreshold) +{ + switch (t) + { + case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_CPU: + return cv::makePtr(_intrinsics, _iterations, _angleThreshold, _distanceThreshold); + case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_GPU: + return cv::makePtr(_intrinsics, _iterations, _angleThreshold, _distanceThreshold); + default: + return cv::Ptr(); + } +} + +} // namespace kinfu +} // namespace cv diff --git a/modules/rgbd/src/fast_icp.hpp b/modules/rgbd/src/fast_icp.hpp new file mode 100644 index 000000000..8d31351e8 --- /dev/null +++ b/modules/rgbd/src/fast_icp.hpp @@ -0,0 +1,39 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#ifndef __OPENCV_KINFU_FAST_ICP_H__ +#define __OPENCV_KINFU_FAST_ICP_H__ + +#include "precomp.hpp" +#include "kinfu_frame.hpp" + +namespace cv { +namespace kinfu { + +class ICP +{ +public: + ICP(const cv::kinfu::Intr _intrinsics, const std::vector &_iterations, float _angleThreshold, float _distanceThreshold); + + virtual bool estimateTransform(cv::Affine3f& transform, cv::Ptr oldFrame, cv::Ptr newFrame) const = 0; + + virtual ~ICP() { } + +protected: + + std::vector iterations; + float angleThreshold; + float distanceThreshold; + cv::kinfu::Intr intrinsics; +}; + +cv::Ptr makeICP(cv::kinfu::KinFu::Params::PlatformType t, + const cv::kinfu::Intr _intrinsics, const std::vector &_iterations, + float _angleThreshold, float _distanceThreshold); + +} // namespace kinfu +} // namespace cv +#endif diff --git a/modules/rgbd/src/kinfu.cpp b/modules/rgbd/src/kinfu.cpp new file mode 100644 index 000000000..62ca933d3 --- /dev/null +++ b/modules/rgbd/src/kinfu.cpp @@ -0,0 +1,319 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#include "precomp.hpp" +#include "fast_icp.hpp" +#include "tsdf.hpp" +#include "kinfu_frame.hpp" + +namespace cv { +namespace kinfu { + +class KinFu::KinFuImpl +{ +public: + KinFuImpl(const KinFu::Params& _params); + virtual ~KinFuImpl(); + + const KinFu::Params& getParams() const; + void setParams(const KinFu::Params&); + + void render(OutputArray image, const Affine3f cameraPose = Affine3f::Identity()) const; + + void getCloud(OutputArray points, OutputArray normals) const; + void getPoints(OutputArray points) const; + void getNormals(InputArray points, OutputArray normals) const; + + void reset(); + + const Affine3f getPose() const; + + bool update(InputArray depth); + +private: + KinFu::Params params; + + cv::Ptr frameGenerator; + cv::Ptr icp; + cv::Ptr volume; + + int frameCounter; + Affine3f pose; + cv::Ptr frame; +}; + +KinFu::Params KinFu::Params::defaultParams() +{ + Params p; + + p.platform = PLATFORM_CPU; + + p.frameSize = Size(640, 480); + + float fx, fy, cx, cy; + fx = fy = 525.f; + cx = p.frameSize.width/2 - 0.5f; + cy = p.frameSize.height/2 - 0.5f; + p.intr = Matx33f(fx, 0, cx, + 0, fy, cy, + 0, 0, 1); + + // 5000 for the 16-bit PNG files + // 1 for the 32-bit float images in the ROS bag files + p.depthFactor = 5000; + + // sigma_depth is scaled by depthFactor when calling bilateral filter + p.bilateral_sigma_depth = 0.04f; //meter + p.bilateral_sigma_spatial = 4.5; //pixels + p.bilateral_kernel_size = 7; //pixels + + p.icpAngleThresh = (float)(30. * CV_PI / 180.); // radians + p.icpDistThresh = 0.1f; // meters + // first non-zero numbers are accepted + const int iters[] = {10, 5, 4, 0}; + + for(size_t i = 0; i < sizeof(iters)/sizeof(int); i++) + { + if(iters[i]) + { + p.icpIterations.push_back(iters[i]); + } + else + break; + } + p.pyramidLevels = (int)p.icpIterations.size(); + + p.tsdf_min_camera_movement = 0.f; //meters, disabled + + p.volumeDims = 512; //number of voxels + + p.volumeSize = 3.f; //meters + + // default pose of volume cube + p.volumePose = Affine3f().translate(Vec3f(-p.volumeSize/2, -p.volumeSize/2, 0.5f)); + p.tsdf_trunc_dist = 0.04f; //meters; + p.tsdf_max_weight = 64; //frames + + p.raycast_step_factor = 0.25f; //in voxel sizes + // gradient delta factor is fixed at 1.0f and is not used + //p.gradient_delta_factor = 0.5f; //in voxel sizes + + //p.lightPose = p.volume_pose.translation()/4; //meters + p.lightPose = Vec3f::all(0.f); //meters + + // depth truncation is not used by default + //p.icp_truncate_depth_dist = 0.f; //meters, disabled + + return p; +} + +KinFu::Params KinFu::Params::coarseParams() +{ + Params p = defaultParams(); + + // first non-zero numbers are accepted + const int iters[] = {5, 3, 2}; + + p.icpIterations.clear(); + for(size_t i = 0; i < sizeof(iters)/sizeof(int); i++) + { + if(iters[i]) + { + p.icpIterations.push_back(iters[i]); + } + else + break; + } + p.pyramidLevels = (int)p.icpIterations.size(); + + p.volumeDims = 128; //number of voxels + + p.raycast_step_factor = 0.75f; //in voxel sizes + + return p; +} + +KinFu::KinFuImpl::KinFuImpl(const KinFu::Params &_params) : + params(_params), + frameGenerator(makeFrameGenerator(params.platform)), + icp(makeICP(params.platform, params.intr, params.icpIterations, params.icpAngleThresh, params.icpDistThresh)), + volume(makeTSDFVolume(params.platform, params.volumeDims, params.volumeSize, params.volumePose, + params.tsdf_trunc_dist, params.tsdf_max_weight, + params.raycast_step_factor)), + frame() +{ + reset(); +} + +void KinFu::KinFuImpl::reset() +{ + frameCounter = 0; + pose = Affine3f::Identity(); + volume->reset(); +} + +KinFu::KinFuImpl::~KinFuImpl() +{ + +} + +const KinFu::Params& KinFu::KinFuImpl::getParams() const +{ + return params; +} + +void KinFu::KinFuImpl::setParams(const KinFu::Params& p) +{ + params = p; +} + +const Affine3f KinFu::KinFuImpl::getPose() const +{ + return pose; +} + +bool KinFu::KinFuImpl::update(InputArray _depth) +{ + ScopeTime st("kinfu update"); + + CV_Assert(!_depth.empty() && _depth.size() == params.frameSize); + + cv::Ptr newFrame = (*frameGenerator)(); + (*frameGenerator)(newFrame, _depth, + params.intr, + params.pyramidLevels, + params.depthFactor, + params.bilateral_sigma_depth, + params.bilateral_sigma_spatial, + params.bilateral_kernel_size); + + if(frameCounter == 0) + { + // use depth instead of distance + volume->integrate(newFrame, params.depthFactor, pose, params.intr); + + frame = newFrame; + } + else + { + Affine3f affine; + bool success = icp->estimateTransform(affine, frame, newFrame); + if(!success) + return false; + + pose = pose * affine; + + float rnorm = (float)cv::norm(affine.rvec()); + float tnorm = (float)cv::norm(affine.translation()); + // We do not integrate volume if camera does not move + if((rnorm + tnorm)/2 >= params.tsdf_min_camera_movement) + { + // use depth instead of distance + volume->integrate(newFrame, params.depthFactor, pose, params.intr); + } + + // raycast and build a pyramid of points and normals + volume->raycast(pose, params.intr, params.frameSize, + params.pyramidLevels, frameGenerator, frame); + } + + frameCounter++; + return true; +} + + +void KinFu::KinFuImpl::render(OutputArray image, const Affine3f cameraPose) const +{ + ScopeTime st("kinfu render"); + + const Affine3f id = Affine3f::Identity(); + if((cameraPose.rotation() == pose.rotation() && cameraPose.translation() == pose.translation()) || + (cameraPose.rotation() == id.rotation() && cameraPose.translation() == id.translation())) + { + frame->render(image, 0, params.lightPose); + } + else + { + // raycast and build a pyramid of points and normals + cv::Ptr f = (*frameGenerator)(); + volume->raycast(cameraPose, params.intr, params.frameSize, + params.pyramidLevels, frameGenerator, f); + f->render(image, 0, params.lightPose); + } +} + + +void KinFu::KinFuImpl::getCloud(OutputArray p, OutputArray n) const +{ + volume->fetchPointsNormals(p, n); +} + +void KinFu::KinFuImpl::getPoints(OutputArray points) const +{ + volume->fetchPointsNormals(points, noArray()); +} + +void KinFu::KinFuImpl::getNormals(InputArray points, OutputArray normals) const +{ + volume->fetchNormals(points, normals); +} + +// importing class + +KinFu::KinFu(const Params& _params) +{ + impl = makePtr(_params); +} + +KinFu::~KinFu() { } + +const KinFu::Params& KinFu::getParams() const +{ + return impl->getParams(); +} + +void KinFu::setParams(const Params& p) +{ + impl->setParams(p); +} + +const Affine3f KinFu::getPose() const +{ + return impl->getPose(); +} + +void KinFu::reset() +{ + impl->reset(); +} + +void KinFu::getCloud(cv::OutputArray points, cv::OutputArray normals) const +{ + impl->getCloud(points, normals); +} + +void KinFu::getPoints(OutputArray points) const +{ + impl->getPoints(points); +} + +void KinFu::getNormals(InputArray points, OutputArray normals) const +{ + impl->getNormals(points, normals); +} + +bool KinFu::update(InputArray depth) +{ + return impl->update(depth); +} + +void KinFu::render(cv::OutputArray image, const Affine3f cameraPose) const +{ + impl->render(image, cameraPose); +} + +} // namespace kinfu +} // namespace cv diff --git a/modules/rgbd/src/kinfu_frame.cpp b/modules/rgbd/src/kinfu_frame.cpp new file mode 100644 index 000000000..74d37b476 --- /dev/null +++ b/modules/rgbd/src/kinfu_frame.cpp @@ -0,0 +1,459 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#include "precomp.hpp" +#include "kinfu_frame.hpp" + +namespace cv { +namespace kinfu { + +struct FrameGeneratorCPU : FrameGenerator +{ +public: + virtual cv::Ptr operator ()() const override; + virtual void operator() (Ptr _frame, InputArray depth, const kinfu::Intr, int levels, float depthFactor, + float sigmaDepth, float sigmaSpatial, int kernelSize) const override; + virtual void operator() (Ptr _frame, InputArray points, InputArray normals, int levels) const override; + + virtual ~FrameGeneratorCPU() {} +}; + +void computePointsNormals(const cv::kinfu::Intr, float depthFactor, const Depth, Points, Normals ); +Depth pyrDownBilateral(const Depth depth, float sigma); +void pyrDownPointsNormals(const Points p, const Normals n, Points& pdown, Normals& ndown); + +cv::Ptr FrameGeneratorCPU::operator ()() const +{ + return makePtr(); +} + +void FrameGeneratorCPU::operator ()(Ptr _frame, InputArray depth, const Intr intr, int levels, float depthFactor, + float sigmaDepth, float sigmaSpatial, int kernelSize) const +{ + ScopeTime st("frameGenerator: from depth"); + + Ptr frame = _frame.dynamicCast(); + + CV_Assert(frame); + + //CV_Assert(depth.type() == CV_16S); + // this should convert CV_16S to CV_32F + frame->depthData = Depth(depth.getMat()); + + // looks like OpenCV's bilateral filter works the same as KinFu's + Depth smooth; + bilateralFilter(frame->depthData, smooth, kernelSize, sigmaDepth*depthFactor, sigmaSpatial); + + // depth truncation is not used by default + //if (p.icp_truncate_depth_dist > 0) kfusion::cuda::depthTruncation(curr_.depth_pyr[0], p.icp_truncate_depth_dist); + + // we don't need depth pyramid outside this method + // if we do, the code is to be refactored + + Depth scaled = smooth; + Size sz = smooth.size(); + frame->points.resize(levels); + frame->normals.resize(levels); + for(int i = 0; i < levels; i++) + { + Points p = frame->points[i]; + Normals n = frame->normals[i]; + p.create(sz); n.create(sz); + + computePointsNormals(intr.scale(i), depthFactor, scaled, p, n); + + frame->points[i] = p; + frame->normals[i] = n; + + if(i < levels - 1) + { + sz.width /= 2; sz.height /= 2; + scaled = pyrDownBilateral(scaled, sigmaDepth*depthFactor); + } + } +} + +void FrameGeneratorCPU::operator ()(Ptr _frame, InputArray _points, InputArray _normals, int levels) const +{ + ScopeTime st("frameGenerator: pyrDown p, n"); + + CV_Assert( _points.type() == DataType::type); + CV_Assert(_normals.type() == DataType::type); + + Ptr frame = _frame.dynamicCast(); + + CV_Assert(frame); + + frame->depthData = Depth(); + frame->points.resize(levels); + frame->normals.resize(levels); + frame->points[0] = _points.getMat(); + frame->normals[0] = _normals.getMat(); + Size sz = _points.size(); + for(int i = 1; i < levels; i++) + { + sz.width /= 2; sz.height /= 2; + frame->points[i].create(sz); + frame->normals[i].create(sz); + pyrDownPointsNormals(frame->points[i-1], frame->normals[i-1], + frame->points[i ], frame->normals[i ]); + } +} + +template +inline float specPow(float x) +{ + if(p % 2 == 0) + { + float v = specPow

(x); + return v*v; + } + else + { + float v = specPow<(p-1)/2>(x); + return v*v*x; + } +} + +template<> +inline float specPow<0>(float /*x*/) +{ + return 1.f; +} + +template<> +inline float specPow<1>(float x) +{ + return x; +} + +struct RenderInvoker : ParallelLoopBody +{ + RenderInvoker(const Points& _points, const Normals& _normals, Mat_& _img, Affine3f _lightPose, Size _sz) : + ParallelLoopBody(), + points(_points), + normals(_normals), + img(_img), + lightPose(_lightPose), + sz(_sz) + { } + + virtual void operator ()(const Range& range) const override + { + for(int y = range.start; y < range.end; y++) + { + Vec3b* imgRow = img[y]; + const ptype* ptsRow = points[y]; + const ptype* nrmRow = normals[y]; + + for(int x = 0; x < sz.width; x++) + { + Point3f p = fromPtype(ptsRow[x]); + Point3f n = fromPtype(nrmRow[x]); + + Vec3b color; + + if(isNaN(p)) + { + color = Vec3b(0, 32, 0); + } + else + { + const float Ka = 0.3f; //ambient coeff + const float Kd = 0.5f; //diffuse coeff + const float Ks = 0.2f; //specular coeff + const int sp = 20; //specular power + + const float Ax = 1.f; //ambient color, can be RGB + const float Dx = 1.f; //diffuse color, can be RGB + const float Sx = 1.f; //specular color, can be RGB + const float Lx = 1.f; //light color + + Point3f l = normalize(lightPose.translation() - Vec3f(p)); + Point3f v = normalize(-Vec3f(p)); + Point3f r = normalize(Vec3f(2.f*n*n.dot(l) - l)); + + uchar ix = (uchar)((Ax*Ka*Dx + Lx*Kd*Dx*max(0.f, n.dot(l)) + + Lx*Ks*Sx*specPow(max(0.f, r.dot(v))))*255.f); + color = Vec3b(ix, ix, ix); + } + + imgRow[x] = color; + } + } + } + + const Points& points; + const Normals& normals; + Mat_& img; + Affine3f lightPose; + Size sz; +}; + +void FrameCPU::render(OutputArray image, int level, Affine3f lightPose) const +{ + ScopeTime st("frame render"); + + CV_Assert(level < (int)points.size()); + CV_Assert(level < (int)normals.size()); + + Size sz = points[level].size(); + image.create(sz, CV_8UC3); + Mat_ img = image.getMat(); + + RenderInvoker ri(points[level], normals[level], img, lightPose, sz); + Range range(0, sz.height); + const int nstripes = -1; + parallel_for_(range, ri, nstripes); +} + + +void FrameCPU::getDepth(OutputArray _depth) const +{ + CV_Assert(!depthData.empty()); + _depth.assign(depthData); +} + + +void pyrDownPointsNormals(const Points p, const Normals n, Points &pdown, Normals &ndown) +{ + for(int y = 0; y < pdown.rows; y++) + { + ptype* ptsRow = pdown[y]; + ptype* nrmRow = ndown[y]; + const ptype* pUpRow0 = p[2*y]; + const ptype* pUpRow1 = p[2*y+1]; + const ptype* nUpRow0 = n[2*y]; + const ptype* nUpRow1 = n[2*y+1]; + for(int x = 0; x < pdown.cols; x++) + { + Point3f point = nan3, normal = nan3; + + Point3f d00 = fromPtype(pUpRow0[2*x]); + Point3f d01 = fromPtype(pUpRow0[2*x+1]); + Point3f d10 = fromPtype(pUpRow1[2*x]); + Point3f d11 = fromPtype(pUpRow1[2*x+1]); + + if(!(isNaN(d00) || isNaN(d01) || isNaN(d10) || isNaN(d11))) + { + point = (d00 + d01 + d10 + d11)*0.25f; + + Point3f n00 = fromPtype(nUpRow0[2*x]); + Point3f n01 = fromPtype(nUpRow0[2*x+1]); + Point3f n10 = fromPtype(nUpRow1[2*x]); + Point3f n11 = fromPtype(nUpRow1[2*x+1]); + + normal = (n00 + n01 + n10 + n11)*0.25f; + } + + ptsRow[x] = toPtype(point); + nrmRow[x] = toPtype(normal); + } + } +} + +struct PyrDownBilateralInvoker : ParallelLoopBody +{ + PyrDownBilateralInvoker(const Depth& _depth, Depth& _depthDown, float _sigma) : + ParallelLoopBody(), + depth(_depth), + depthDown(_depthDown), + sigma(_sigma) + { } + + virtual void operator ()(const Range& range) const override + { + float sigma3 = sigma*3; + const int D = 5; + + for(int y = range.start; y < range.end; y++) + { + depthType* downRow = depthDown[y]; + const depthType* srcCenterRow = depth[2*y]; + + for(int x = 0; x < depthDown.cols; x++) + { + depthType center = srcCenterRow[2*x]; + + int sx = max(0, 2*x - D/2), ex = min(2*x - D/2 + D, depth.cols-1); + int sy = max(0, 2*y - D/2), ey = min(2*y - D/2 + D, depth.rows-1); + + depthType sum = 0; + int count = 0; + + for(int iy = sy; iy < ey; iy++) + { + const depthType* srcRow = depth[iy]; + for(int ix = sx; ix < ex; ix++) + { + depthType val = srcRow[ix]; + if(abs(val - center) < sigma3) + { + sum += val; count ++; + } + } + } + + downRow[x] = (count == 0) ? 0 : sum / count; + } + } + } + + const Depth& depth; + Depth& depthDown; + float sigma; +}; + + +Depth pyrDownBilateral(const Depth depth, float sigma) +{ + Depth depthDown(depth.rows/2, depth.cols/2); + + PyrDownBilateralInvoker pdi(depth, depthDown, sigma); + Range range(0, depthDown.rows); + const int nstripes = -1; + parallel_for_(range, pdi, nstripes); + + return depthDown; +} + +struct ComputePointsNormalsInvoker : ParallelLoopBody +{ + ComputePointsNormalsInvoker(const Depth& _depth, Points& _points, Normals& _normals, + const Intr::Reprojector& _reproj, float _dfac) : + ParallelLoopBody(), + depth(_depth), + points(_points), + normals(_normals), + reproj(_reproj), + dfac(_dfac) + { } + + virtual void operator ()(const Range& range) const override + { + for(int y = range.start; y < range.end; y++) + { + const depthType* depthRow0 = depth[y]; + const depthType* depthRow1 = (y < depth.rows - 1) ? depth[y + 1] : 0; + ptype *ptsRow = points[y]; + ptype *normRow = normals[y]; + + for(int x = 0; x < depth.cols; x++) + { + depthType d00 = depthRow0[x]; + depthType z00 = d00*dfac; + Point3f v00 = reproj(Point3f((float)x, (float)y, z00)); + + Point3f p = nan3, n = nan3; + + if(x < depth.cols - 1 && y < depth.rows - 1) + { + depthType d01 = depthRow0[x+1]; + depthType d10 = depthRow1[x]; + + depthType z01 = d01*dfac; + depthType z10 = d10*dfac; + + // before it was + //if(z00*z01*z10 != 0) + if(z00 != 0 && z01 != 0 && z10 != 0) + { + Point3f v01 = reproj(Point3f((float)(x+1), (float)(y+0), z01)); + Point3f v10 = reproj(Point3f((float)(x+0), (float)(y+1), z10)); + + cv::Vec3f vec = (v01-v00).cross(v10-v00); + n = -normalize(vec); + p = v00; + } + } + + ptsRow[x] = toPtype(p); + normRow[x] = toPtype(n); + } + } + } + + const Depth& depth; + Points& points; + Normals& normals; + const Intr::Reprojector& reproj; + float dfac; +}; + +void computePointsNormals(const Intr intr, float depthFactor, const Depth depth, + Points points, Normals normals) +{ + CV_Assert(!points.empty() && !normals.empty()); + CV_Assert(depth.size() == points.size()); + CV_Assert(depth.size() == normals.size()); + + // conversion to meters + // before it was: + //float dfac = 0.001f/depthFactor; + float dfac = 1.f/depthFactor; + + Intr::Reprojector reproj = intr.makeReprojector(); + + ComputePointsNormalsInvoker ci(depth, points, normals, reproj, dfac); + Range range(0, depth.rows); + const int nstripes = -1; + parallel_for_(range, ci, nstripes); +} + +///////// GPU implementation ///////// + +struct FrameGeneratorGPU : FrameGenerator +{ +public: + virtual cv::Ptr operator ()() const override; + virtual void operator() (Ptr frame, InputArray depth, const kinfu::Intr, int levels, float depthFactor, + float sigmaDepth, float sigmaSpatial, int kernelSize) const override; + virtual void operator() (Ptr frame, InputArray points, InputArray normals, int levels) const override; + + virtual ~FrameGeneratorGPU() {} +}; + +cv::Ptr FrameGeneratorGPU::operator ()() const +{ + return makePtr(); +} + +void FrameGeneratorGPU::operator ()(Ptr /*frame*/, InputArray /*depth*/, const Intr /*intr*/, int /*levels*/, float /*depthFactor*/, + float /*sigmaDepth*/, float /*sigmaSpatial*/, int /*kernelSize*/) const +{ + throw std::runtime_error("Not implemented"); +} + +void FrameGeneratorGPU::operator ()(Ptr /*frame*/, InputArray /*_points*/, InputArray /*_normals*/, int /*levels*/) const +{ + throw std::runtime_error("Not implemented"); +} + +void FrameGPU::render(OutputArray /* image */, int /*level*/, Affine3f /*lightPose*/) const +{ + throw std::runtime_error("Not implemented"); +} + +void FrameGPU::getDepth(OutputArray /* depth */) const +{ + throw std::runtime_error("Not implemented"); +} + +cv::Ptr makeFrameGenerator(cv::kinfu::KinFu::Params::PlatformType t) +{ + switch (t) + { + case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_CPU: + return cv::makePtr(); + case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_GPU: + return cv::makePtr(); + default: + return cv::Ptr(); + } +} + +} // namespace kinfu +} // namespace cv diff --git a/modules/rgbd/src/kinfu_frame.hpp b/modules/rgbd/src/kinfu_frame.hpp new file mode 100644 index 000000000..572bf5098 --- /dev/null +++ b/modules/rgbd/src/kinfu_frame.hpp @@ -0,0 +1,122 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#ifndef __OPENCV_KINFU_FRAME_H__ +#define __OPENCV_KINFU_FRAME_H__ + +#include "precomp.hpp" +#include "utils.hpp" + +namespace cv { + +template<> class DataType +{ +public: + typedef float value_type; + typedef value_type work_type; + typedef value_type channel_type; + typedef value_type vec_type; + enum { generic_type = 0, + depth = CV_32F, + channels = 3, + fmt = (int)'f', + type = CV_MAKETYPE(depth, channels) + }; +}; + +template<> class DataType +{ +public: + typedef float value_type; + typedef value_type work_type; + typedef value_type channel_type; + typedef value_type vec_type; + enum { generic_type = 0, + depth = CV_32F, + channels = 3, + fmt = (int)'f', + type = CV_MAKETYPE(depth, channels) + }; +}; + +template<> class DataType +{ +public: + typedef float value_type; + typedef value_type work_type; + typedef value_type channel_type; + typedef value_type vec_type; + enum { generic_type = 0, + depth = CV_32F, + channels = 4, + fmt = (int)'f', + type = CV_MAKETYPE(depth, channels) + }; +}; + +namespace kinfu { + +typedef cv::Vec4f ptype; +inline cv::Vec3f fromPtype(const ptype& x) +{ + return cv::Vec3f(x[0], x[1], x[2]); +} + +inline ptype toPtype(const cv::Vec3f& x) +{ + return ptype(x[0], x[1], x[2], 0); +} + +typedef cv::Mat_< ptype > Points; +typedef Points Normals; + +typedef cv::Mat_< depthType > Depth; + +struct Frame +{ +public: + virtual void render(cv::OutputArray image, int level, cv::Affine3f lightPose) const = 0; + virtual void getDepth(cv::OutputArray depth) const = 0; + virtual ~Frame() { } +}; + +struct FrameCPU : Frame +{ +public: + FrameCPU() : points(), normals() { } + virtual ~FrameCPU() { } + + virtual void render(cv::OutputArray image, int level, cv::Affine3f lightPose) const override; + virtual void getDepth(cv::OutputArray depth) const override; + + std::vector points; + std::vector normals; + Depth depthData; +}; + +struct FrameGPU : Frame +{ +public: + virtual void render(cv::OutputArray image, int level, cv::Affine3f lightPose) const override; + virtual void getDepth(cv::OutputArray depth) const override; + virtual ~FrameGPU() { } +}; + +struct FrameGenerator +{ +public: + virtual cv::Ptr operator ()() const = 0; + virtual void operator() (cv::Ptr frame, cv::InputArray depth, const cv::kinfu::Intr, int levels, float depthFactor, + float sigmaDepth, float sigmaSpatial, int kernelSize) const = 0; + virtual void operator() (cv::Ptr frame, cv::InputArray points, cv::InputArray normals, int levels) const = 0; + virtual ~FrameGenerator() {} +}; + +cv::Ptr makeFrameGenerator(cv::kinfu::KinFu::Params::PlatformType t); + +} // namespace kinfu +} // namespace cv +#endif diff --git a/modules/rgbd/src/linemod.cpp b/modules/rgbd/src/linemod.cpp index 509741c7a..43147d6ca 100644 --- a/modules/rgbd/src/linemod.cpp +++ b/modules/rgbd/src/linemod.cpp @@ -1,44 +1,8 @@ -/*M/////////////////////////////////////////////////////////////////////////////////////// -// -// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. -// -// By downloading, copying, installing or using the software you agree to this license. -// If you do not agree to this license, do not download, install, -// copy or use the software. -// -// -// License Agreement -// For Open Source Computer Vision Library -// -// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. -// Copyright (C) 2009, Willow Garage Inc., all rights reserved. -// Third party copyrights are property of their respective owners. -// -// Redistribution and use in source and binary forms, with or without modification, -// are permitted provided that the following conditions are met: -// -// * Redistribution's of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// * Redistribution's in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// * The name of the copyright holders may not be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// This software is provided by the copyright holders and contributors "as is" and -// any express or implied warranties, including, but not limited to, the implied -// warranties of merchantability and fitness for a particular purpose are disclaimed. -// In no event shall the Intel Corporation or contributors be liable for any direct, -// indirect, incidental, special, exemplary, or consequential damages -// (including, but not limited to, procurement of substitute goods or services; -// loss of use, data, or profits; or business interruption) however caused -// and on any theory of liability, whether in contract, strict liability, -// or tort (including negligence or otherwise) arising in any way out of -// the use of this software, even if advised of the possibility of such damage. -// -//M*/ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include "precomp.hpp" diff --git a/modules/rgbd/src/normal.cpp b/modules/rgbd/src/normal.cpp index 906c22d12..3eec7e269 100644 --- a/modules/rgbd/src/normal.cpp +++ b/modules/rgbd/src/normal.cpp @@ -1,37 +1,8 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include "precomp.hpp" @@ -283,10 +254,13 @@ namespace rgbd Vec3T *row_B = B[0]; for (; row_r != row_r_end; ++row_r, ++row_B, ++row_V) { - if (cvIsNaN(*row_r)) - *row_B = Vec3T(); - else - *row_B = (*row_V) / (*row_r); + Vec3T val = (*row_V) / (*row_r); + if(cvIsInf(val[0]) || cvIsNaN(val[0]) || + cvIsInf(val[1]) || cvIsNaN(val[1]) || + cvIsInf(val[2]) || cvIsNaN(val[2])) + *row_B = Vec3T(); + else + *row_B = val; } // Apply a box filter to B diff --git a/modules/rgbd/src/normal_lut.i b/modules/rgbd/src/normal_lut.i index e6cba6fc9..7e51fad0b 100644 --- a/modules/rgbd/src/normal_lut.i +++ b/modules/rgbd/src/normal_lut.i @@ -1,4 +1,404 @@ // Auto-generated by scripts/create_depth_normal_lut.py 20 static const int GRANULARITY = 20; -static const unsigned char NORMAL_LUT[20][20][20] = {{{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}}; +static const unsigned char NORMAL_LUT[20][20][20] = +{{{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}, + {{32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128}, + {16, 32, 32, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 128, 128}, + {16, 16, 16, 32, 32, 32, 32, 32, 32, 64, 64, 64, 128, 128, 128, 128, 128, 128, 1, 1}, + {16, 16, 16, 16, 16, 16, 32, 32, 32, 32, 64, 128, 128, 128, 128, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 32, 32, 64, 128, 128, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 16, 16, 8, 8, 4, 2, 2, 1, 1, 1, 1, 1, 1, 1}, + {16, 16, 16, 16, 16, 16, 8, 8, 8, 8, 4, 2, 2, 2, 2, 1, 1, 1, 1, 1}, + {16, 16, 16, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 1, 1}, + {16, 8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}, + {8, 8, 8, 8, 8, 8, 8, 4, 4, 4, 4, 4, 4, 4, 2, 2, 2, 2, 2, 2}}}; diff --git a/modules/rgbd/src/odometry.cpp b/modules/rgbd/src/odometry.cpp index f26ca5d8d..9270873bd 100755 --- a/modules/rgbd/src/odometry.cpp +++ b/modules/rgbd/src/odometry.cpp @@ -1,39 +1,13 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include "precomp.hpp" +#include "fast_icp.hpp" #if defined(HAVE_EIGEN) && EIGEN_WORLD_VERSION == 3 #define HAVE_EIGEN3_HERE @@ -1095,6 +1069,8 @@ Ptr Odometry::create(const String & odometryType) return makePtr(); else if (odometryType == "RgbdICPOdometry") return makePtr(); + else if (odometryType == "FastICPOdometry") + return makePtr(); return Ptr(); } @@ -1441,6 +1417,130 @@ bool RgbdICPOdometry::computeImpl(const Ptr& srcFrame, const Ptr< // +using namespace cv::kinfu; + +FastICPOdometry::FastICPOdometry() : + maxDistDiff(DEFAULT_MAX_DEPTH_DIFF()), + angleThreshold((float)(30. * CV_PI / 180.)), + sigmaDepth(0.04f), + sigmaSpatial(4.5f), + kernelSize(7) +{ + setDefaultIterCounts(iterCounts); +} + +FastICPOdometry::FastICPOdometry(const Mat& _cameraMatrix, + float _maxDistDiff, + float _angleThreshold, + float _sigmaDepth, + float _sigmaSpatial, + int _kernelSize, + const std::vector& _iterCounts) : + maxDistDiff(_maxDistDiff), + angleThreshold(_angleThreshold), + sigmaDepth(_sigmaDepth), + sigmaSpatial(_sigmaSpatial), + kernelSize(_kernelSize), + iterCounts(Mat(_iterCounts).clone()), + cameraMatrix(_cameraMatrix) +{ + if(iterCounts.empty()) + setDefaultIterCounts(iterCounts); +} + +Ptr FastICPOdometry::create(const Mat& _cameraMatrix, + float _maxDistDiff, + float _angleThreshold, + float _sigmaDepth, + float _sigmaSpatial, + int _kernelSize, + const std::vector& _iterCounts) +{ + return makePtr(_cameraMatrix, _maxDistDiff, _angleThreshold, + _sigmaDepth, _sigmaSpatial, _kernelSize, _iterCounts); +} + +Size FastICPOdometry::prepareFrameCache(Ptr& frame, int cacheType) const +{ + Odometry::prepareFrameCache(frame, cacheType); + + if(frame->depth.empty()) + { + if(!frame->pyramidDepth.empty()) + frame->depth = frame->pyramidDepth[0]; + else if(!frame->pyramidCloud.empty()) + { + Mat cloud = frame->pyramidCloud[0]; + std::vector xyz; + split(cloud, xyz); + frame->depth = xyz[2]; + } + else + CV_Error(Error::StsBadSize, "Depth or pyramidDepth or pyramidCloud have to be set."); + } + checkDepth(frame->depth, frame->depth.size()); + + // mask isn't used by FastICP + + Ptr fg = makeFrameGenerator(KinFu::Params::PlatformType::PLATFORM_CPU); + Ptr f = (*fg)().dynamicCast(); + Intr intr(cameraMatrix); + float depthFactor = 1.f; // user should rescale depth manually + (*fg)(f, frame->depth, intr, (int)iterCounts.total(), depthFactor, + sigmaDepth, sigmaSpatial, kernelSize); + + frame->pyramidCloud.clear(); + frame->pyramidNormals.clear(); + for(size_t i = 0; i < f->points.size(); i++) + { + frame->pyramidCloud.push_back(f->points[i]); + frame->pyramidNormals.push_back(f->normals[i]); + } + + return frame->depth.size(); +} + +void FastICPOdometry::checkParams() const +{ + CV_Assert(cameraMatrix.size() == Size(3,3) && + (cameraMatrix.type() == CV_32FC1 || + cameraMatrix.type() == CV_64FC1)); + + CV_Assert(maxDistDiff > 0); + CV_Assert(angleThreshold > 0); + CV_Assert(sigmaDepth > 0 && sigmaSpatial > 0 && kernelSize > 0); +} + +bool FastICPOdometry::computeImpl(const Ptr& srcFrame, + const Ptr& dstFrame, + OutputArray Rt, const Mat& /*initRt*/) const +{ + kinfu::Intr intr(cameraMatrix); + std::vector iterations = iterCounts; + Ptr icp = kinfu::makeICP(kinfu::KinFu::Params::PlatformType::PLATFORM_CPU, + intr, + iterations, + angleThreshold, + maxDistDiff); + + Affine3f transform; + Ptr srcF = makePtr(), dstF = makePtr(); + for(size_t i = 0; i < srcFrame->pyramidCloud.size(); i++) + { + srcF-> points.push_back(srcFrame->pyramidCloud [i]); + srcF->normals.push_back(srcFrame->pyramidNormals[i]); + dstF-> points.push_back(dstFrame->pyramidCloud [i]); + dstF->normals.push_back(dstFrame->pyramidNormals[i]); + } + bool result = icp->estimateTransform(transform, dstF, srcF); + + Rt.create(Size(4, 4), CV_64FC1); + Mat(Matx44d(transform.matrix)).copyTo(Rt.getMat()); + return result; +} + +// + void warpFrame(const Mat& image, const Mat& depth, const Mat& mask, const Mat& Rt, const Mat& cameraMatrix, const Mat& distCoeff, @@ -1453,5 +1553,5 @@ warpFrame(const Mat& image, const Mat& depth, const Mat& mask, else CV_Error(Error::StsBadArg, "Image has to be type of CV_8UC1 or CV_8UC3"); } -} +} // namespace rgbd } // namespace cv diff --git a/modules/rgbd/src/plane.cpp b/modules/rgbd/src/plane.cpp index 859d044f3..4156422b7 100644 --- a/modules/rgbd/src/plane.cpp +++ b/modules/rgbd/src/plane.cpp @@ -1,37 +1,8 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory /** This is an implementation of a fast plane detection loosely inspired by * Fast Plane Detection and Polygonalization in noisy 3D Range Images diff --git a/modules/rgbd/src/precomp.hpp b/modules/rgbd/src/precomp.hpp index 5bcf8895c..a94627e6c 100644 --- a/modules/rgbd/src/precomp.hpp +++ b/modules/rgbd/src/precomp.hpp @@ -1,53 +1,21 @@ -/*M/////////////////////////////////////////////////////////////////////////////////////// -// -// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. -// -// By downloading, copying, installing or using the software you agree to this license. -// If you do not agree to this license, do not download, install, -// copy or use the software. -// -// -// License Agreement -// For Open Source Computer Vision Library -// -// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. -// Copyright (C) 2009, Willow Garage Inc., all rights reserved. -// Third party copyrights are property of their respective owners. -// -// Redistribution and use in source and binary forms, with or without modification, -// are permitted provided that the following conditions are met: -// -// * Redistribution's of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// * Redistribution's in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// * The name of the copyright holders may not be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// This software is provided by the copyright holders and contributors "as is" and -// any express or implied warranties, including, but not limited to, the implied -// warranties of merchantability and fitness for a particular purpose are disclaimed. -// In no event shall the Intel Corporation or contributors be liable for any direct, -// indirect, incidental, special, exemplary, or consequential damages -// (including, but not limited to, procurement of substitute goods or services; -// loss of use, data, or profits; or business interruption) however caused -// and on any theory of liability, whether in contract, strict liability, -// or tort (including negligence or otherwise) arising in any way out of -// the use of this software, even if advised of the possibility of such damage. -// -//M*/ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + #ifndef __OPENCV_PRECOMP_H__ #define __OPENCV_PRECOMP_H__ -#include "opencv2/rgbd.hpp" -#include "opencv2/calib3d.hpp" -#include "opencv2/imgproc.hpp" #include "opencv2/core/utility.hpp" #include "opencv2/core/private.hpp" +#include "opencv2/core/hal/intrin.hpp" +#include "opencv2/imgproc.hpp" +#include "opencv2/calib3d.hpp" +#include "opencv2/rgbd.hpp" #include #include #include diff --git a/modules/rgbd/src/tsdf.cpp b/modules/rgbd/src/tsdf.cpp new file mode 100644 index 000000000..ca3eaae62 --- /dev/null +++ b/modules/rgbd/src/tsdf.cpp @@ -0,0 +1,1218 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#include "precomp.hpp" +#include "tsdf.hpp" + +namespace cv { + +namespace kinfu { + +typedef float volumeType; // can be float16 +struct Voxel +{ + volumeType v; + int weight; +}; + +} + +template<> class DataType +{ +public: + typedef kinfu::Voxel value_type; + typedef value_type work_type; + typedef value_type channel_type; + typedef value_type vec_type; + enum { generic_type = 0, + depth = CV_64F, + channels = 1, + fmt = (int)'v', + type = CV_MAKETYPE(depth, channels) + }; +}; + +namespace kinfu { + + +class TSDFVolumeCPU : public TSDFVolume +{ + typedef cv::Mat_ Volume; + +public: + // dimension in voxels, size in meters + TSDFVolumeCPU(int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, + float _raycastStepFactor); + + virtual void integrate(cv::Ptr depth, float depthFactor, cv::Affine3f cameraPose, cv::kinfu::Intr intrinsics) override; + virtual void raycast(cv::Affine3f cameraPose, cv::kinfu::Intr intrinsics, cv::Size frameSize, int pyramidLevels, + cv::Ptr frameGenerator, cv::Ptr frame) const override; + + virtual void fetchNormals(cv::InputArray points, cv::OutputArray _normals) const override; + virtual void fetchPointsNormals(cv::OutputArray points, cv::OutputArray normals) const override; + + virtual void reset() override; + + volumeType interpolateVoxel(cv::Point3f p) const; + Point3f getNormalVoxel(cv::Point3f p) const; + +#if CV_SIMD128 + volumeType interpolateVoxel(const v_float32x4& p) const; + v_float32x4 getNormalVoxel(const v_float32x4& p) const; +#endif + + // edgeResolution^3 array + // &elem(x, y, z) = data + x*edgeRes^2 + y*edgeRes + z; + Volume volume; + + int neighbourCoords[8]; + int dims[4]; + float voxelSize; + float voxelSizeInv; + float truncDist; + float raycastStepFactor; +}; + + +TSDFVolume::TSDFVolume(int _res, float _size, Affine3f _pose, float /*_truncDist*/, int _maxWeight, + float /*_raycastStepFactor*/) : + edgeSize(_size), + edgeResolution(_res), + maxWeight(_maxWeight), + pose(_pose) +{ } + +// dimension in voxels, size in meters +TSDFVolumeCPU::TSDFVolumeCPU(int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, + float _raycastStepFactor) : + TSDFVolume(_res, _size, _pose, _truncDist, _maxWeight, _raycastStepFactor) +{ + CV_Assert(_res % 32 == 0); + + int xdim = edgeResolution*edgeResolution; + int ydim = edgeResolution; + int steps[4] = { xdim, ydim, 1, 0 }; + for(int i = 0; i < 4; i++) + dims[i] = steps[i]; + int coords[8] = { + xdim*0 + ydim*0 + 1*0, + xdim*0 + ydim*0 + 1*1, + xdim*0 + ydim*1 + 1*0, + xdim*0 + ydim*1 + 1*1, + xdim*1 + ydim*0 + 1*0, + xdim*1 + ydim*0 + 1*1, + xdim*1 + ydim*1 + 1*0, + xdim*1 + ydim*1 + 1*1 + }; + for(int i = 0; i < 8; i++) + neighbourCoords[i] = coords[i]; + + voxelSize = edgeSize/edgeResolution; + voxelSizeInv = edgeResolution/edgeSize; + volume = Volume(1, _res * _res * _res); + + truncDist = std::max (_truncDist, 2.1f * voxelSize); + raycastStepFactor = _raycastStepFactor; + + reset(); +} + +struct FillZero +{ + void operator ()(Voxel &v, const int* /*position*/) const + { + v.v = 0; v.weight = 0; + } +}; + +// zero volume, leave rest params the same +void TSDFVolumeCPU::reset() +{ + ScopeTime st("tsdf: reset"); + + volume.forEach(FillZero()); +} + +// SIMD version of that code is manually inlined +#if !CV_SIMD128 +static const bool fixMissingData = false; + +static inline depthType bilinearDepth(const Depth& m, cv::Point2f pt) +{ + const depthType defaultValue = qnan; + if(pt.x < 0 || pt.x >= m.cols-1 || + pt.y < 0 || pt.y >= m.rows-1) + return defaultValue; + + int xi = cvFloor(pt.x), yi = cvFloor(pt.y); + + const depthType* row0 = m[yi+0]; + const depthType* row1 = m[yi+1]; + + depthType v00 = row0[xi+0]; + depthType v01 = row0[xi+1]; + depthType v10 = row1[xi+0]; + depthType v11 = row1[xi+1]; + + // assume correct depth is positive + bool b00 = v00 > 0; + bool b01 = v01 > 0; + bool b10 = v10 > 0; + bool b11 = v11 > 0; + + if(!fixMissingData) + { + if(!(b00 && b01 && b10 && b11)) + return defaultValue; + else + { + float tx = pt.x - xi, ty = pt.y - yi; + depthType v0 = v00 + tx*(v01 - v00); + depthType v1 = v10 + tx*(v11 - v10); + return v0 + ty*(v1 - v0); + } + } + else + { + int nz = b00 + b01 + b10 + b11; + if(nz == 0) + { + return defaultValue; + } + if(nz == 1) + { + if(b00) return v00; + if(b01) return v01; + if(b10) return v10; + if(b11) return v11; + } + else if(nz == 2) + { + if(b00 && b10) v01 = v00, v11 = v10; + if(b01 && b11) v00 = v01, v10 = v11; + if(b00 && b01) v10 = v00, v11 = v01; + if(b10 && b11) v00 = v10, v01 = v11; + if(b00 && b11) v01 = v10 = (v00 + v11)*0.5f; + if(b01 && b10) v00 = v11 = (v01 + v10)*0.5f; + } + else if(nz == 3) + { + if(!b00) v00 = v10 + v01 - v11; + if(!b01) v01 = v00 + v11 - v10; + if(!b10) v10 = v00 + v11 - v01; + if(!b11) v11 = v01 + v10 - v00; + } + + float tx = pt.x - xi, ty = pt.y - yi; + depthType v0 = v00 + tx*(v01 - v00); + depthType v1 = v10 + tx*(v11 - v10); + return v0 + ty*(v1 - v0); + } +} +#endif + +struct IntegrateInvoker : ParallelLoopBody +{ + IntegrateInvoker(TSDFVolumeCPU& _volume, const Depth& _depth, Intr intrinsics, cv::Affine3f cameraPose, + float depthFactor) : + ParallelLoopBody(), + volume(_volume), + depth(_depth), + proj(intrinsics.makeProjector()), + vol2cam(cameraPose.inv() * volume.pose), + truncDistInv(1.f/volume.truncDist), + dfac(1.f/depthFactor) + { + volDataStart = volume.volume[0]; + } + +#if CV_SIMD128 + virtual void operator() (const Range& range) const override + { + // zStep == vol2cam*(Point3f(x, y, 1)*voxelSize) - basePt; + Point3f zStepPt = Point3f(vol2cam.matrix(0, 2), vol2cam.matrix(1, 2), vol2cam.matrix(2, 2))*volume.voxelSize; + v_float32x4 zStep(zStepPt.x, zStepPt.y, zStepPt.z, 0); + v_float32x4 vfxy(proj.fx, proj.fy, 0.f, 0.f), vcxy(proj.cx, proj.cy, 0.f, 0.f); + const v_float32x4 upLimits = v_cvt_f32(v_int32x4(depth.cols-1, depth.rows-1, 0, 0)); + + // &elem(x, y, z) = data + x*edgeRes^2 + y*edgeRes + z; + for(int x = range.start; x < range.end; x++) + { + Voxel* volDataX = volDataStart + x*volume.dims[0]; + for(int y = 0; y < volume.edgeResolution; y++) + { + Voxel* volDataY = volDataX+y*volume.dims[1]; + // optimization of camSpace transformation (vector addition instead of matmul at each z) + Point3f basePt = vol2cam*Point3f(x*volume.voxelSize, y*volume.voxelSize, 0); + v_float32x4 camSpacePt(basePt.x, basePt.y, basePt.z, 0); + + int startZ, endZ; + if(abs(zStepPt.z) > 1e-5) + { + int baseZ = (int)(-basePt.z / zStepPt.z); + if(zStepPt.z > 0) + { + startZ = baseZ; + endZ = volume.edgeResolution; + } + else + { + startZ = 0; + endZ = baseZ; + } + } + else + { + if(basePt.z > 0) + { + startZ = 0; endZ = volume.edgeResolution; + } + else + { + // z loop shouldn't be performed + startZ = endZ = 0; + } + } + startZ = max(0, startZ); + endZ = min(volume.edgeResolution, endZ); + for(int z = startZ; z < endZ; z++) + { + // optimization of the following: + //Point3f volPt = Point3f(x, y, z)*voxelSize; + //Point3f camSpacePt = vol2cam * volPt; + camSpacePt += zStep; + + float zCamSpace = v_reinterpret_as_f32(v_rotate_right<2>(v_reinterpret_as_u32(camSpacePt))).get0(); + + if(zCamSpace <= 0.f) + continue; + + v_float32x4 camPixVec = camSpacePt/v_setall_f32(zCamSpace); + v_float32x4 projected = v_muladd(camPixVec, vfxy, vcxy); + // leave only first 2 lanes + projected = v_reinterpret_as_f32(v_reinterpret_as_u32(projected) & + v_uint32x4(0xFFFFFFFF, 0xFFFFFFFF, 0, 0)); + + depthType v; + // bilinearly interpolate depth at projected + { + const v_float32x4& pt = projected; + // check coords >= 0 and < imgSize + v_uint32x4 limits = v_reinterpret_as_u32(pt < v_setzero_f32()) | + v_reinterpret_as_u32(pt >= upLimits); + limits = limits | v_rotate_right<1>(limits); + if(limits.get0()) + continue; + + // xi, yi = floor(pt) + v_int32x4 ip = v_floor(pt); + v_int32x4 ipshift = ip; + int xi = ipshift.get0(); + ipshift = v_rotate_right<1>(ipshift); + int yi = ipshift.get0(); + + const depthType* row0 = depth[yi+0]; + const depthType* row1 = depth[yi+1]; + + // v001 = [v(xi + 0, yi + 0), v(xi + 1, yi + 0)] + v_float32x4 v001 = v_load_low(row0 + xi); + // v101 = [v(xi + 0, yi + 1), v(xi + 1, yi + 1)] + v_float32x4 v101 = v_load_low(row1 + xi); + + v_float32x4 vall = v_combine_low(v001, v101); + + // assume correct depth is positive + // don't fix missing data + if(v_check_all(vall > v_setzero_f32())) + { + v_float32x4 t = pt - v_cvt_f32(ip); + float tx = t.get0(); + t = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(t))); + v_float32x4 ty = v_setall_f32(t.get0()); + // vx is y-interpolated between rows 0 and 1 + v_float32x4 vx = v001 + ty*(v101 - v001); + float v0 = vx.get0(); + vx = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(vx))); + float v1 = vx.get0(); + v = v0 + tx*(v1 - v0); + } + else + continue; + } + + // norm(camPixVec) produces double which is too slow + float pixNorm = sqrt(v_reduce_sum(camPixVec*camPixVec)); + // difference between distances of point and of surface to camera + volumeType sdf = pixNorm*(v*dfac - zCamSpace); + // possible alternative is: + // kftype sdf = norm(camSpacePt)*(v*dfac/camSpacePt.z - 1); + + if(sdf >= -volume.truncDist) + { + volumeType tsdf = fmin(1.f, sdf * truncDistInv); + + Voxel& voxel = volDataY[z]; + int& weight = voxel.weight; + volumeType& value = voxel.v; + + // update TSDF + value = (value*weight+tsdf) / (weight + 1); + weight = min(weight + 1, volume.maxWeight); + } + } + } + } + } +#else + virtual void operator() (const Range& range) const + { + // &elem(x, y, z) = data + x*edgeRes^2 + y*edgeRes + z; + for(int x = range.start; x < range.end; x++) + { + Voxel* volDataX = volDataStart + x*volume.dims[0]; + for(int y = 0; y < volume.edgeResolution; y++) + { + Voxel* volDataY = volDataX+y*volume.dims[1]; + // optimization of camSpace transformation (vector addition instead of matmul at each z) + Point3f basePt = vol2cam*Point3f(x*volume.voxelSize, y*volume.voxelSize, 0); + Point3f camSpacePt = basePt; + // zStep == vol2cam*(Point3f(x, y, 1)*voxelSize) - basePt; + Point3f zStep = Point3f(vol2cam.matrix(0, 2), vol2cam.matrix(1, 2), vol2cam.matrix(2, 2))*volume.voxelSize; + + int startZ, endZ; + if(abs(zStep.z) > 1e-5) + { + int baseZ = -basePt.z / zStep.z; + if(zStep.z > 0) + { + startZ = baseZ; + endZ = volume.edgeResolution; + } + else + { + startZ = 0; + endZ = baseZ; + } + } + else + { + if(basePt.z > 0) + { + startZ = 0; endZ = volume.edgeResolution; + } + else + { + // z loop shouldn't be performed + startZ = endZ = 0; + } + } + startZ = max(0, startZ); + endZ = min(volume.edgeResolution, endZ); + for(int z = startZ; z < endZ; z++) + { + // optimization of the following: + //Point3f volPt = Point3f(x, y, z)*volume.voxelSize; + //Point3f camSpacePt = vol2cam * volPt; + camSpacePt += zStep; + + if(camSpacePt.z <= 0) + continue; + + Point3f camPixVec; + Point2f projected = proj(camSpacePt, camPixVec); + + depthType v = bilinearDepth(depth, projected); + if(v == 0) + continue; + + // norm(camPixVec) produces double which is too slow + float pixNorm = sqrt(camPixVec.dot(camPixVec)); + // difference between distances of point and of surface to camera + volumeType sdf = pixNorm*(v*dfac - camSpacePt.z); + // possible alternative is: + // kftype sdf = norm(camSpacePt)*(v*dfac/camSpacePt.z - 1); + + if(sdf >= -volume.truncDist) + { + volumeType tsdf = fmin(1.f, sdf * truncDistInv); + + Voxel& voxel = volDataY[z]; + int& weight = voxel.weight; + volumeType& value = voxel.v; + + // update TSDF + value = (value*weight+tsdf) / (weight + 1); + weight = min(weight + 1, volume.maxWeight); + } + } + } + } + } +#endif + + TSDFVolumeCPU& volume; + const Depth& depth; + const Intr::Projector proj; + const cv::Affine3f vol2cam; + const float truncDistInv; + const float dfac; + Voxel* volDataStart; +}; + +// use depth instead of distance (optimization) +void TSDFVolumeCPU::integrate(cv::Ptr _depth, float depthFactor, cv::Affine3f cameraPose, Intr intrinsics) +{ + ScopeTime st("tsdf: integrate"); + + Depth depth; + _depth->getDepth(depth); + + IntegrateInvoker ii(*this, depth, intrinsics, cameraPose, depthFactor); + Range range(0, edgeResolution); + parallel_for_(range, ii); +} + +#if CV_SIMD128 +// all coordinate checks should be done in inclosing cycle +inline volumeType TSDFVolumeCPU::interpolateVoxel(Point3f _p) const +{ + v_float32x4 p(_p.x, _p.y, _p.z, 0); + return interpolateVoxel(p); +} + +inline volumeType TSDFVolumeCPU::interpolateVoxel(const v_float32x4& p) const +{ + // tx, ty, tz = floor(p) + v_int32x4 ip = v_floor(p); + v_float32x4 t = p - v_cvt_f32(ip); + float tx = t.get0(); + t = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(t))); + float ty = t.get0(); + t = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(t))); + float tz = t.get0(); + + int xdim = dims[0], ydim = dims[1]; + const Voxel* volData = volume[0]; + + int ix = ip.get0(); ip = v_rotate_right<1>(ip); + int iy = ip.get0(); ip = v_rotate_right<1>(ip); + int iz = ip.get0(); + + int coordBase = ix*xdim + iy*ydim + iz; + + volumeType vx[8]; + for(int i = 0; i < 8; i++) + vx[i] = volData[neighbourCoords[i] + coordBase].v; + + v_float32x4 v0246(vx[0], vx[2], vx[4], vx[6]), v1357(vx[1], vx[3], vx[5], vx[7]); + v_float32x4 vxx = v0246 + v_setall_f32(tz)*(v1357 - v0246); + + v_float32x4 v00_10 = vxx; + v_float32x4 v01_11 = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(vxx))); + + v_float32x4 v0_1 = v00_10 + v_setall_f32(ty)*(v01_11 - v00_10); + float v0 = v0_1.get0(); + v0_1 = v_reinterpret_as_f32(v_rotate_right<2>(v_reinterpret_as_u32(v0_1))); + float v1 = v0_1.get0(); + + return v0 + tx*(v1 - v0); +} +#else +inline volumeType TSDFVolumeCPU::interpolateVoxel(Point3f p) const +{ + int xdim = dims[0], ydim = dims[1]; + + int ix = cvFloor(p.x); + int iy = cvFloor(p.y); + int iz = cvFloor(p.z); + + float tx = p.x - ix; + float ty = p.y - iy; + float tz = p.z - iz; + + int coordBase = ix*xdim + iy*ydim + iz; + const Voxel* volData = volume[0]; + + volumeType vx[8]; + for(int i = 0; i < 8; i++) + vx[i] = volData[neighbourCoords[i] + coordBase].v; + + volumeType v00 = vx[0] + tz*(vx[1] - vx[0]); + volumeType v01 = vx[2] + tz*(vx[3] - vx[2]); + volumeType v10 = vx[4] + tz*(vx[5] - vx[4]); + volumeType v11 = vx[6] + tz*(vx[7] - vx[6]); + + volumeType v0 = v00 + ty*(v01 - v00); + volumeType v1 = v10 + ty*(v11 - v10); + + return v0 + tx*(v1 - v0); +} +#endif + + +#if CV_SIMD128 +//gradientDeltaFactor is fixed at 1.0 of voxel size +inline Point3f TSDFVolumeCPU::getNormalVoxel(Point3f _p) const +{ + v_float32x4 p(_p.x, _p.y, _p.z, 0.f); + v_float32x4 result = getNormalVoxel(p); + float CV_DECL_ALIGNED(16) ares[4]; + v_store_aligned(ares, result); + return Point3f(ares[0], ares[1], ares[2]); +} + +inline v_float32x4 TSDFVolumeCPU::getNormalVoxel(const v_float32x4& p) const +{ + if(v_check_any((p < v_float32x4(1.f, 1.f, 1.f, 0.f)) + + (p >= v_setall_f32((float)(edgeResolution-2))))) + return nanv; + + v_int32x4 ip = v_floor(p); + v_float32x4 t = p - v_cvt_f32(ip); + float tx = t.get0(); + t = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(t))); + float ty = t.get0(); + t = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(t))); + float tz = t.get0(); + + int xdim = dims[0], ydim = dims[1]; + const Voxel* volData = volume[0]; + + int ix = ip.get0(); ip = v_rotate_right<1>(ip); + int iy = ip.get0(); ip = v_rotate_right<1>(ip); + int iz = ip.get0(); + + int coordBase = ix*xdim + iy*ydim + iz; + + float CV_DECL_ALIGNED(16) an[4]; + an[0] = an[1] = an[2] = an[3] = 0.f; + for(int c = 0; c < 3; c++) + { + const int dim = dims[c]; + float& nv = an[c]; + + volumeType vx[8]; + for(int i = 0; i < 8; i++) + vx[i] = volData[neighbourCoords[i] + coordBase + 1*dim].v - + volData[neighbourCoords[i] + coordBase - 1*dim].v; + + v_float32x4 v0246(vx[0], vx[2], vx[4], vx[6]), v1357(vx[1], vx[3], vx[5], vx[7]); + v_float32x4 vxx = v0246 + v_setall_f32(tz)*(v1357 - v0246); + + v_float32x4 v00_10 = vxx; + v_float32x4 v01_11 = v_reinterpret_as_f32(v_rotate_right<1>(v_reinterpret_as_u32(vxx))); + + v_float32x4 v0_1 = v00_10 + v_setall_f32(ty)*(v01_11 - v00_10); + float v0 = v0_1.get0(); + v0_1 = v_reinterpret_as_f32(v_rotate_right<2>(v_reinterpret_as_u32(v0_1))); + float v1 = v0_1.get0(); + + nv = v0 + tx*(v1 - v0); + } + + v_float32x4 n = v_load_aligned(an); + v_float32x4 invNorm = v_invsqrt(v_setall_f32(v_reduce_sum(n*n))); + return n*invNorm; +} +#else +inline Point3f TSDFVolumeCPU::getNormalVoxel(Point3f p) const +{ + const int xdim = dims[0], ydim = dims[1]; + const Voxel* volData = volume[0]; + + if(p.x < 1 || p.x >= edgeResolution -2 || + p.y < 1 || p.y >= edgeResolution -2 || + p.z < 1 || p.z >= edgeResolution -2) + return nan3; + + int ix = cvFloor(p.x); + int iy = cvFloor(p.y); + int iz = cvFloor(p.z); + + float tx = p.x - ix; + float ty = p.y - iy; + float tz = p.z - iz; + + int coordBase = ix*xdim + iy*ydim + iz; + + Vec3f an; + for(int c = 0; c < 3; c++) + { + const int dim = dims[c]; + float& nv = an[c]; + + volumeType vx[8]; + for(int i = 0; i < 8; i++) + vx[i] = volData[neighbourCoords[i] + coordBase + 1*dim].v - + volData[neighbourCoords[i] + coordBase - 1*dim].v; + + volumeType v00 = vx[0] + tz*(vx[1] - vx[0]); + volumeType v01 = vx[2] + tz*(vx[3] - vx[2]); + volumeType v10 = vx[4] + tz*(vx[5] - vx[4]); + volumeType v11 = vx[6] + tz*(vx[7] - vx[6]); + + volumeType v0 = v00 + ty*(v01 - v00); + volumeType v1 = v10 + ty*(v11 - v10); + + nv = v0 + tx*(v1 - v0); + } + + return normalize(an); +} +#endif + + +struct RaycastInvoker : ParallelLoopBody +{ + RaycastInvoker(Points& _points, Normals& _normals, Affine3f cameraPose, + Intr intrinsics, const TSDFVolumeCPU& _volume) : + ParallelLoopBody(), + points(_points), + normals(_normals), + volume(_volume), + tstep(volume.truncDist * volume.raycastStepFactor), + // We do subtract voxel size to minimize checks after + // Note: origin of volume coordinate is placed + // in the center of voxel (0,0,0), not in the corner of the voxel! + boxMax(volume.edgeSize - volume.voxelSize, + volume.edgeSize - volume.voxelSize, + volume.edgeSize - volume.voxelSize), + boxMin(), + cam2vol(volume.pose.inv() * cameraPose), + vol2cam(cameraPose.inv() * volume.pose), + reproj(intrinsics.makeReprojector()) + { } + +#if CV_SIMD128 + virtual void operator() (const Range& range) const override + { + const v_float32x4 vfxy(reproj.fxinv, reproj.fyinv, 0, 0); + const v_float32x4 vcxy(reproj.cx, reproj.cy, 0, 0); + + const float (&cm)[16] = cam2vol.matrix.val; + const v_float32x4 camRot0(cm[0], cm[4], cm[ 8], 0); + const v_float32x4 camRot1(cm[1], cm[5], cm[ 9], 0); + const v_float32x4 camRot2(cm[2], cm[6], cm[10], 0); + const v_float32x4 camTrans(cm[3], cm[7], cm[11], 0); + + const v_float32x4 boxDown(boxMin.x, boxMin.y, boxMin.z, 0.f); + const v_float32x4 boxUp(boxMax.x, boxMax.y, boxMax.z, 0.f); + + const v_float32x4 invVoxelSize = v_setall_f32(volume.voxelSizeInv); + + const float (&vm)[16] = vol2cam.matrix.val; + const v_float32x4 volRot0(vm[0], vm[4], vm[ 8], 0); + const v_float32x4 volRot1(vm[1], vm[5], vm[ 9], 0); + const v_float32x4 volRot2(vm[2], vm[6], vm[10], 0); + const v_float32x4 volTrans(vm[3], vm[7], vm[11], 0); + + for(int y = range.start; y < range.end; y++) + { + ptype* ptsRow = points[y]; + ptype* nrmRow = normals[y]; + + for(int x = 0; x < points.cols; x++) + { + v_float32x4 point = nanv, normal = nanv; + + v_float32x4 orig = camTrans; + + // get direction through pixel in volume space: + + // 1. reproject (x, y) on projecting plane where z = 1.f + v_float32x4 planed = (v_float32x4((float)x, (float)y, 0.f, 0.f) - vcxy)*vfxy; + planed = v_combine_low(planed, v_float32x4(1.f, 0.f, 0.f, 0.f)); + + // 2. rotate to volume space + planed = v_matmuladd(planed, camRot0, camRot1, camRot2, v_setzero_f32()); + + // 3. normalize + v_float32x4 invNorm = v_invsqrt(v_setall_f32(v_reduce_sum(planed*planed))); + v_float32x4 dir = planed*invNorm; + + // compute intersection of ray with all six bbox planes + v_float32x4 rayinv = v_setall_f32(1.f)/dir; + // div by zero should be eliminated by these products + v_float32x4 tbottom = rayinv*(boxDown - orig); + v_float32x4 ttop = rayinv*(boxUp - orig); + + // re-order intersections to find smallest and largest on each axis + v_float32x4 minAx = v_min(ttop, tbottom); + v_float32x4 maxAx = v_max(ttop, tbottom); + + // near clipping plane + const float clip = 0.f; + float tmin = max(v_reduce_max(minAx), clip); + float tmax = v_reduce_min(maxAx); + + // precautions against getting coordinates out of bounds + tmin = tmin + tstep; + tmax = tmax - tstep; + + if(tmin < tmax) + { + // interpolation optimized a little + orig *= invVoxelSize; + dir *= invVoxelSize; + + int xdim = volume.dims[0], ydim = volume.dims[1]; + v_float32x4 rayStep = dir * v_setall_f32(tstep); + v_float32x4 next = (orig + dir * v_setall_f32(tmin)); + volumeType f = volume.interpolateVoxel(next), fnext = f; + + //raymarch + int steps = 0; + int nSteps = cvFloor((tmax - tmin)/tstep); + for(; steps < nSteps; steps++) + { + next += rayStep; + v_int32x4 ip = v_round(next); + int ix = ip.get0(); ip = v_rotate_right<1>(ip); + int iy = ip.get0(); ip = v_rotate_right<1>(ip); + int iz = ip.get0(); + int coord = ix*xdim + iy*ydim + iz; + + fnext = volume.volume(coord).v; + if(fnext != f) + { + fnext = volume.interpolateVoxel(next); + + // when ray crosses a surface + if(std::signbit(f) != std::signbit(fnext)) + break; + + f = fnext; + } + } + + // if ray penetrates a surface from outside + // linearly interpolate t between two f values + if(f > 0.f && fnext < 0.f) + { + v_float32x4 tp = next - rayStep; + volumeType ft = volume.interpolateVoxel(tp); + volumeType ftdt = volume.interpolateVoxel(next); + // float t = tmin + steps*tstep; + // float ts = t - tstep*ft/(ftdt - ft); + float ts = tmin + tstep*(steps - ft/(ftdt - ft)); + + // avoid division by zero + if(!cvIsNaN(ts) && !cvIsInf(ts)) + { + v_float32x4 pv = (orig + dir*v_setall_f32(ts)); + v_float32x4 nv = volume.getNormalVoxel(pv); + + if(!isNaN(nv)) + { + //convert pv and nv to camera space + normal = v_matmuladd(nv, volRot0, volRot1, volRot2, v_setzero_f32()); + // interpolation optimized a little + point = v_matmuladd(pv*v_setall_f32(volume.voxelSize), volRot0, volRot1, volRot2, volTrans); + } + } + } + } + + v_store((float*)(&ptsRow[x]), point); + v_store((float*)(&nrmRow[x]), normal); + } + } + } +#else + virtual void operator() (const Range& range) const + { + const Point3f camTrans = cam2vol.translation(); + const Matx33f camRot = cam2vol.rotation(); + const Matx33f volRot = vol2cam.rotation(); + + for(int y = range.start; y < range.end; y++) + { + ptype* ptsRow = points[y]; + ptype* nrmRow = normals[y]; + + for(int x = 0; x < points.cols; x++) + { + Point3f point = nan3, normal = nan3; + + Point3f orig = camTrans; + // direction through pixel in volume space + Point3f dir = normalize(Vec3f(camRot * reproj(Point3f(x, y, 1.f)))); + + // compute intersection of ray with all six bbox planes + Vec3f rayinv(1.f/dir.x, 1.f/dir.y, 1.f/dir.z); + Point3f tbottom = rayinv.mul(boxMin - orig); + Point3f ttop = rayinv.mul(boxMax - orig); + + // re-order intersections to find smallest and largest on each axis + Point3f minAx(min(ttop.x, tbottom.x), min(ttop.y, tbottom.y), min(ttop.z, tbottom.z)); + Point3f maxAx(max(ttop.x, tbottom.x), max(ttop.y, tbottom.y), max(ttop.z, tbottom.z)); + + // near clipping plane + const float clip = 0.f; + float tmin = max(max(max(minAx.x, minAx.y), max(minAx.x, minAx.z)), clip); + float tmax = min(min(maxAx.x, maxAx.y), min(maxAx.x, maxAx.z)); + + if(tmin < tmax) + { + // precautions against getting coordinates out of bounds + tmin = tmin + tstep; + tmax = tmax - tstep - tstep; + + // interpolation optimized a little + orig *= volume.voxelSizeInv; + dir *= volume.voxelSizeInv; + + Point3f rayStep = dir * tstep; + Point3f next = (orig + dir * tmin); + volumeType f = volume.interpolateVoxel(next), fnext = f; + + //raymarch + int steps = 0; + int nSteps = floor((tmax - tmin)/tstep); + for(; steps < nSteps; steps++) + { + next += rayStep; + int xdim = volume.dims[0], ydim = volume.dims[1]; + int ix = cvRound(next.x); + int iy = cvRound(next.y); + int iz = cvRound(next.z); + fnext = volume.volume(ix*xdim + iy*ydim + iz).v; + if(fnext != f) + { + fnext = volume.interpolateVoxel(next); + + // when ray crosses a surface + if(std::signbit(f) != std::signbit(fnext)) + break; + + f = fnext; + } + } + + // if ray penetrates a surface from outside + // linearly interpolate t between two f values + if(f > 0.f && fnext < 0.f) + { + Point3f tp = next - rayStep; + volumeType ft = volume.interpolateVoxel(tp); + volumeType ftdt = volume.interpolateVoxel(next); + // float t = tmin + steps*tstep; + // float ts = t - tstep*ft/(ftdt - ft); + float ts = tmin + tstep*(steps - ft/(ftdt - ft)); + + // avoid division by zero + if(!cvIsNaN(ts) && !cvIsInf(ts)) + { + Point3f pv = (orig + dir*ts); + Point3f nv = volume.getNormalVoxel(pv); + + if(!isNaN(nv)) + { + //convert pv and nv to camera space + normal = volRot * nv; + // interpolation optimized a little + point = vol2cam * (pv * volume.voxelSize); + } + } + } + } + + ptsRow[x] = toPtype(point); + nrmRow[x] = toPtype(normal); + } + } + } +#endif + + Points& points; + Normals& normals; + const TSDFVolumeCPU& volume; + + const float tstep; + + const Point3f boxMax; + const Point3f boxMin; + + const Affine3f cam2vol; + const Affine3f vol2cam; + const Intr::Reprojector reproj; +}; + + +void TSDFVolumeCPU::raycast(cv::Affine3f cameraPose, Intr intrinsics, Size frameSize, int pyramidLevels, + cv::Ptr frameGenerator, cv::Ptr frame) const +{ + ScopeTime st("tsdf: raycast"); + + CV_Assert(frameSize.area() > 0); + + Points points(frameSize); + Normals normals(frameSize); + + const int nstripes = -1; + parallel_for_(Range(0, points.rows), RaycastInvoker(points, normals, cameraPose, intrinsics, *this), nstripes); + + // build a pyramid of points and normals + (*frameGenerator)(frame, points, normals, pyramidLevels); +} + + +struct FetchPointsNormalsInvoker : ParallelLoopBody +{ + FetchPointsNormalsInvoker(const TSDFVolumeCPU& _volume, + std::vector< std::vector >& _pVecs, + std::vector< std::vector >& _nVecs, + bool _needNormals) : + ParallelLoopBody(), + vol(_volume), + pVecs(_pVecs), + nVecs(_nVecs), + needNormals(_needNormals) + { + volDataStart = vol.volume[0]; + } + + inline void coord(std::vector& points, std::vector& normals, + int x, int y, int z, Point3f V, float v0, int axis) const + { + // 0 for x, 1 for y, 2 for z + const int edgeResolution = vol.edgeResolution; + bool limits = false; + Point3i shift; + float Vc = 0.f; + if(axis == 0) + { + shift = Point3i(1, 0, 0); + limits = (x + 1 < edgeResolution); + Vc = V.x; + } + if(axis == 1) + { + shift = Point3i(0, 1, 0); + limits = (y + 1 < edgeResolution); + Vc = V.y; + } + if(axis == 2) + { + shift = Point3i(0, 0, 1); + limits = (z + 1 < edgeResolution); + Vc = V.z; + } + + if(limits) + { + const Voxel& voxeld = volDataStart[(x+shift.x)*vol.dims[0] + + (y+shift.y)*vol.dims[1] + + (z+shift.z)]; + volumeType vd = voxeld.v; + + if(voxeld.weight != 0 && vd != 1.f) + { + if((v0 > 0 && vd < 0) || (v0 < 0 && vd > 0)) + { + //linearly interpolate coordinate + float Vn = Vc + vol.voxelSize; + float dinv = 1.f/(abs(v0)+abs(vd)); + float inter = (Vc*abs(vd) + Vn*abs(v0))*dinv; + + Point3f p(shift.x ? inter : V.x, + shift.y ? inter : V.y, + shift.z ? inter : V.z); + { + points.push_back(toPtype(vol.pose * p)); + if(needNormals) + normals.push_back(toPtype(vol.pose.rotation() * vol.getNormalVoxel(p * vol.voxelSizeInv))); + } + } + } + } + } + + virtual void operator() (const Range& range) const override + { + // &elem(x, y, z) = data + x*edgeRes^2 + y*edgeRes + z; + std::vector points, normals; + for(int x = range.start; x < range.end; x++) + { + const Voxel* volDataX = volDataStart + x*vol.dims[0]; + for(int y = 0; y < vol.edgeResolution; y++) + { + const Voxel* volDataY = volDataX + y*vol.dims[1]; + for(int z = 0; z < vol.edgeResolution; z++) + { + const Voxel& voxel0 = volDataY[z]; + volumeType v0 = voxel0.v; + if(voxel0.weight != 0 && v0 != 1.f) + { + Point3f V = (Point3f((float)x, (float)y, (float)z) + + Point3f(0.5f, 0.5f, 0.5f))*vol.voxelSize; + + coord(points, normals, x, y, z, V, v0, 0); + coord(points, normals, x, y, z, V, v0, 1); + coord(points, normals, x, y, z, V, v0, 2); + + } // if voxel is not empty + } + } + } + + AutoLock al(mutex); + pVecs.push_back(points); + nVecs.push_back(normals); + } + + const TSDFVolumeCPU& vol; + std::vector< std::vector >& pVecs; + std::vector< std::vector >& nVecs; + const Voxel* volDataStart; + bool needNormals; + mutable Mutex mutex; +}; + +void TSDFVolumeCPU::fetchPointsNormals(OutputArray _points, OutputArray _normals) const +{ + ScopeTime st("tsdf: fetch points+normals"); + + if(_points.needed()) + { + std::vector< std::vector > pVecs, nVecs; + FetchPointsNormalsInvoker fi(*this, pVecs, nVecs, _normals.needed()); + Range range(0, edgeResolution); + const int nstripes = -1; + parallel_for_(range, fi, nstripes); + std::vector points, normals; + for(size_t i = 0; i < pVecs.size(); i++) + { + points.insert(points.end(), pVecs[i].begin(), pVecs[i].end()); + normals.insert(normals.end(), nVecs[i].begin(), nVecs[i].end()); + } + + _points.create((int)points.size(), 1, DataType::type); + Mat((int)points.size(), 1, DataType::type, &points[0]).copyTo(_points.getMat()); + + if(_normals.needed()) + { + _normals.create((int)normals.size(), 1, DataType::type); + Mat((int)normals.size(), 1, DataType::type, &normals[0]).copyTo(_normals.getMat()); + } + } +} + + +struct PushNormals +{ + PushNormals(const TSDFVolumeCPU& _vol, Mat_& _nrm) : + vol(_vol), normals(_nrm), invPose(vol.pose.inv()) + { } + void operator ()(const ptype &pp, const int * position) const + { + Point3f p = fromPtype(pp); + Point3f n = nan3; + if(!isNaN(p)) + { + n = vol.pose.rotation() * vol.getNormalVoxel(invPose * p * vol.voxelSizeInv); + } + normals(position[0], position[1]) = toPtype(n); + } + const TSDFVolumeCPU& vol; + Mat_& normals; + + Affine3f invPose; +}; + + +void TSDFVolumeCPU::fetchNormals(InputArray _points, OutputArray _normals) const +{ + ScopeTime st("tsdf: fetch normals"); + + if(_normals.needed()) + { + Points points = _points.getMat(); + CV_Assert(points.type() == DataType::type); + + _normals.createSameSize(_points, _points.type()); + Mat_ normals = _normals.getMat(); + + points.forEach(PushNormals(*this, normals)); + } +} + +///////// GPU implementation ///////// + +class TSDFVolumeGPU : public TSDFVolume +{ +public: + // dimension in voxels, size in meters + TSDFVolumeGPU(int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, + float _raycastStepFactor); + + virtual void integrate(cv::Ptr depth, float depthFactor, cv::Affine3f cameraPose, cv::kinfu::Intr intrinsics) override; + virtual void raycast(cv::Affine3f cameraPose, cv::kinfu::Intr intrinsics, cv::Size frameSize, int pyramidLevels, + cv::Ptr frameGenerator, cv::Ptr frame) const override; + + virtual void fetchPointsNormals(cv::OutputArray points, cv::OutputArray normals) const override; + virtual void fetchNormals(cv::InputArray points, cv::OutputArray _normals) const override; + + virtual void reset() override; +}; + + +TSDFVolumeGPU::TSDFVolumeGPU(int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, + float _raycastStepFactor) : + TSDFVolume(_res, _size, _pose, _truncDist, _maxWeight, _raycastStepFactor) +{ } + + +// zero volume, leave rest params the same +void TSDFVolumeGPU::reset() +{ + throw std::runtime_error("Not implemented"); +} + + +// use depth instead of distance (optimization) +void TSDFVolumeGPU::integrate(cv::Ptr /*depth*/, float /*depthFactor*/, cv::Affine3f /*cameraPose*/, Intr /*intrinsics*/) +{ + throw std::runtime_error("Not implemented"); +} + + +void TSDFVolumeGPU::raycast(cv::Affine3f /*cameraPose*/, Intr /*intrinsics*/, Size /*frameSize*/, int /*pyramidLevels*/, + Ptr /* frameGenerator */, Ptr /* frame */) const +{ + throw std::runtime_error("Not implemented"); +} + + +void TSDFVolumeGPU::fetchNormals(InputArray /*_points*/, OutputArray /*_normals*/) const +{ + throw std::runtime_error("Not implemented"); +} + +void TSDFVolumeGPU::fetchPointsNormals(OutputArray /*points*/, OutputArray /*normals*/) const +{ + throw std::runtime_error("Not implemented"); +} + +cv::Ptr makeTSDFVolume(cv::kinfu::KinFu::Params::PlatformType t, + int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, + float _raycastStepFactor) +{ + switch (t) + { + case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_CPU: + return cv::makePtr(_res, _size, _pose, _truncDist, _maxWeight, + _raycastStepFactor); + case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_GPU: + return cv::makePtr(_res, _size, _pose, _truncDist, _maxWeight, + _raycastStepFactor); + default: + return cv::Ptr(); + } +} + +} // namespace kinfu +} // namespace cv diff --git a/modules/rgbd/src/tsdf.hpp b/modules/rgbd/src/tsdf.hpp new file mode 100644 index 000000000..41b4f8b37 --- /dev/null +++ b/modules/rgbd/src/tsdf.hpp @@ -0,0 +1,47 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#ifndef __OPENCV_KINFU_TSDF_H__ +#define __OPENCV_KINFU_TSDF_H__ + +#include "precomp.hpp" +#include "kinfu_frame.hpp" + +namespace cv { +namespace kinfu { + + +class TSDFVolume +{ +public: + // dimension in voxels, size in meters + TSDFVolume(int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, + float _raycastStepFactor); + + virtual void integrate(cv::Ptr depth, float depthFactor, cv::Affine3f cameraPose, cv::kinfu::Intr intrinsics) = 0; + virtual void raycast(cv::Affine3f cameraPose, cv::kinfu::Intr intrinsics, cv::Size frameSize, int pyramidLevels, + cv::Ptr frameGenerator, cv::Ptr frame) const = 0; + + virtual void fetchPointsNormals(cv::OutputArray points, cv::OutputArray normals) const = 0; + virtual void fetchNormals(cv::InputArray points, cv::OutputArray _normals) const = 0; + + virtual void reset() = 0; + + virtual ~TSDFVolume() { } + + float edgeSize; + int edgeResolution; + int maxWeight; + cv::Affine3f pose; +}; + +cv::Ptr makeTSDFVolume(cv::kinfu::KinFu::Params::PlatformType t, + int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, + float _raycastStepFactor); + +} // namespace kinfu +} // namespace cv +#endif diff --git a/modules/rgbd/src/utils.cpp b/modules/rgbd/src/utils.cpp index f068c298e..92e227d93 100644 --- a/modules/rgbd/src/utils.cpp +++ b/modules/rgbd/src/utils.cpp @@ -1,42 +1,12 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ - -#include -#include - -#include "utils.h" +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + +#include "utils.hpp" namespace cv { @@ -76,6 +46,42 @@ namespace rgbd if ((in_depth == CV_32F) || (in_depth == CV_64F)) in.convertTo(out, depth); } +} // namespace rgbd + +namespace kinfu { + +#if PRINT_TIME + +ScopeTime::ScopeTime(std::string name_, bool _enablePrint) : + name(name_), enablePrint(_enablePrint) +{ + start = (double)cv::getTickCount(); + nested++; } + +ScopeTime::~ScopeTime() +{ + double time_ms = ((double)cv::getTickCount() - start)*1000.0/cv::getTickFrequency(); + if(enablePrint) + { + std::string spaces(nested, '-'); + std::cout << spaces << "Time(" << name << ") = " << time_ms << " ms" << std::endl; + } + nested--; } +int ScopeTime::nested = 0; + +#else + +ScopeTime::ScopeTime(std::string /*name_*/, bool /*_enablePrint = true*/) +{ } + +ScopeTime::~ScopeTime() +{ } + +#endif + +} // namespace kinfu +} // namespace cv + diff --git a/modules/rgbd/src/utils.h b/modules/rgbd/src/utils.h deleted file mode 100644 index 54f4c100a..000000000 --- a/modules/rgbd/src/utils.h +++ /dev/null @@ -1,81 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2009, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ - -#ifndef __OPENCV_RGBD_UTILS_HPP__ -#define __OPENCV_RGBD_UTILS_HPP__ - -#ifdef __cplusplus - -#include - -namespace cv -{ -namespace rgbd -{ - -/** If the input image is of type CV_16UC1 (like the Kinect one), the image is converted to floats, divided - * by 1000 to get a depth in meters, and the values 0 are converted to std::numeric_limits::quiet_NaN() - * Otherwise, the image is simply converted to floats - * @param in the depth image (if given as short int CV_U, it is assumed to be the depth in millimeters - * (as done with the Microsoft Kinect), it is assumed in meters) - * @param the desired output depth (floats or double) - * @param out The rescaled float depth image - */ -template -void -rescaleDepthTemplated(const Mat& in, Mat& out); - -template<> -inline void -rescaleDepthTemplated(const Mat& in, Mat& out) -{ - rescaleDepth(in, CV_32F, out); -} - -template<> -inline void -rescaleDepthTemplated(const Mat& in, Mat& out) -{ - rescaleDepth(in, CV_64F, out); -} - -} -} - -#endif /* __cplusplus */ - -#endif - -/* End of file. */ diff --git a/modules/rgbd/src/utils.hpp b/modules/rgbd/src/utils.hpp new file mode 100644 index 000000000..83c6fddaf --- /dev/null +++ b/modules/rgbd/src/utils.hpp @@ -0,0 +1,153 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + +#ifndef __OPENCV_RGBD_UTILS_HPP__ +#define __OPENCV_RGBD_UTILS_HPP__ + +#include "precomp.hpp" + +namespace cv +{ +namespace rgbd +{ + +/** If the input image is of type CV_16UC1 (like the Kinect one), the image is converted to floats, divided + * by 1000 to get a depth in meters, and the values 0 are converted to std::numeric_limits::quiet_NaN() + * Otherwise, the image is simply converted to floats + * @param in the depth image (if given as short int CV_U, it is assumed to be the depth in millimeters + * (as done with the Microsoft Kinect), it is assumed in meters) + * @param the desired output depth (floats or double) + * @param out The rescaled float depth image + */ +template +void +rescaleDepthTemplated(const Mat& in, Mat& out); + +template<> +inline void +rescaleDepthTemplated(const Mat& in, Mat& out) +{ + rescaleDepth(in, CV_32F, out); +} + +template<> +inline void +rescaleDepthTemplated(const Mat& in, Mat& out) +{ + rescaleDepth(in, CV_64F, out); +} + +} // namespace rgbd + + +namespace kinfu { + +// Print execution times of each block marked with ScopeTime +#define PRINT_TIME 0 + +typedef float depthType; + +const float qnan = std::numeric_limits::quiet_NaN(); +const cv::Vec3f nan3(qnan, qnan, qnan); +#if CV_SIMD128 +const cv::v_float32x4 nanv(qnan, qnan, qnan, qnan); +#endif + +inline bool isNaN(cv::Point3f p) +{ + return (cvIsNaN(p.x) || cvIsNaN(p.y) || cvIsNaN(p.z)); +} + +#if CV_SIMD128 +static inline bool isNaN(const cv::v_float32x4& p) +{ + return cv::v_check_any(p != p); +} +#endif + +struct ScopeTime +{ + ScopeTime(std::string name_, bool _enablePrint = true); + ~ScopeTime(); + +#if PRINT_TIME + static int nested; + const std::string name; + const bool enablePrint; + double start; +#endif +}; + +/** @brief Camera intrinsics */ +struct Intr +{ + /** Reprojects screen point to camera space given z coord. */ + struct Reprojector + { + Reprojector() {} + inline Reprojector(Intr intr) + { + fxinv = 1.f/intr.fx, fyinv = 1.f/intr.fy; + cx = intr.cx, cy = intr.cy; + } + template + inline cv::Point3_ operator()(cv::Point3_ p) const + { + T x = p.z * (p.x - cx) * fxinv; + T y = p.z * (p.y - cy) * fyinv; + return cv::Point3_(x, y, p.z); + } + + float fxinv, fyinv, cx, cy; + }; + /** Projects camera space vector onto screen */ + struct Projector + { + inline Projector(Intr intr) : fx(intr.fx), fy(intr.fy), cx(intr.cx), cy(intr.cy) { } + template + inline cv::Point_ operator()(cv::Point3_ p) const + { + T invz = T(1)/p.z; + T x = fx*(p.x*invz) + cx; + T y = fy*(p.y*invz) + cy; + return cv::Point_(x, y); + } + template + inline cv::Point_ operator()(cv::Point3_ p, cv::Point3_& pixVec) const + { + T invz = T(1)/p.z; + pixVec = cv::Point3_(p.x*invz, p.y*invz, 1); + T x = fx*pixVec.x + cx; + T y = fy*pixVec.y + cy; + return cv::Point_(x, y); + } + float fx, fy, cx, cy; + }; + Intr() : fx(), fy(), cx(), cy() { } + Intr(float _fx, float _fy, float _cx, float _cy) : fx(_fx), fy(_fy), cx(_cx), cy(_cy) { } + Intr(cv::Matx33f m) : fx(m(0, 0)), fy(m(1, 1)), cx(m(0, 2)), cy(m(1, 2)) { } + // scale intrinsics to pyramid level + inline Intr scale(int pyr) const + { + float factor = (1.f /(1 << pyr)); + return Intr(fx*factor, fy*factor, cx*factor, cy*factor); + } + inline Reprojector makeReprojector() const { return Reprojector(*this); } + inline Projector makeProjector() const { return Projector(*this); } + + float fx, fy, cx, cy; +}; + +} // namespace kinfu + +} // namespace cv + + +#endif + +/* End of file. */ diff --git a/modules/rgbd/test/test_kinfu.cpp b/modules/rgbd/test/test_kinfu.cpp new file mode 100644 index 000000000..9bb104a7e --- /dev/null +++ b/modules/rgbd/test/test_kinfu.cpp @@ -0,0 +1,343 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +#include "test_precomp.hpp" + +// Inspired by Inigo Quilez' raymarching guide: +// http://iquilezles.org/www/articles/distfunctions/distfunctions.htm + +namespace opencv_test { namespace { + +using namespace cv; + +/** Reprojects screen point to camera space given z coord. */ +struct Reprojector +{ + Reprojector() {} + inline Reprojector(Matx33f intr) + { + fxinv = 1.f/intr(0, 0), fyinv = 1.f/intr(1, 1); + cx = intr(0, 2), cy = intr(1, 2); + } + template + inline cv::Point3_ operator()(cv::Point3_ p) const + { + T x = p.z * (p.x - cx) * fxinv; + T y = p.z * (p.y - cy) * fyinv; + return cv::Point3_(x, y, p.z); + } + + float fxinv, fyinv, cx, cy; +}; + +template +struct RenderInvoker : ParallelLoopBody +{ + RenderInvoker(Mat_& _frame, Affine3f _pose, + Reprojector _reproj, + float _depthFactor) : ParallelLoopBody(), + frame(_frame), + pose(_pose), + reproj(_reproj), + depthFactor(_depthFactor) + { } + + virtual void operator ()(const cv::Range& r) const + { + for(int y = r.start; y < r.end; y++) + { + float* frameRow = frame[y]; + for(int x = 0; x < frame.cols; x++) + { + float pix = 0; + + Point3f orig = pose.translation(); + // direction through pixel + Point3f screenVec = reproj(Point3f((float)x, (float)y, 1.f)); + float xyt = 1.f/(screenVec.x*screenVec.x + + screenVec.y*screenVec.y + 1.f); + Point3f dir = normalize(Vec3f(pose.rotation() * screenVec)); + // screen space axis + dir.y = - dir.y; + + const float maxDepth = 20.f; + const float maxSteps = 256; + float t = 0.f; + for(int step = 0; step < maxSteps && t < maxDepth; step++) + { + Point3f p = orig + dir*t; + float d = Scene::map(p); + if(d < 0.000001f) + { + float depth = std::sqrt(t*t*xyt); + pix = depth*depthFactor; + break; + } + t += d; + } + + frameRow[x] = pix; + } + } + } + + Mat_& frame; + Affine3f pose; + Reprojector reproj; + float depthFactor; +}; + +struct CubeSpheresScene +{ + const int framesPerCycle = 32; + const int nCycles = 1; + const Affine3f startPose = Affine3f(Vec3f(-0.5f, 0.f, 0.f), Vec3f(2.1f, 1.4f, -2.1f)); + + CubeSpheresScene(Size sz, Matx33f _intr, float _depthFactor) : + frameSize(sz), intr(_intr), depthFactor(_depthFactor) + { } + + static float map(Point3f p) + { + float plane = p.y + 0.5f; + + Point3f boxPose = p - Point3f(-0.0f, 0.3f, 0.0f); + float boxSize = 0.5f; + float roundness = 0.08f; + Point3f boxTmp; + boxTmp.x = max(abs(boxPose.x) - boxSize, 0.0f); + boxTmp.y = max(abs(boxPose.y) - boxSize, 0.0f); + boxTmp.z = max(abs(boxPose.z) - boxSize, 0.0f); + float roundBox = (float)cv::norm(boxTmp) - roundness; + + float sphereRadius = 0.7f; + float sphere = (float)cv::norm(boxPose) - sphereRadius; + + float boxMinusSphere = max(roundBox, -sphere); + + float sphere2 = (float)cv::norm(p - Point3f(0.3f, 1.f, 0.f)) - 0.1f; + float sphere3 = (float)cv::norm(p - Point3f(0.0f, 1.f, 0.f)) - 0.2f; + float res = min(min(plane, boxMinusSphere), min(sphere2, sphere3)); + + return res; + } + + Mat depth(Affine3f pose) + { + Mat_ frame(frameSize); + Reprojector reproj(intr); + + Range range(0, frame.rows); + parallel_for_(range, RenderInvoker(frame, pose, reproj, depthFactor)); + + return frame; + } + + std::vector getPoses() + { + std::vector poses; + for(int i = 0; i < framesPerCycle*nCycles; i++) + { + float angle = (float)(CV_2PI*i/framesPerCycle); + Affine3f pose; + pose = pose.rotate(startPose.rotation()); + pose = pose.rotate(Vec3f(0.f, -1.f, 0.f)*angle); + pose = pose.translate(Vec3f(startPose.translation()[0]*sin(angle), + startPose.translation()[1], + startPose.translation()[2]*cos(angle))); + poses.push_back(pose); + } + + return poses; + } + + Size frameSize; + Matx33f intr; + float depthFactor; +}; + + +struct RotatingScene +{ + const int framesPerCycle = 64; + const int nCycles = 1; + const Affine3f startPose = Affine3f(Vec3f(-1.f, 0.f, 0.f), Vec3f(1.5f, 2.f, -1.5f)); + + RotatingScene(Size sz, Matx33f _intr, float _depthFactor) : + frameSize(sz), intr(_intr), depthFactor(_depthFactor) + { + cv::RNG rng(0); + rng.fill(randTexture, cv::RNG::UNIFORM, 0.f, 1.f); + } + + static float noise(Point2f pt) + { + pt.x = abs(pt.x - (int)pt.x); + pt.y = abs(pt.y - (int)pt.y); + pt *= 256.f; + + int xi = cvFloor(pt.x), yi = cvFloor(pt.y); + + const float* row0 = randTexture[(yi+0)%256]; + const float* row1 = randTexture[(yi+1)%256]; + + float v00 = row0[(xi+0)%256]; + float v01 = row0[(xi+1)%256]; + float v10 = row1[(xi+0)%256]; + float v11 = row1[(xi+1)%256]; + + float tx = pt.x - xi, ty = pt.y - yi; + float v0 = v00 + tx*(v01 - v00); + float v1 = v10 + tx*(v11 - v10); + return v0 + ty*(v1 - v0); + } + + static float map(Point3f p) + { + const Point3f torPlace(0.f, 0.f, 0.f); + Point3f torPos(p - torPlace); + const Point2f torusParams(1.f, 0.2f); + Point2f torq(std::sqrt(torPos.x*torPos.x + torPos.z*torPos.z) - torusParams.x, torPos.y); + float torus = (float)cv::norm(torq) - torusParams.y; + + const Point3f cylShift(0.25f, 0.25f, 0.25f); + + Point3f cylPos = Point3f(abs(std::fmod(p.x-0.1f, cylShift.x)), + p.y, + abs(std::fmod(p.z-0.2f, cylShift.z))) - cylShift*0.5f; + + const Point2f cylParams(0.1f, + 0.1f+0.1f*sin(p.x*p.y*5.f /* +std::log(1.f+abs(p.x*0.1f)) */)); + Point2f cyld = Point2f(abs(std::sqrt(cylPos.x*cylPos.x + cylPos.z*cylPos.z)), abs(cylPos.y)) - cylParams; + float pins = min(max(cyld.x, cyld.y), 0.0f) + (float)cv::norm(Point2f(max(cyld.x, 0.f), max(cyld.y, 0.f))); + + float terrain = p.y + 0.25f*noise(Point2f(p.x, p.z)*0.01f); + + float res = min(terrain, max(-pins, torus)); + + return res; + } + + Mat depth(Affine3f pose) + { + Mat_ frame(frameSize); + Reprojector reproj(intr); + + Range range(0, frame.rows); + parallel_for_(range, RenderInvoker(frame, pose, reproj, depthFactor)); + + return frame; + } + + std::vector getPoses() + { + std::vector poses; + for(int i = 0; i < framesPerCycle*nCycles; i++) + { + float angle = (float)(CV_2PI*i/framesPerCycle); + Affine3f pose; + pose = pose.rotate(startPose.rotation()); + pose = pose.rotate(Vec3f(0.f, -1.f, 0.f)*angle); + pose = pose.translate(Vec3f(startPose.translation()[0]*sin(angle), + startPose.translation()[1], + startPose.translation()[2]*cos(angle))); + poses.push_back(pose); + } + + return poses; + } + + Size frameSize; + Matx33f intr; + float depthFactor; + static cv::Mat_ randTexture; +}; + +Mat_ RotatingScene::randTexture(256, 256); + +static const bool display = false; + +TEST( KinectFusion, lowDense ) +{ + kinfu::KinFu::Params params; + params = kinfu::KinFu::Params::coarseParams(); + + RotatingScene scene(params.frameSize, params.intr, params.depthFactor); + + kinfu::KinFu kf(params); + + std::vector poses = scene.getPoses(); + Affine3f startPoseGT = poses[0], startPoseKF; + Affine3f pose, kfPose; + for(size_t i = 0; i < poses.size(); i++) + { + pose = poses[i]; + + Mat depth = scene.depth(pose); + + ASSERT_TRUE(kf.update(depth)); + + kfPose = kf.getPose(); + if(i == 0) + startPoseKF = kfPose; + + pose = ( startPoseGT.inv() * pose )*startPoseKF; + + if(display) + { + imshow("depth", depth*(1.f/params.depthFactor/4.f)); + Mat rendered; + kf.render(rendered); + imshow("render", rendered); + waitKey(10); + } + } + + ASSERT_LT(cv::norm(kfPose.rvec() - pose.rvec()), 0.01); + ASSERT_LT(cv::norm(kfPose.translation() - pose.translation()), 0.1); +} + +TEST( KinectFusion, highDense ) +{ + kinfu::KinFu::Params params; + + params = kinfu::KinFu::Params::defaultParams(); + CubeSpheresScene scene(params.frameSize, params.intr, params.depthFactor); + + kinfu::KinFu kf(params); + + std::vector poses = scene.getPoses(); + Affine3f startPoseGT = poses[0], startPoseKF; + Affine3f pose, kfPose; + for(size_t i = 0; i < poses.size(); i++) + { + pose = poses[i]; + + Mat depth = scene.depth(pose); + + ASSERT_TRUE(kf.update(depth)); + + kfPose = kf.getPose(); + if(i == 0) + startPoseKF = kfPose; + + pose = ( startPoseGT.inv() * pose )*startPoseKF; + + if(display) + { + imshow("depth", depth*(1.f/params.depthFactor/4.f)); + Mat rendered; + kf.render(rendered); + imshow("render", rendered); + waitKey(10); + } + } + + ASSERT_LT(cv::norm(kfPose.rvec() - pose.rvec()), 0.01); + ASSERT_LT(cv::norm(kfPose.translation() - pose.translation()), 0.03); +} + +}} // namespace diff --git a/modules/rgbd/test/test_main.cpp b/modules/rgbd/test/test_main.cpp index 0e51ddfd0..3bd6c9121 100644 --- a/modules/rgbd/test/test_main.cpp +++ b/modules/rgbd/test/test_main.cpp @@ -1,6 +1,11 @@ // This file is part of OpenCV project. // It is subject to the license terms in the LICENSE file found in the top-level directory -// of this distribution and at http://opencv.org/license.html. +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + #include "test_precomp.hpp" CV_TEST_MAIN("cv") diff --git a/modules/rgbd/test/test_normal.cpp b/modules/rgbd/test/test_normal.cpp index f2233553a..55e7ce253 100644 --- a/modules/rgbd/test/test_normal.cpp +++ b/modules/rgbd/test/test_normal.cpp @@ -1,37 +1,8 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include "test_precomp.hpp" #include diff --git a/modules/rgbd/test/test_odometry.cpp b/modules/rgbd/test/test_odometry.cpp index 62b654a1e..3da490c0b 100644 --- a/modules/rgbd/test/test_odometry.cpp +++ b/modules/rgbd/test/test_odometry.cpp @@ -1,37 +1,10 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2012, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include "test_precomp.hpp" @@ -150,10 +123,13 @@ class CV_OdometryTest : public cvtest::BaseTest public: CV_OdometryTest(const Ptr& _odometry, double _maxError1, - double _maxError5) : + double _maxError5, + double _idError = DBL_EPSILON) : odometry(_odometry), maxError1(_maxError1), - maxError5(_maxError5) {} + maxError5(_maxError5), + idError(_idError) + { } protected: bool readData(Mat& image, Mat& depth) const; @@ -164,6 +140,7 @@ protected: Ptr odometry; double maxError1; double maxError5; + double idError; }; bool CV_OdometryTest::readData(Mat& image, Mat& depth) const @@ -239,8 +216,8 @@ void CV_OdometryTest::run(int) Mat calcRt; // 1. Try to find Rt between the same frame (try masks also). - bool isComputed = odometry->compute(image, depth, Mat(image.size(), CV_8UC1, Scalar(255)), - image, depth, Mat(image.size(), CV_8UC1, Scalar(255)), + bool isComputed = odometry->compute(image, depth, Mat(image.size(), CV_8UC1, Scalar(255)), + image, depth, Mat(image.size(), CV_8UC1, Scalar(255)), calcRt); if(!isComputed) { @@ -248,15 +225,15 @@ void CV_OdometryTest::run(int) ts->set_failed_test_info(cvtest::TS::FAIL_INVALID_OUTPUT); } double diff = cv::norm(calcRt, Mat::eye(4,4,CV_64FC1)); - if(diff > DBL_EPSILON) + if(diff > idError) { ts->printf(cvtest::TS::LOG, "Incorrect transformation between the same frame (not the identity matrix), diff = %f", diff); ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY); } - // 2. Generate random rigid body motion in some ranges several times (iterCount). + // 2. Generate random rigid body motion in some ranges several times (iterCount). // On each iteration an input frame is warped using generated transformation. - // Odometry is run on the following pair: the original frame and the warped one. + // Odometry is run on the following pair: the original frame and the warped one. // Comparing a computed transformation with an applied one we compute 2 errors: // better_1time_count - count of poses which error is less than ground thrush pose, // better_5times_count - count of poses which error is 5 times less than ground thrush pose. @@ -271,7 +248,8 @@ void CV_OdometryTest::run(int) warpFrame(image, depth, rvec, tvec, K, warpedImage, warpedDepth); dilateFrame(warpedImage, warpedDepth); // due to inaccuracy after warping - isComputed = odometry->compute(image, depth, Mat(), warpedImage, warpedDepth, Mat(), calcRt); + Mat imageMask(image.size(), CV_8UC1, Scalar(255)); + isComputed = odometry->compute(image, depth, imageMask, warpedImage, warpedDepth, imageMask, calcRt); if(!isComputed) continue; @@ -329,21 +307,27 @@ void CV_OdometryTest::run(int) TEST(RGBD_Odometry_Rgbd, algorithmic) { - CV_OdometryTest test(cv::rgbd::Odometry::create("RgbdOdometry"), 0.99, 0.94); + CV_OdometryTest test(cv::rgbd::Odometry::create("RgbdOdometry"), 0.99, 0.89); test.safe_run(); } -TEST(DISABLED_RGBD_Odometry_ICP, algorithmic) +TEST(RGBD_Odometry_ICP, algorithmic) { CV_OdometryTest test(cv::rgbd::Odometry::create("ICPOdometry"), 0.99, 0.99); test.safe_run(); } -TEST(DISABLED_RGBD_Odometry_RgbdICP, algorithmic) +TEST(RGBD_Odometry_RgbdICP, algorithmic) { CV_OdometryTest test(cv::rgbd::Odometry::create("RgbdICPOdometry"), 0.99, 0.99); test.safe_run(); } +TEST(RGBD_Odometry_FastICP, algorithmic) +{ + CV_OdometryTest test(cv::rgbd::Odometry::create("FastICPOdometry"), 0.99, 0.99, FLT_EPSILON); + test.safe_run(); +} + }} // namespace diff --git a/modules/rgbd/test/test_precomp.hpp b/modules/rgbd/test/test_precomp.hpp index 1a6ea9015..b39793a6c 100644 --- a/modules/rgbd/test/test_precomp.hpp +++ b/modules/rgbd/test/test_precomp.hpp @@ -1,6 +1,11 @@ // This file is part of OpenCV project. // It is subject to the license terms in the LICENSE file found in the top-level directory -// of this distribution and at http://opencv.org/license.html. +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_KinectFusion.md file found in this module's directory + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + #ifndef __OPENCV_TEST_PRECOMP_HPP__ #define __OPENCV_TEST_PRECOMP_HPP__ diff --git a/modules/rgbd/test/test_registration.cpp b/modules/rgbd/test/test_registration.cpp index f88998367..0001c9aab 100644 --- a/modules/rgbd/test/test_registration.cpp +++ b/modules/rgbd/test/test_registration.cpp @@ -1,46 +1,8 @@ -/*M/////////////////////////////////////////////////////////////////////////////////////// -// -// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. -// -// By downloading, copying, installing or using the software you agree to this license. -// If you do not agree to this license, do not download, install, -// copy or use the software. -// -// -// License Agreement -// For Open Source Computer Vision Library -// -// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. -// Copyright (C) 2009, Willow Garage Inc., all rights reserved. -// Copyright (C) 2014, OpenCV Foundation, all rights reserved. -// Third party copyrights are property of their respective owners. -// -// Redistribution and use in source and binary forms, with or without modification, -// are permitted provided that the following conditions are met: -// -// * Redistribution's of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// * Redistribution's in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// * The name of the copyright holders may not be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// This software is provided by the copyright holders and contributors "as is" and -// any express or implied warranties, including, but not limited to, the implied -// warranties of merchantability and fitness for a particular purpose are disclaimed. -// In no event shall the Intel Corporation or contributors be liable for any direct, -// indirect, incidental, special, exemplary, or consequential damages -// (including, but not limited to, procurement of substitute goods or services; -// loss of use, data, or profits; or business interruption) however caused -// and on any theory of liability, whether in contract, strict liability, -// or tort (including negligence or otherwise) arising in any way out of -// the use of this software, even if advised of the possibility of such damage. -// -//M*/ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory #include "test_precomp.hpp" diff --git a/modules/rgbd/test/test_utils.cpp b/modules/rgbd/test/test_utils.cpp index 19190e627..b155eaff9 100644 --- a/modules/rgbd/test/test_utils.cpp +++ b/modules/rgbd/test/test_utils.cpp @@ -1,6 +1,9 @@ // This file is part of OpenCV project. // It is subject to the license terms in the LICENSE file found in the top-level directory -// of this distribution and at http://opencv.org/license.html. +// of this distribution and at http://opencv.org/license.html + +// This code is also subject to the license terms in the LICENSE_WillowGarage.md file found in this module's directory + #include "test_precomp.hpp" namespace opencv_test { namespace { @@ -65,4 +68,4 @@ TEST(Rgbd_DepthTo3d, compute) } -}} // namespace \ No newline at end of file +}} // namespace From e351caedf7d8d13f19dde1366e236dbd9cf70ccc Mon Sep 17 00:00:00 2001 From: Rostislav Vasilikhin Date: Mon, 25 Jun 2018 14:09:39 +0300 Subject: [PATCH 05/97] KinectFusion demo: live input support added (#1671) * KinFu demo: added support for live demo, some bugs fixed * minor fixes * Kinect2 workarounds and defaults added --- modules/rgbd/samples/kinfu_demo.cpp | 187 ++++++++++++++++++++++------ modules/rgbd/src/tsdf.cpp | 6 +- 2 files changed, 153 insertions(+), 40 deletions(-) diff --git a/modules/rgbd/samples/kinfu_demo.cpp b/modules/rgbd/samples/kinfu_demo.cpp index 0abb9f165..b42cf46f5 100644 --- a/modules/rgbd/samples/kinfu_demo.cpp +++ b/modules/rgbd/samples/kinfu_demo.cpp @@ -48,6 +48,101 @@ static vector readDepth(std::string fileList) return v; } + +const Size kinect2FrameSize(512, 424); +// approximate values, no guarantee to be correct +const float kinect2Focal = 366.1f; +const float kinect2Cx = 258.2f; +const float kinect2Cy = 204.f; + +struct DepthSource +{ +public: + DepthSource() : + depthFileList(), + frameIdx(0), + vc(), + useKinect2Workarounds(true) + { } + + DepthSource(int cam) : + depthFileList(), + frameIdx(), + vc(VideoCaptureAPIs::CAP_OPENNI2 + cam), + useKinect2Workarounds(true) + { } + + DepthSource(String fileListName) : + depthFileList(readDepth(fileListName)), + frameIdx(0), + vc(), + useKinect2Workarounds(true) + { } + + Mat getDepth() + { + Mat out; + if (!vc.isOpened()) + { + if (frameIdx < depthFileList.size()) + out = cv::imread(depthFileList[frameIdx++], IMREAD_ANYDEPTH); + else + { + return Mat(); + } + } + else + { + vc.grab(); + vc.retrieve(out, CAP_OPENNI_DEPTH_MAP); + + // workaround for Kinect 2 + if(useKinect2Workarounds) + { + out = out(Rect(Point(), kinect2FrameSize)); + cv::flip(out, out, 1); + } + } + if (out.empty()) + throw std::runtime_error("Matrix is empty"); + return out; + } + + bool empty() + { + return depthFileList.empty() && !(vc.isOpened()); + } + + void updateParams(KinFu::Params& params) + { + if (vc.isOpened()) + { + // this should be set in according to user's depth sensor + int w = (int)vc.get(VideoCaptureProperties::CAP_PROP_FRAME_WIDTH); + int h = (int)vc.get(VideoCaptureProperties::CAP_PROP_FRAME_HEIGHT); + + float focal = (float)vc.get(CAP_OPENNI_DEPTH_GENERATOR | CAP_PROP_OPENNI_FOCAL_LENGTH); + + // it's recommended to calibrate sensor to obtain its intrinsics + float fx, fy, cx, cy; + fx = fy = useKinect2Workarounds ? kinect2Focal : focal; + cx = useKinect2Workarounds ? kinect2Cx : w/2 - 0.5f; + cy = useKinect2Workarounds ? kinect2Cy : h/2 - 0.5f; + + params.frameSize = useKinect2Workarounds ? kinect2FrameSize : Size(w, h); + params.intr = Matx33f(fx, 0, cx, + 0, fy, cy, + 0, 0, 1); + params.depthFactor = 1000.f; + } + } + + vector depthFileList; + size_t frameIdx; + VideoCapture vc; + bool useKinect2Workarounds; +}; + const std::string vizWindowName = "cloud"; struct PauseCallbackArgs @@ -77,13 +172,14 @@ void pauseCallback(const viz::MouseEvent& me, void* args) static const char* keys = { "{help h usage ? | | print this message }" - "{@depth || Path to depth.txt file listing a set of depth images }" + "{depth | | Path to depth.txt file listing a set of depth images }" + "{camera | | Index of depth camera to be used as a depth source }" "{coarse | | Run on coarse settings (fast but ugly) or on default (slow but looks better)," " in coarse mode points and normals are displayed }" }; static const std::string message = - "\nThis demo uses RGB-D dataset taken from" + "\nThis demo uses live depth input or RGB-D dataset taken from" "\nhttps://vision.in.tum.de/data/datasets/rgbd-dataset" "\nto demonstrate KinectFusion implementation \n"; @@ -104,8 +200,6 @@ int main(int argc, char **argv) coarse = true; } - String depthPath = parser.get(0); - if(!parser.check()) { parser.printMessage(); @@ -113,7 +207,18 @@ int main(int argc, char **argv) return -1; } - vector depthFileList = readDepth(depthPath); + DepthSource ds; + if (parser.has("depth")) + ds = DepthSource(parser.get("depth")); + if (parser.has("camera") && ds.empty()) + ds = DepthSource(parser.get("camera")); + + if (ds.empty()) + { + std::cerr << "Failed to open depth source" << std::endl; + parser.printMessage(); + return -1; + } KinFu::Params params; if(coarse) @@ -121,9 +226,12 @@ int main(int argc, char **argv) else params = KinFu::Params::defaultParams(); - // scene-specific params should be tuned for each scene individually - params.volumePose = params.volumePose.translate(Vec3f(0.f, 0.f, 0.5f)); - params.tsdf_max_weight = 16; + // These params can be different for each depth sensor + ds.updateParams(params); + + // Scene-specific params should be tuned for each scene individually + //params.volumePose = params.volumePose.translate(Vec3f(0.f, 0.f, 0.5f)); + //params.tsdf_max_weight = 16; KinFu kf(params); @@ -135,42 +243,41 @@ int main(int argc, char **argv) Mat points; Mat normals; - double prevTime = getTickCount(); + int64 prevTime = getTickCount(); bool pause = false; - for(size_t nFrame = 0; nFrame < depthFileList.size(); nFrame++) + for(Mat frame = ds.getDepth(); !frame.empty(); frame = ds.getDepth()) { if(pause) { kf.getCloud(points, normals); - viz::WCloud cloudWidget(points, viz::Color::white()); - viz::WCloudNormals cloudNormals(points, normals, /*level*/1, /*scale*/0.05, viz::Color::gray()); - window.showWidget("cloud", cloudWidget); - window.showWidget("normals", cloudNormals); - - window.showWidget("cube", viz::WCube(Vec3d::all(0), - Vec3d::all(kf.getParams().volumeSize)), - kf.getParams().volumePose); - PauseCallbackArgs pca(kf); - window.registerMouseCallback(pauseCallback, (void*)&pca); - window.showWidget("text", viz::WText(cv::String("Move camera in this window. " - "Close the window or press Q to resume"), Point())); - window.spin(); - window.removeWidget("text"); - window.registerMouseCallback(0); + if(!points.empty() && !normals.empty()) + { + viz::WCloud cloudWidget(points, viz::Color::white()); + viz::WCloudNormals cloudNormals(points, normals, /*level*/1, /*scale*/0.05, viz::Color::gray()); + window.showWidget("cloud", cloudWidget); + window.showWidget("normals", cloudNormals); + + window.showWidget("cube", viz::WCube(Vec3d::all(0), + Vec3d::all(kf.getParams().volumeSize)), + kf.getParams().volumePose); + PauseCallbackArgs pca(kf); + window.registerMouseCallback(pauseCallback, (void*)&pca); + window.showWidget("text", viz::WText(cv::String("Move camera in this window. " + "Close the window or press Q to resume"), Point())); + window.spin(); + window.removeWidget("text"); + window.registerMouseCallback(0); + } pause = false; } else { - Mat frame = cv::imread(depthFileList[nFrame], IMREAD_ANYDEPTH); - if(frame.empty()) - throw std::runtime_error("Matrix is empty"); - - // 5000 for typical per-meter coefficient of PNG files Mat cvt8; - convertScaleAbs(frame, cvt8, 0.25/5000.*256.); + float depthFactor = kf.getParams().depthFactor; + convertScaleAbs(frame, cvt8, 0.25*256. / depthFactor); imshow("depth", cvt8); if(!kf.update(frame)) @@ -183,10 +290,13 @@ int main(int argc, char **argv) if(coarse) { kf.getCloud(points, normals); - viz::WCloud cloudWidget(points, viz::Color::white()); - viz::WCloudNormals cloudNormals(points, normals, /*level*/1, /*scale*/0.05, viz::Color::gray()); - window.showWidget("cloud", cloudWidget); - window.showWidget("normals", cloudNormals); + if(!points.empty() && !normals.empty()) + { + viz::WCloud cloudWidget(points, viz::Color::white()); + viz::WCloudNormals cloudNormals(points, normals, /*level*/1, /*scale*/0.05, viz::Color::gray()); + window.showWidget("cloud", cloudWidget); + window.showWidget("normals", cloudNormals); + } } //window.showWidget("worldAxes", viz::WCoordinateSystem()); @@ -200,14 +310,15 @@ int main(int argc, char **argv) kf.render(rendered); } - double newTime = getTickCount(); - putText(rendered, cv::format("FPS: %2d press R to reset, P to pause, Q to quit", (int)(getTickFrequency()/(newTime - prevTime))), + int64 newTime = getTickCount(); + putText(rendered, cv::format("FPS: %2d press R to reset, P to pause, Q to quit", + (int)(getTickFrequency()/(newTime - prevTime))), Point(0, rendered.rows-1), FONT_HERSHEY_SIMPLEX, 0.5, Scalar(0, 255, 255)); prevTime = newTime; imshow("render", rendered); - int c = waitKey(1); + int c = waitKey(100); switch (c) { case 'r': diff --git a/modules/rgbd/src/tsdf.cpp b/modules/rgbd/src/tsdf.cpp index ca3eaae62..384072797 100644 --- a/modules/rgbd/src/tsdf.cpp +++ b/modules/rgbd/src/tsdf.cpp @@ -1091,12 +1091,14 @@ void TSDFVolumeCPU::fetchPointsNormals(OutputArray _points, OutputArray _normals } _points.create((int)points.size(), 1, DataType::type); - Mat((int)points.size(), 1, DataType::type, &points[0]).copyTo(_points.getMat()); + if(!points.empty()) + Mat((int)points.size(), 1, DataType::type, &points[0]).copyTo(_points.getMat()); if(_normals.needed()) { _normals.create((int)normals.size(), 1, DataType::type); - Mat((int)normals.size(), 1, DataType::type, &normals[0]).copyTo(_normals.getMat()); + if(!normals.empty()) + Mat((int)normals.size(), 1, DataType::type, &normals[0]).copyTo(_normals.getMat()); } } } From 9e787377dc82038d5f8d6ccf606ecb53a2f0b7ea Mon Sep 17 00:00:00 2001 From: Pavel Rojtberg Date: Thu, 21 Jun 2018 15:46:22 +0200 Subject: [PATCH 06/97] kinfu: allow basic wrapping for bindings for this - move Params struct out of class - use static create instead of pimpl - allow demo to be compiled without VIZ --- modules/rgbd/include/opencv2/rgbd/kinfu.hpp | 206 ++++++++++---------- modules/rgbd/samples/kinfu_demo.cpp | 70 +++---- modules/rgbd/src/fast_icp.cpp | 6 +- modules/rgbd/src/fast_icp.hpp | 2 +- modules/rgbd/src/kinfu.cpp | 103 +++------- modules/rgbd/src/kinfu_frame.cpp | 6 +- modules/rgbd/src/kinfu_frame.hpp | 2 +- modules/rgbd/src/odometry.cpp | 4 +- modules/rgbd/src/tsdf.cpp | 6 +- modules/rgbd/src/tsdf.hpp | 2 +- modules/rgbd/test/test_kinfu.cpp | 31 ++- 11 files changed, 195 insertions(+), 243 deletions(-) diff --git a/modules/rgbd/include/opencv2/rgbd/kinfu.hpp b/modules/rgbd/include/opencv2/rgbd/kinfu.hpp index 02af753ce..31f6de5e6 100644 --- a/modules/rgbd/include/opencv2/rgbd/kinfu.hpp +++ b/modules/rgbd/include/opencv2/rgbd/kinfu.hpp @@ -15,134 +15,134 @@ namespace kinfu { //! @addtogroup kinect_fusion //! @{ -/** @brief KinectFusion implementation +struct CV_EXPORTS_W Params +{ + /** @brief Default parameters + A set of parameters which provides better model quality, can be very slow. + */ + CV_WRAP static Ptr defaultParams(); - This class implements a 3d reconstruction algorithm described in - @cite kinectfusion paper. + /** @brief Coarse parameters + A set of parameters which provides better speed, can fail to match frames + in case of rapid sensor motion. + */ + CV_WRAP static Ptr coarseParams(); - It takes a sequence of depth images taken from depth sensor - (or any depth images source such as stereo camera matching algorithm or even raymarching renderer). - The output can be obtained as a vector of points and their normals - or can be Phong-rendered from given camera pose. + enum PlatformType + { - An internal representation of a model is a voxel cube that keeps TSDF values - which are a sort of distances to the surface (for details read the @cite kinectfusion article about TSDF). - There is no interface to that representation yet. + PLATFORM_CPU, PLATFORM_GPU + }; - This implementation is based on (kinfu-remake)[https://github.com/Nerei/kinfu_remake]. -*/ -class CV_EXPORTS KinFu -{ -public: - struct CV_EXPORTS Params - { - /** @brief Default parameters - A set of parameters which provides better model quality, can be very slow. - */ - static Params defaultParams(); + /** @brief A platform on which to run the algorithm. + * + Currently KinFu supports only one platform which is a CPU. + GPU platform is to be implemented in the future. + */ + PlatformType platform; - /** @brief Coarse parameters - A set of parameters which provides better speed, can fail to match frames - in case of rapid sensor motion. - */ - static Params coarseParams(); + /** @brief frame size in pixels */ + CV_PROP_RW Size frameSize; - enum PlatformType - { + /** @brief camera intrinsics */ + CV_PROP Matx33f intr; - PLATFORM_CPU, PLATFORM_GPU - }; + /** @brief pre-scale per 1 meter for input values - /** @brief A platform on which to run the algorithm. - * - Currently KinFu supports only one platform which is a CPU. - GPU platform is to be implemented in the future. - */ - PlatformType platform; + Typical values are: + * 5000 per 1 meter for the 16-bit PNG files of TUM database + * 1 per 1 meter for the 32-bit float images in the ROS bag files + */ + CV_PROP_RW float depthFactor; - /** @brief frame size in pixels */ - Size frameSize; + /** @brief Depth sigma in meters for bilateral smooth */ + CV_PROP_RW float bilateral_sigma_depth; + /** @brief Spatial sigma in pixels for bilateral smooth */ + CV_PROP_RW float bilateral_sigma_spatial; + /** @brief Kernel size in pixels for bilateral smooth */ + CV_PROP_RW int bilateral_kernel_size; - /** @brief camera intrinsics */ - Matx33f intr; + /** @brief Number of pyramid levels for ICP */ + CV_PROP_RW int pyramidLevels; - /** @brief pre-scale per 1 meter for input values + /** @brief Resolution of voxel cube - Typical values are: - * 5000 per 1 meter for the 16-bit PNG files of TUM database - * 1 per 1 meter for the 32-bit float images in the ROS bag files - */ - float depthFactor; + Number of voxels in each cube edge. + */ + CV_PROP_RW int volumeDims; + /** @brief Size of voxel cube side in meters */ + CV_PROP_RW float volumeSize; - /** @brief Depth sigma in meters for bilateral smooth */ - float bilateral_sigma_depth; - /** @brief Spatial sigma in pixels for bilateral smooth */ - float bilateral_sigma_spatial; - /** @brief Kernel size in pixels for bilateral smooth */ - int bilateral_kernel_size; + /** @brief Minimal camera movement in meters - /** @brief Number of pyramid levels for ICP */ - int pyramidLevels; + Integrate new depth frame only if camera movement exceeds this value. + */ + CV_PROP_RW float tsdf_min_camera_movement; - /** @brief Resolution of voxel cube + /** @brief initial volume pose in meters */ + Affine3f volumePose; - Number of voxels in each cube edge. - */ - int volumeDims; - /** @brief Size of voxel cube side in meters */ - float volumeSize; + /** @brief distance to truncate in meters - /** @brief Minimal camera movement in meters + Distances that exceed this value will be truncated in voxel cube values. + */ + CV_PROP_RW float tsdf_trunc_dist; - Integrate new depth frame only if camera movement exceeds this value. - */ - float tsdf_min_camera_movement; + /** @brief max number of frames per voxel - /** @brief initial volume pose in meters */ - Affine3f volumePose; + Each voxel keeps running average of distances no longer than this value. + */ + CV_PROP_RW int tsdf_max_weight; - /** @brief distance to truncate in meters + /** @brief A length of one raycast step - Distances that exceed this value will be truncated in voxel cube values. - */ - float tsdf_trunc_dist; + How much voxel sizes we skip each raycast step + */ + CV_PROP_RW float raycast_step_factor; - /** @brief max number of frames per voxel + // gradient delta in voxel sizes + // fixed at 1.0f + // float gradient_delta_factor; - Each voxel keeps running average of distances no longer than this value. - */ - int tsdf_max_weight; + /** @brief light pose for rendering in meters */ + CV_PROP Vec3f lightPose; - /** @brief A length of one raycast step + /** @brief distance theshold for ICP in meters */ + CV_PROP_RW float icpDistThresh; + /** angle threshold for ICP in radians */ + CV_PROP_RW float icpAngleThresh; + /** number of ICP iterations for each pyramid level */ + CV_PROP std::vector icpIterations; - How much voxel sizes we skip each raycast step - */ - float raycast_step_factor; + // depth truncation is not used by default + // float icp_truncate_depth_dist; //meters +}; - // gradient delta in voxel sizes - // fixed at 1.0f - // float gradient_delta_factor; +/** @brief KinectFusion implementation - /** @brief light pose for rendering in meters */ - Vec3f lightPose; + This class implements a 3d reconstruction algorithm described in + @cite kinectfusion paper. - /** @brief distance theshold for ICP in meters */ - float icpDistThresh; - /** angle threshold for ICP in radians */ - float icpAngleThresh; - /** number of ICP iterations for each pyramid level */ - std::vector icpIterations; + It takes a sequence of depth images taken from depth sensor + (or any depth images source such as stereo camera matching algorithm or even raymarching renderer). + The output can be obtained as a vector of points and their normals + or can be Phong-rendered from given camera pose. - // depth truncation is not used by default - // float icp_truncate_depth_dist; //meters - }; + An internal representation of a model is a voxel cube that keeps TSDF values + which are a sort of distances to the surface (for details read the @cite kinectfusion article about TSDF). + There is no interface to that representation yet. - KinFu(const Params& _params); + This implementation is based on (kinfu-remake)[https://github.com/Nerei/kinfu_remake]. +*/ +class CV_EXPORTS_W KinFu +{ +public: + CV_WRAP static Ptr create(const Ptr& _params); virtual ~KinFu(); /** @brief Get current parameters */ - const Params& getParams() const; - void setParams(const Params&); + virtual const Params& getParams() const = 0; + virtual void setParams(const Params&) = 0; /** @brief Renders a volume into an image @@ -154,7 +154,7 @@ public: which is a last frame camera pose. */ - void render(OutputArray image, const Affine3f cameraPose = Affine3f::Identity()) const; + CV_WRAP virtual void render(OutputArray image, const Matx44f& cameraPose = Matx44f::eye()) const = 0; /** @brief Gets points and normals of current 3d mesh @@ -164,7 +164,7 @@ public: @param points vector of points which are 4-float vectors @param normals vector of normals which are 4-float vectors */ - void getCloud(OutputArray points, OutputArray normals) const; + CV_WRAP virtual void getCloud(OutputArray points, OutputArray normals) const = 0; /** @brief Gets points of current 3d mesh @@ -172,22 +172,22 @@ public: @param points vector of points which are 4-float vectors */ - void getPoints(OutputArray points) const; + CV_WRAP virtual void getPoints(OutputArray points) const = 0; /** @brief Calculates normals for given points @param points input vector of points which are 4-float vectors @param normals output vector of corresponding normals which are 4-float vectors */ - void getNormals(InputArray points, OutputArray normals) const; + CV_WRAP virtual void getNormals(InputArray points, OutputArray normals) const = 0; /** @brief Resets the algorithm Clears current model and resets a pose. */ - void reset(); + CV_WRAP virtual void reset() = 0; /** @brief Get current pose in voxel cube space */ - const Affine3f getPose() const; + virtual const Affine3f getPose() const = 0; /** @brief Process next depth frame @@ -197,12 +197,10 @@ public: @param depth one-channel image which size and depth scale is described in algorithm's parameters @return true if succeded to align new frame with current scene, false if opposite */ - bool update(InputArray depth); + CV_WRAP virtual bool update(InputArray depth) = 0; private: - class KinFuImpl; - cv::Ptr impl; }; //! @} diff --git a/modules/rgbd/samples/kinfu_demo.cpp b/modules/rgbd/samples/kinfu_demo.cpp index b42cf46f5..55cd69891 100644 --- a/modules/rgbd/samples/kinfu_demo.cpp +++ b/modules/rgbd/samples/kinfu_demo.cpp @@ -10,14 +10,14 @@ #include #include -#ifdef HAVE_OPENCV_VIZ - -#include - using namespace cv; using namespace cv::kinfu; using namespace std; +#ifdef HAVE_OPENCV_VIZ +#include +#endif + static vector readDepth(std::string fileList); static vector readDepth(std::string fileList) @@ -113,7 +113,7 @@ public: return depthFileList.empty() && !(vc.isOpened()); } - void updateParams(KinFu::Params& params) + void updateParams(Params& params) { if (vc.isOpened()) { @@ -143,6 +143,7 @@ public: bool useKinect2Workarounds; }; +#ifdef HAVE_OPENCV_VIZ const std::string vizWindowName = "cloud"; struct PauseCallbackArgs @@ -163,11 +164,12 @@ void pauseCallback(const viz::MouseEvent& me, void* args) PauseCallbackArgs pca = *((PauseCallbackArgs*)(args)); viz::Viz3d window(vizWindowName); Mat rendered; - pca.kf.render(rendered, window.getViewerPose()); + pca.kf.render(rendered, window.getViewerPose().matrix); imshow("render", rendered); waitKey(1); } } +#endif static const char* keys = { @@ -220,23 +222,26 @@ int main(int argc, char **argv) return -1; } - KinFu::Params params; + Ptr params; if(coarse) - params = KinFu::Params::coarseParams(); + params = Params::coarseParams(); else - params = KinFu::Params::defaultParams(); + params = Params::defaultParams(); // These params can be different for each depth sensor - ds.updateParams(params); + ds.updateParams(*params); // Scene-specific params should be tuned for each scene individually //params.volumePose = params.volumePose.translate(Vec3f(0.f, 0.f, 0.5f)); //params.tsdf_max_weight = 16; - KinFu kf(params); + Ptr kf = KinFu::create(params); +#ifdef HAVE_OPENCV_VIZ cv::viz::Viz3d window(vizWindowName); window.setViewerPose(Affine3f::Identity()); + bool pause = false; +#endif // TODO: can we use UMats for that? Mat rendered; @@ -245,13 +250,12 @@ int main(int argc, char **argv) int64 prevTime = getTickCount(); - bool pause = false; - for(Mat frame = ds.getDepth(); !frame.empty(); frame = ds.getDepth()) { +#ifdef HAVE_OPENCV_VIZ if(pause) { - kf.getCloud(points, normals); + kf->getCloud(points, normals); if(!points.empty() && !normals.empty()) { viz::WCloud cloudWidget(points, viz::Color::white()); @@ -260,9 +264,9 @@ int main(int argc, char **argv) window.showWidget("normals", cloudNormals); window.showWidget("cube", viz::WCube(Vec3d::all(0), - Vec3d::all(kf.getParams().volumeSize)), - kf.getParams().volumePose); - PauseCallbackArgs pca(kf); + Vec3d::all(kf->getParams().volumeSize)), + kf->getParams().volumePose); + PauseCallbackArgs pca(*kf); window.registerMouseCallback(pauseCallback, (void*)&pca); window.showWidget("text", viz::WText(cv::String("Move camera in this window. " "Close the window or press Q to resume"), Point())); @@ -274,22 +278,24 @@ int main(int argc, char **argv) pause = false; } else +#endif { Mat cvt8; - float depthFactor = kf.getParams().depthFactor; + float depthFactor = kf->getParams().depthFactor; convertScaleAbs(frame, cvt8, 0.25*256. / depthFactor); imshow("depth", cvt8); - if(!kf.update(frame)) + if(!kf->update(frame)) { - kf.reset(); + kf->reset(); std::cout << "reset" << std::endl; } +#ifdef HAVE_OPENCV_VIZ else { if(coarse) { - kf.getCloud(points, normals); + kf->getCloud(points, normals); if(!points.empty() && !normals.empty()) { viz::WCloud cloudWidget(points, viz::Color::white()); @@ -301,13 +307,14 @@ int main(int argc, char **argv) //window.showWidget("worldAxes", viz::WCoordinateSystem()); window.showWidget("cube", viz::WCube(Vec3d::all(0), - Vec3d::all(kf.getParams().volumeSize)), - kf.getParams().volumePose); - window.setViewerPose(kf.getPose()); + Vec3d::all(kf->getParams().volumeSize)), + kf->getParams().volumePose); + window.setViewerPose(kf->getPose()); window.spinOnce(1, true); } +#endif - kf.render(rendered); + kf->render(rendered); } int64 newTime = getTickCount(); @@ -322,12 +329,14 @@ int main(int argc, char **argv) switch (c) { case 'r': - kf.reset(); + kf->reset(); break; case 'q': return 0; +#ifdef HAVE_OPENCV_VIZ case 'p': pause = true; +#endif default: break; } @@ -335,12 +344,3 @@ int main(int argc, char **argv) return 0; } - -#else - -int main(int /* argc */, char ** /* argv */) -{ - std::cout << "This demo requires viz module" << std::endl; - return 0; -} -#endif diff --git a/modules/rgbd/src/fast_icp.cpp b/modules/rgbd/src/fast_icp.cpp index 342170b27..a58205564 100644 --- a/modules/rgbd/src/fast_icp.cpp +++ b/modules/rgbd/src/fast_icp.cpp @@ -500,15 +500,15 @@ bool ICPGPU::estimateTransform(cv::Affine3f& /*transform*/, cv::Ptr /*_ol throw std::runtime_error("Not implemented"); } -cv::Ptr makeICP(cv::kinfu::KinFu::Params::PlatformType t, +cv::Ptr makeICP(cv::kinfu::Params::PlatformType t, const cv::kinfu::Intr _intrinsics, const std::vector &_iterations, float _angleThreshold, float _distanceThreshold) { switch (t) { - case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_CPU: + case cv::kinfu::Params::PlatformType::PLATFORM_CPU: return cv::makePtr(_intrinsics, _iterations, _angleThreshold, _distanceThreshold); - case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_GPU: + case cv::kinfu::Params::PlatformType::PLATFORM_GPU: return cv::makePtr(_intrinsics, _iterations, _angleThreshold, _distanceThreshold); default: return cv::Ptr(); diff --git a/modules/rgbd/src/fast_icp.hpp b/modules/rgbd/src/fast_icp.hpp index 8d31351e8..d036e9074 100644 --- a/modules/rgbd/src/fast_icp.hpp +++ b/modules/rgbd/src/fast_icp.hpp @@ -30,7 +30,7 @@ protected: cv::kinfu::Intr intrinsics; }; -cv::Ptr makeICP(cv::kinfu::KinFu::Params::PlatformType t, +cv::Ptr makeICP(cv::kinfu::Params::PlatformType t, const cv::kinfu::Intr _intrinsics, const std::vector &_iterations, float _angleThreshold, float _distanceThreshold); diff --git a/modules/rgbd/src/kinfu.cpp b/modules/rgbd/src/kinfu.cpp index 62ca933d3..99fa8257c 100644 --- a/modules/rgbd/src/kinfu.cpp +++ b/modules/rgbd/src/kinfu.cpp @@ -12,29 +12,29 @@ namespace cv { namespace kinfu { -class KinFu::KinFuImpl +class KinFu::KinFuImpl : public KinFu { public: - KinFuImpl(const KinFu::Params& _params); + KinFuImpl(const Params& _params); virtual ~KinFuImpl(); - const KinFu::Params& getParams() const; - void setParams(const KinFu::Params&); + const Params& getParams() const CV_OVERRIDE; + void setParams(const Params&) CV_OVERRIDE; - void render(OutputArray image, const Affine3f cameraPose = Affine3f::Identity()) const; + void render(OutputArray image, const Matx44f& cameraPose) const CV_OVERRIDE; - void getCloud(OutputArray points, OutputArray normals) const; - void getPoints(OutputArray points) const; - void getNormals(InputArray points, OutputArray normals) const; + void getCloud(OutputArray points, OutputArray normals) const CV_OVERRIDE; + void getPoints(OutputArray points) const CV_OVERRIDE; + void getNormals(InputArray points, OutputArray normals) const CV_OVERRIDE; - void reset(); + void reset() CV_OVERRIDE; - const Affine3f getPose() const; + const Affine3f getPose() const CV_OVERRIDE; - bool update(InputArray depth); + bool update(InputArray depth) CV_OVERRIDE; private: - KinFu::Params params; + Params params; cv::Ptr frameGenerator; cv::Ptr icp; @@ -45,7 +45,7 @@ private: cv::Ptr frame; }; -KinFu::Params KinFu::Params::defaultParams() +Ptr Params::defaultParams() { Params p; @@ -107,36 +107,36 @@ KinFu::Params KinFu::Params::defaultParams() // depth truncation is not used by default //p.icp_truncate_depth_dist = 0.f; //meters, disabled - return p; + return makePtr(p); } -KinFu::Params KinFu::Params::coarseParams() +Ptr Params::coarseParams() { - Params p = defaultParams(); + Ptr p = defaultParams(); // first non-zero numbers are accepted const int iters[] = {5, 3, 2}; - p.icpIterations.clear(); + p->icpIterations.clear(); for(size_t i = 0; i < sizeof(iters)/sizeof(int); i++) { if(iters[i]) { - p.icpIterations.push_back(iters[i]); + p->icpIterations.push_back(iters[i]); } else break; } - p.pyramidLevels = (int)p.icpIterations.size(); + p->pyramidLevels = (int)p->icpIterations.size(); - p.volumeDims = 128; //number of voxels + p->volumeDims = 128; //number of voxels - p.raycast_step_factor = 0.75f; //in voxel sizes + p->raycast_step_factor = 0.75f; //in voxel sizes return p; } -KinFu::KinFuImpl::KinFuImpl(const KinFu::Params &_params) : +KinFu::KinFuImpl::KinFuImpl(const Params &_params) : params(_params), frameGenerator(makeFrameGenerator(params.platform)), icp(makeICP(params.platform, params.intr, params.icpIterations, params.icpAngleThresh, params.icpDistThresh)), @@ -160,12 +160,12 @@ KinFu::KinFuImpl::~KinFuImpl() } -const KinFu::Params& KinFu::KinFuImpl::getParams() const +const Params& KinFu::KinFuImpl::getParams() const { return params; } -void KinFu::KinFuImpl::setParams(const KinFu::Params& p) +void KinFu::KinFuImpl::setParams(const Params& p) { params = p; } @@ -225,10 +225,12 @@ bool KinFu::KinFuImpl::update(InputArray _depth) } -void KinFu::KinFuImpl::render(OutputArray image, const Affine3f cameraPose) const +void KinFu::KinFuImpl::render(OutputArray image, const Matx44f& _cameraPose) const { ScopeTime st("kinfu render"); + Affine3f cameraPose(_cameraPose); + const Affine3f id = Affine3f::Identity(); if((cameraPose.rotation() == pose.rotation() && cameraPose.translation() == pose.translation()) || (cameraPose.rotation() == id.rotation() && cameraPose.translation() == id.translation())) @@ -263,57 +265,12 @@ void KinFu::KinFuImpl::getNormals(InputArray points, OutputArray normals) const // importing class -KinFu::KinFu(const Params& _params) -{ - impl = makePtr(_params); -} - -KinFu::~KinFu() { } - -const KinFu::Params& KinFu::getParams() const +Ptr KinFu::create(const Ptr& _params) { - return impl->getParams(); + return makePtr(*_params); } -void KinFu::setParams(const Params& p) -{ - impl->setParams(p); -} - -const Affine3f KinFu::getPose() const -{ - return impl->getPose(); -} - -void KinFu::reset() -{ - impl->reset(); -} - -void KinFu::getCloud(cv::OutputArray points, cv::OutputArray normals) const -{ - impl->getCloud(points, normals); -} - -void KinFu::getPoints(OutputArray points) const -{ - impl->getPoints(points); -} - -void KinFu::getNormals(InputArray points, OutputArray normals) const -{ - impl->getNormals(points, normals); -} - -bool KinFu::update(InputArray depth) -{ - return impl->update(depth); -} - -void KinFu::render(cv::OutputArray image, const Affine3f cameraPose) const -{ - impl->render(image, cameraPose); -} +KinFu::~KinFu() {} } // namespace kinfu } // namespace cv diff --git a/modules/rgbd/src/kinfu_frame.cpp b/modules/rgbd/src/kinfu_frame.cpp index 74d37b476..eef81b3cc 100644 --- a/modules/rgbd/src/kinfu_frame.cpp +++ b/modules/rgbd/src/kinfu_frame.cpp @@ -442,13 +442,13 @@ void FrameGPU::getDepth(OutputArray /* depth */) const throw std::runtime_error("Not implemented"); } -cv::Ptr makeFrameGenerator(cv::kinfu::KinFu::Params::PlatformType t) +cv::Ptr makeFrameGenerator(cv::kinfu::Params::PlatformType t) { switch (t) { - case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_CPU: + case cv::kinfu::Params::PlatformType::PLATFORM_CPU: return cv::makePtr(); - case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_GPU: + case cv::kinfu::Params::PlatformType::PLATFORM_GPU: return cv::makePtr(); default: return cv::Ptr(); diff --git a/modules/rgbd/src/kinfu_frame.hpp b/modules/rgbd/src/kinfu_frame.hpp index 572bf5098..02c281d2a 100644 --- a/modules/rgbd/src/kinfu_frame.hpp +++ b/modules/rgbd/src/kinfu_frame.hpp @@ -115,7 +115,7 @@ public: virtual ~FrameGenerator() {} }; -cv::Ptr makeFrameGenerator(cv::kinfu::KinFu::Params::PlatformType t); +cv::Ptr makeFrameGenerator(cv::kinfu::Params::PlatformType t); } // namespace kinfu } // namespace cv diff --git a/modules/rgbd/src/odometry.cpp b/modules/rgbd/src/odometry.cpp index 9270873bd..52bd3486a 100755 --- a/modules/rgbd/src/odometry.cpp +++ b/modules/rgbd/src/odometry.cpp @@ -1482,7 +1482,7 @@ Size FastICPOdometry::prepareFrameCache(Ptr& frame, int cacheType // mask isn't used by FastICP - Ptr fg = makeFrameGenerator(KinFu::Params::PlatformType::PLATFORM_CPU); + Ptr fg = makeFrameGenerator(Params::PlatformType::PLATFORM_CPU); Ptr f = (*fg)().dynamicCast(); Intr intr(cameraMatrix); float depthFactor = 1.f; // user should rescale depth manually @@ -1517,7 +1517,7 @@ bool FastICPOdometry::computeImpl(const Ptr& srcFrame, { kinfu::Intr intr(cameraMatrix); std::vector iterations = iterCounts; - Ptr icp = kinfu::makeICP(kinfu::KinFu::Params::PlatformType::PLATFORM_CPU, + Ptr icp = kinfu::makeICP(kinfu::Params::PlatformType::PLATFORM_CPU, intr, iterations, angleThreshold, diff --git a/modules/rgbd/src/tsdf.cpp b/modules/rgbd/src/tsdf.cpp index 384072797..19560e985 100644 --- a/modules/rgbd/src/tsdf.cpp +++ b/modules/rgbd/src/tsdf.cpp @@ -1199,16 +1199,16 @@ void TSDFVolumeGPU::fetchPointsNormals(OutputArray /*points*/, OutputArray /*nor throw std::runtime_error("Not implemented"); } -cv::Ptr makeTSDFVolume(cv::kinfu::KinFu::Params::PlatformType t, +cv::Ptr makeTSDFVolume(cv::kinfu::Params::PlatformType t, int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, float _raycastStepFactor) { switch (t) { - case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_CPU: + case cv::kinfu::Params::PlatformType::PLATFORM_CPU: return cv::makePtr(_res, _size, _pose, _truncDist, _maxWeight, _raycastStepFactor); - case cv::kinfu::KinFu::Params::PlatformType::PLATFORM_GPU: + case cv::kinfu::Params::PlatformType::PLATFORM_GPU: return cv::makePtr(_res, _size, _pose, _truncDist, _maxWeight, _raycastStepFactor); default: diff --git a/modules/rgbd/src/tsdf.hpp b/modules/rgbd/src/tsdf.hpp index 41b4f8b37..f4008ac11 100644 --- a/modules/rgbd/src/tsdf.hpp +++ b/modules/rgbd/src/tsdf.hpp @@ -38,7 +38,7 @@ public: cv::Affine3f pose; }; -cv::Ptr makeTSDFVolume(cv::kinfu::KinFu::Params::PlatformType t, +cv::Ptr makeTSDFVolume(cv::kinfu::Params::PlatformType t, int _res, float _size, cv::Affine3f _pose, float _truncDist, int _maxWeight, float _raycastStepFactor); diff --git a/modules/rgbd/test/test_kinfu.cpp b/modules/rgbd/test/test_kinfu.cpp index 9bb104a7e..16bba6776 100644 --- a/modules/rgbd/test/test_kinfu.cpp +++ b/modules/rgbd/test/test_kinfu.cpp @@ -262,12 +262,11 @@ static const bool display = false; TEST( KinectFusion, lowDense ) { - kinfu::KinFu::Params params; - params = kinfu::KinFu::Params::coarseParams(); + Ptr params = kinfu::Params::coarseParams(); - RotatingScene scene(params.frameSize, params.intr, params.depthFactor); + RotatingScene scene(params->frameSize, params->intr, params->depthFactor); - kinfu::KinFu kf(params); + Ptr kf = kinfu::KinFu::create(params); std::vector poses = scene.getPoses(); Affine3f startPoseGT = poses[0], startPoseKF; @@ -278,9 +277,9 @@ TEST( KinectFusion, lowDense ) Mat depth = scene.depth(pose); - ASSERT_TRUE(kf.update(depth)); + ASSERT_TRUE(kf->update(depth)); - kfPose = kf.getPose(); + kfPose = kf->getPose(); if(i == 0) startPoseKF = kfPose; @@ -288,9 +287,9 @@ TEST( KinectFusion, lowDense ) if(display) { - imshow("depth", depth*(1.f/params.depthFactor/4.f)); + imshow("depth", depth*(1.f/params->depthFactor/4.f)); Mat rendered; - kf.render(rendered); + kf->render(rendered); imshow("render", rendered); waitKey(10); } @@ -302,12 +301,10 @@ TEST( KinectFusion, lowDense ) TEST( KinectFusion, highDense ) { - kinfu::KinFu::Params params; + Ptr params = kinfu::Params::defaultParams(); + CubeSpheresScene scene(params->frameSize, params->intr, params->depthFactor); - params = kinfu::KinFu::Params::defaultParams(); - CubeSpheresScene scene(params.frameSize, params.intr, params.depthFactor); - - kinfu::KinFu kf(params); + Ptr kf = kinfu::KinFu::create(params); std::vector poses = scene.getPoses(); Affine3f startPoseGT = poses[0], startPoseKF; @@ -318,9 +315,9 @@ TEST( KinectFusion, highDense ) Mat depth = scene.depth(pose); - ASSERT_TRUE(kf.update(depth)); + ASSERT_TRUE(kf->update(depth)); - kfPose = kf.getPose(); + kfPose = kf->getPose(); if(i == 0) startPoseKF = kfPose; @@ -328,9 +325,9 @@ TEST( KinectFusion, highDense ) if(display) { - imshow("depth", depth*(1.f/params.depthFactor/4.f)); + imshow("depth", depth*(1.f/params->depthFactor/4.f)); Mat rendered; - kf.render(rendered); + kf->render(rendered); imshow("render", rendered); waitKey(10); } From 4ea11a088b267c6ef8698994f8066052676f2d39 Mon Sep 17 00:00:00 2001 From: yarglawaldeg Date: Mon, 25 Jun 2018 15:21:50 +0200 Subject: [PATCH 07/97] update structured_edge_detection (#1579) * update structured_edge_detection update structured_edge_detection to read models from updated p. dollar toolbox * Update structured_edge_detection.cpp * Update structured_edge_detection.cpp casting size_t to int --- modules/ximgproc/src/structured_edge_detection.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/modules/ximgproc/src/structured_edge_detection.cpp b/modules/ximgproc/src/structured_edge_detection.cpp index 795dd8d67..b9fd09771 100644 --- a/modules/ximgproc/src/structured_edge_detection.cpp +++ b/modules/ximgproc/src/structured_edge_detection.cpp @@ -801,9 +801,11 @@ protected: {// for j,k in [0;width)x[0;nTreesEval) int currentNode = pIndex[j*nTreesEval + k]; - - int start = __rf.edgeBoundaries[currentNode]; - int finish = __rf.edgeBoundaries[currentNode + 1]; + size_t sizeBoundaries = __rf.edgeBoundaries.size(); + int convertedBoundaries = static_cast(sizeBoundaries); + int nBnds = (convertedBoundaries - 1) / (nTreesNodes * nTrees); + int start = __rf.edgeBoundaries[currentNode * nBnds]; + int finish = __rf.edgeBoundaries[currentNode * nBnds + 1]; if (start == finish) continue; From 0e03fea432d2be41540569cb212879d2264d9719 Mon Sep 17 00:00:00 2001 From: "d.bouron" Date: Mon, 25 Jun 2018 17:10:18 +0200 Subject: [PATCH 08/97] Fix corruption exception in StaticSaliencySpectralResidual In some case, Discrete Fourier Transform in computeSaliencyImpl() returns magnitude matrix which contains zero values. Then, log() returns -inf values and normalization with blur() returns -nan. When computeBinaryMap() is called double free or corruption exception occurs because kmeans() fails to compute distance. Signed-off-by: d.bouron --- .../src/staticSaliencySpectralResidual.cpp | 2 +- modules/saliency/test/test_main.cpp | 41 ++++++++++++++ modules/saliency/test/test_precomp.hpp | 14 +++++ ...test_static_saliency_spectral_residual.cpp | 53 +++++++++++++++++++ 4 files changed, 109 insertions(+), 1 deletion(-) create mode 100644 modules/saliency/test/test_main.cpp create mode 100644 modules/saliency/test/test_precomp.hpp create mode 100644 modules/saliency/test/test_static_saliency_spectral_residual.cpp diff --git a/modules/saliency/src/staticSaliencySpectralResidual.cpp b/modules/saliency/src/staticSaliencySpectralResidual.cpp index 0182822e3..73bb1536d 100644 --- a/modules/saliency/src/staticSaliencySpectralResidual.cpp +++ b/modules/saliency/src/staticSaliencySpectralResidual.cpp @@ -109,7 +109,7 @@ bool StaticSaliencySpectralResidual::computeSaliencyImpl( InputArray image, Outp //-- Get magnitude and phase of frequency spectrum --// cartToPolar( mv.at( 0 ), mv.at( 1 ), magnitude, angle, false ); - log( magnitude, logAmplitude ); + log( magnitude + Scalar( 1 ), logAmplitude ); //-- Blur log amplitude with averaging filter --// blur( logAmplitude, logAmplitude_blur, Size( 3, 3 ), Point( -1, -1 ), BORDER_DEFAULT ); diff --git a/modules/saliency/test/test_main.cpp b/modules/saliency/test/test_main.cpp new file mode 100644 index 000000000..2f16b0cd8 --- /dev/null +++ b/modules/saliency/test/test_main.cpp @@ -0,0 +1,41 @@ +/* +By downloading, copying, installing or using the software you agree to this +license. If you do not agree to this license, do not download, install, +copy or use the software. + + License Agreement + For Open Source Computer Vision Library + (3-clause BSD License) + +Copyright (C) 2013, OpenCV Foundation, all rights reserved. +Third party copyrights are property of their respective owners. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * Neither the names of the copyright holders nor the names of the contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +This software is provided by the copyright holders and contributors "as is" and +any express or implied warranties, including, but not limited to, the implied +warranties of merchantability and fitness for a particular purpose are +disclaimed. In no event shall copyright holders or contributors be liable for +any direct, indirect, incidental, special, exemplary, or consequential damages +(including, but not limited to, procurement of substitute goods or services; +loss of use, data, or profits; or business interruption) however caused +and on any theory of liability, whether in contract, strict liability, +or tort (including negligence or otherwise) arising in any way out of +the use of this software, even if advised of the possibility of such damage. +*/ + +#include "test_precomp.hpp" + +CV_TEST_MAIN("cv") diff --git a/modules/saliency/test/test_precomp.hpp b/modules/saliency/test/test_precomp.hpp new file mode 100644 index 000000000..37332d2d0 --- /dev/null +++ b/modules/saliency/test/test_precomp.hpp @@ -0,0 +1,14 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. +#ifndef __OPENCV_TEST_PRECOMP_HPP__ +#define __OPENCV_TEST_PRECOMP_HPP__ + +#include "opencv2/ts.hpp" +#include "opencv2/saliency.hpp" + +namespace opencv_test { + using namespace saliency; +} + +#endif diff --git a/modules/saliency/test/test_static_saliency_spectral_residual.cpp b/modules/saliency/test/test_static_saliency_spectral_residual.cpp new file mode 100644 index 000000000..ff0f46d54 --- /dev/null +++ b/modules/saliency/test/test_static_saliency_spectral_residual.cpp @@ -0,0 +1,53 @@ +/* +By downloading, copying, installing or using the software you agree to this +license. If you do not agree to this license, do not download, install, +copy or use the software. + + License Agreement + For Open Source Computer Vision Library + (3-clause BSD License) + +Copyright (C) 2013, OpenCV Foundation, all rights reserved. +Third party copyrights are property of their respective owners. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. + + * Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + * Neither the names of the copyright holders nor the names of the contributors + may be used to endorse or promote products derived from this software + without specific prior written permission. + +This software is provided by the copyright holders and contributors "as is" and +any express or implied warranties, including, but not limited to, the implied +warranties of merchantability and fitness for a particular purpose are +disclaimed. In no event shall copyright holders or contributors be liable for +any direct, indirect, incidental, special, exemplary, or consequential damages +(including, but not limited to, procurement of substitute goods or services; +loss of use, data, or profits; or business interruption) however caused +and on any theory of liability, whether in contract, strict liability, +or tort (including negligence or otherwise) arising in any way out of +the use of this software, even if advised of the possibility of such damage. +*/ + +#include "test_precomp.hpp" + +namespace opencv_test { namespace { + +TEST(CV_StaticSaliencySpectralResidual, should_not_contain_nan) +{ + Ptr saliencyAlgorithm = StaticSaliencySpectralResidual::create(); + Mat img = Mat::zeros(cv::Size(1, 1), CV_32F); + Mat saliencyMap; + + saliencyAlgorithm->computeSaliency(img, saliencyMap); + EXPECT_FALSE(std::isnan(saliencyMap.at(0, 0))); +} + +}} // namespace From 0f5d6ae1942870bb1fc4bec9fa086a13f68c48d5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Dietrich=20B=C3=BCsching?= Date: Fri, 6 Jul 2018 22:39:41 +0200 Subject: [PATCH 09/97] Merge pull request #1672 from dbuesching:rl_morphology * run length morphology * remove unused code, avoid warnings for undefined functions * handle empty input in getBoundingRectangle correctly, remove unused operations * changes according to code review --- modules/ximgproc/README.md | 1 + modules/ximgproc/doc/ximgproc.bib | 10 + modules/ximgproc/include/opencv2/ximgproc.hpp | 21 + .../ximgproc/run_length_morphology.hpp | 119 +++ .../perf/perf_run_length_morphology.cpp | 37 + .../samples/run_length_morphology_demo.cpp | 246 ++++++ .../ximgproc/src/run_length_morphology.cpp | 812 ++++++++++++++++++ .../test/test_run_length_morphology.cpp | 249 ++++++ 8 files changed, 1495 insertions(+) create mode 100644 modules/ximgproc/include/opencv2/ximgproc/run_length_morphology.hpp create mode 100644 modules/ximgproc/perf/perf_run_length_morphology.cpp create mode 100644 modules/ximgproc/samples/run_length_morphology_demo.cpp create mode 100644 modules/ximgproc/src/run_length_morphology.cpp create mode 100644 modules/ximgproc/test/test_run_length_morphology.cpp diff --git a/modules/ximgproc/README.md b/modules/ximgproc/README.md index 598a07667..59e744e02 100644 --- a/modules/ximgproc/README.md +++ b/modules/ximgproc/README.md @@ -15,3 +15,4 @@ Extended Image Processing - Deriche Filter - Pei&Lin Normalization - Ridge Detection Filter +- Binary morphology on run-length encoded images diff --git a/modules/ximgproc/doc/ximgproc.bib b/modules/ximgproc/doc/ximgproc.bib index d6fa3d580..43b6d2de2 100644 --- a/modules/ximgproc/doc/ximgproc.bib +++ b/modules/ximgproc/doc/ximgproc.bib @@ -288,3 +288,13 @@ year={1977}, publisher={IEEE Computer Society} } + +@inproceedings{Breuel2008, + title = {Binary Morphology and Related Operations on Run-Length Representations.}, + author = {Breuel, Thomas}, + year = {2008}, + month = {01}, + pages = {159-166}, + volume = {1}, + booktitle = {VISAPP 2008 - 3rd International Conference on Computer Vision Theory and Applications, Proceedings} +} diff --git a/modules/ximgproc/include/opencv2/ximgproc.hpp b/modules/ximgproc/include/opencv2/ximgproc.hpp index 062fcd2ce..874bf63e0 100644 --- a/modules/ximgproc/include/opencv2/ximgproc.hpp +++ b/modules/ximgproc/include/opencv2/ximgproc.hpp @@ -56,6 +56,7 @@ #include "ximgproc/fourier_descriptors.hpp" #include "ximgproc/ridgefilter.hpp" #include "ximgproc/brightedges.hpp" +#include "ximgproc/run_length_morphology.hpp" /** @defgroup ximgproc Extended Image Processing @@ -76,6 +77,26 @@ i.e. algorithms which somehow takes into account pixel affinities in natural ima @defgroup ximgproc_fast_line_detector Fast line detector @defgroup ximgproc_fourier Fourier descriptors + + @defgroup ximgproc_run_length_morphology Binary morphology on run-length encoded image + + These functions support morphological operations on binary images. In order to be fast and space efficient binary images are encoded with a run-length representation. + This representation groups continuous horizontal sequences of "on" pixels together in a "run". A run is charactarized by the column position of the first pixel in the run, the column + position of the last pixel in the run and the row position. This representation is very compact for binary images which contain large continuous areas of "on" and "off" pixels. A checkerboard + pattern would be a good example. The representation is not so suitable for binary images created from random noise images or other images where little correlation between neighboring pixels + exists. + + The morphological operations supported here are very similar to the operations supported in the imgproc module. In general they are fast. However on several occasions they are slower than the functions + from imgproc. The structuring elements of cv::MORPH_RECT and cv::MORPH_CROSS have very good support from the imgproc module. Also small structuring elements are very fast in imgproc (presumably + due to opencl support). Therefore the functions from this module are recommended for larger structuring elements (cv::MORPH_ELLIPSE or self defined structuring elements). A sample application + (run_length_morphology_demo) is supplied which allows to compare the speed of some morphological operations for the functions using run-length encoding and the imgproc functions for a given image. + + Run length encoded images are stored in standard opencv images. Images have a single column of cv::Point3i elements. The number of rows is the number of run + 1. The first row contains + the size of the original (not encoded) image. For the runs the following mapping is used (x: column begin, y: column end (last column), z: row). + + The size of the original image is required for compatiblity with the imgproc functions when the boundary handling requires that pixel outside the image boundary are + "on". + @} */ diff --git a/modules/ximgproc/include/opencv2/ximgproc/run_length_morphology.hpp b/modules/ximgproc/include/opencv2/ximgproc/run_length_morphology.hpp new file mode 100644 index 000000000..5754691a2 --- /dev/null +++ b/modules/ximgproc/include/opencv2/ximgproc/run_length_morphology.hpp @@ -0,0 +1,119 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. + +#ifndef __OPENCV_RUN_LENGTH_MORPHOLOGY_HPP__ +#define __OPENCV_RUN_LENGTH_MORPHOLOGY_HPP__ + +#include + +namespace cv { +namespace ximgproc { +namespace rl { + + +//! @addtogroup ximgproc_run_length_morphology +//! @{ + +/** +* @brief Applies a fixed-level threshold to each array element. +* +* +* @param src input array (single-channel). +* @param rlDest resulting run length encoded image. +* @param thresh threshold value. +* @param type thresholding type (only cv::THRESH_BINARY and cv::THRESH_BINARY_INV are supported) +* +*/ +CV_EXPORTS void threshold(InputArray src, OutputArray rlDest, double thresh, int type); + + +/** +* @brief Dilates an run-length encoded binary image by using a specific structuring element. +* +* +* @param rlSrc input image +* @param rlDest result +* @param rlKernel kernel +* @param anchor position of the anchor within the element; default value (0, 0) +* is usually the element center. +* +*/ +CV_EXPORTS void dilate(InputArray rlSrc, OutputArray rlDest, InputArray rlKernel, Point anchor = Point(0, 0)); + +/** +* @brief Erodes an run-length encoded binary image by using a specific structuring element. +* +* +* @param rlSrc input image +* @param rlDest result +* @param rlKernel kernel +* @param bBoundaryOn indicates whether pixel outside the image boundary are assumed to be on + (True: works in the same way as the default of cv::erode, False: is a little faster) +* @param anchor position of the anchor within the element; default value (0, 0) +* is usually the element center. +* +*/ +CV_EXPORTS void erode(InputArray rlSrc, OutputArray rlDest, InputArray rlKernel, + bool bBoundaryOn = true, Point anchor = Point(0, 0)); + +/** +* @brief Returns a run length encoded structuring element of the specified size and shape. +* +* +* @param shape Element shape that can be one of cv::MorphShapes +* @param ksize Size of the structuring element. +* +*/ +CV_EXPORTS cv::Mat getStructuringElement(int shape, Size ksize); + +/** +* @brief Paint run length encoded binary image into an image. +* +* +* @param image image to paint into (currently only single channel images). +* @param rlSrc run length encoded image +* @param value all foreground pixel of the binary image are set to this value +* +*/ +CV_EXPORTS void paint(InputOutputArray image, InputArray rlSrc, const cv::Scalar& value); + +/** +* @brief Check whether a custom made structuring element can be used with run length morphological operations. +* (It must consist of a continuous array of single runs per row) +* +* @param rlStructuringElement mask to be tested +*/ +CV_EXPORTS bool isRLMorphologyPossible(InputArray rlStructuringElement); + +/** +* @brief Creates a run-length encoded image from a vector of runs (column begin, column end, row) +* +* @param runs vector of runs +* @param res result +* @param size image size (to be used if an "on" boundary should be used in erosion, using the default +* means that the size is computed from the extension of the input) +*/ +CV_EXPORTS void createRLEImage(std::vector& runs, OutputArray res, Size size = Size(0, 0)); + +/** +* @brief Applies a morphological operation to a run-length encoded binary image. +* +* +* @param rlSrc input image +* @param rlDest result +* @param op all operations supported by cv::morphologyEx (except cv::MORPH_HITMISS) +* @param rlKernel kernel +* @param bBoundaryOnForErosion indicates whether pixel outside the image boundary are assumed +* to be on for erosion operations (True: works in the same way as the default of cv::erode, +* False: is a little faster) +* @param anchor position of the anchor within the element; default value (0, 0) is usually the element center. +* +*/ +CV_EXPORTS void morphologyEx(InputArray rlSrc, OutputArray rlDest, int op, InputArray rlKernel, + bool bBoundaryOnForErosion = true, Point anchor = Point(0,0)); + +} +} +} +#endif diff --git a/modules/ximgproc/perf/perf_run_length_morphology.cpp b/modules/ximgproc/perf/perf_run_length_morphology.cpp new file mode 100644 index 000000000..7ab542d8d --- /dev/null +++ b/modules/ximgproc/perf/perf_run_length_morphology.cpp @@ -0,0 +1,37 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. +#include "perf_precomp.hpp" + +namespace opencv_test { +namespace { + +typedef tuple RLParams; + +typedef TestBaseWithParam RLMorphologyPerfTest; + +PERF_TEST_P(RLMorphologyPerfTest, perf, Combine(Values(1,7, 21), Values(sz720p, sz2160p), + Values(MORPH_ERODE, MORPH_DILATE, MORPH_OPEN, MORPH_CLOSE, MORPH_GRADIENT,MORPH_TOPHAT, MORPH_BLACKHAT))) +{ + RLParams params = GetParam(); + int seSize = get<0>(params); + Size sz = get<1>(params); + int op = get<2>(params); + + Mat src(sz, CV_8U); + Mat thresholded, dstRLE; + Mat se = rl::getStructuringElement(MORPH_ELLIPSE, cv::Size(2 * seSize + 1, 2 * seSize + 1)); + + declare.in(src, WARMUP_RNG); + + TEST_CYCLE_N(4) + { + rl::threshold(src, thresholded, 100.0, THRESH_BINARY); + rl::morphologyEx(thresholded, dstRLE, op, se); + } + + SANITY_CHECK_NOTHING(); +} + +} +} // namespace \ No newline at end of file diff --git a/modules/ximgproc/samples/run_length_morphology_demo.cpp b/modules/ximgproc/samples/run_length_morphology_demo.cpp new file mode 100644 index 000000000..37056c2f9 --- /dev/null +++ b/modules/ximgproc/samples/run_length_morphology_demo.cpp @@ -0,0 +1,246 @@ +#include + +#include "opencv2/imgproc.hpp" +#include "opencv2/ximgproc.hpp" +#include "opencv2/imgcodecs.hpp" +#include "opencv2/highgui.hpp" + +using namespace std; +using namespace cv; +using namespace cv::ximgproc; + +// Adapted from cv_timer in cv_utilities +class Timer +{ +public: + Timer() : start_(0), time_(0) {} + + void start() + { + start_ = cv::getTickCount(); + } + + void stop() + { + CV_Assert(start_ != 0); + int64 end = cv::getTickCount(); + time_ += end - start_; + start_ = 0; + } + + double time() + { + double ret = time_ / cv::getTickFrequency(); + time_ = 0; + return ret; + } + +private: + int64 start_, time_; +}; + +static void help() +{ + +printf("\nAllows to estimate the efficiency of the morphology operations implemented\n" + "in ximgproc/run_length_morphology.cpp\n" + "Call:\n example_ximgproc_run_length_morphology_demo [image] -u=factor_upscaling image\n" + "Similar to the morphology2 sample of the main opencv library it shows the use\n" + "of rect, ellipse and cross kernels\n\n" + "As rectangular and cross-shaped structuring elements are highly optimized in opencv_imgproc module,\n" + "only with elliptical structuring elements a speedup is possible (e.g. for larger circles).\n" + "Run-length morphology has advantages for larger images.\n" + "You can verify this by upscaling your input with e.g. -u=2\n"); +printf( "Hot keys: \n" + "\tESC - quit the program\n" + "\tr - use rectangle structuring element\n" + "\te - use elliptic structuring element\n" + "\tc - use cross-shaped structuring element\n" + "\tSPACE - loop through all the options\n" ); +} + +static void print_introduction() +{ + printf("\nFirst select a threshold for binarization.\n" + "Then move the sliders for erosion/dilation or open/close operation\n\n" + "The ratio between the time of the execution from opencv_imgproc\n" + "and the code using run-length encoding will be displayed in the console\n\n"); +} + +Mat src, dst; + +int element_shape = MORPH_ELLIPSE; + +//the address of variable which receives trackbar position update +int max_size = 40; +int open_close_pos = 0; +int erode_dilate_pos = 0; +int nThreshold = 100; +cv::Mat binaryImage; +cv::Mat binaryRLE, dstRLE; +cv::Mat rlePainted; + +static void PaintRLEToImage(cv::Mat& rleImage, cv::Mat& res, unsigned char uValue) +{ + res = cv::Scalar(0); + rl::paint(res, rleImage, Scalar((double) uValue)); +} + + +static bool AreImagesIdentical(cv::Mat& image1, cv::Mat& image2) +{ + cv::Mat diff; + cv::absdiff(image1, image2, diff); + int nDiff = cv::countNonZero(diff); + return (nDiff == 0); +} + +// callback function for open/close trackbar +static void OpenClose(int, void*) +{ + int n = open_close_pos - max_size; + int an = n > 0 ? n : -n; + Mat element = getStructuringElement(element_shape, Size(an*2+1, an*2+1), Point(an, an) ); + Timer timer; + timer.start(); + if( n < 0 ) + morphologyEx(binaryImage, dst, MORPH_OPEN, element); + else + morphologyEx(binaryImage, dst, MORPH_CLOSE, element); + timer.stop(); + double imgproc_duration = timer.time(); + + element = rl::getStructuringElement(element_shape, Size(an * 2 + 1, an * 2 + 1)); + + Timer timer2; + timer2.start(); + if (n < 0) + rl::morphologyEx(binaryRLE, dstRLE, MORPH_OPEN, element, true); + else + rl::morphologyEx(binaryRLE, dstRLE, MORPH_CLOSE, element, true); + + timer2.stop(); + double rl_duration = timer2.time(); + cout << "ratio open/close duration: " << rl_duration / imgproc_duration << " (run-length: " + << rl_duration << ", pixelwise: " << imgproc_duration << " )" << std::endl; + + PaintRLEToImage(dstRLE, rlePainted, (unsigned char)255); + if (!AreImagesIdentical(dst, rlePainted)) + { + cout << "error result image are not identical" << endl; + } + + imshow("Open/Close", rlePainted); +} + +// callback function for erode/dilate trackbar +static void ErodeDilate(int, void*) +{ + int n = erode_dilate_pos - max_size; + int an = n > 0 ? n : -n; + Mat element = getStructuringElement(element_shape, Size(an*2+1, an*2+1), Point(an, an) ); + Timer timer; + timer.start(); + if( n < 0 ) + erode(binaryImage, dst, element); + else + dilate(binaryImage, dst, element); + timer.stop(); + double imgproc_duration = timer.time(); + + element = rl::getStructuringElement(element_shape, Size(an*2+1, an*2+1)); + + Timer timer2; + timer2.start(); + if( n < 0 ) + rl::erode(binaryRLE, dstRLE, element, true); + else + rl::dilate(binaryRLE, dstRLE, element); + timer2.stop(); + double rl_duration = timer2.time(); + + PaintRLEToImage(dstRLE, rlePainted, (unsigned char)255); + cout << "ratio erode/dilate duration: " << rl_duration / imgproc_duration << + " (run-length: " << rl_duration << ", pixelwise: " << imgproc_duration << " )" << std::endl; + + if (!AreImagesIdentical(dst, rlePainted)) + { + cout << "error result image are not identical" << endl; + } + + imshow("Erode/Dilate", rlePainted); +} + +static void OnChangeThreshold(int, void*) +{ + threshold(src, binaryImage, (double) nThreshold, 255.0, THRESH_BINARY ); + rl::threshold(src, binaryRLE, (double) nThreshold, THRESH_BINARY); + imshow("Threshold", binaryImage); +} + + +int main( int argc, char** argv ) +{ + cv::CommandLineParser parser(argc, argv, "{help h||}{ @image | ../data/aloeL.jpg | }{u| |}"); + if (parser.has("help")) + { + help(); + return 0; + } + std::string filename = parser.get("@image"); + + cv::Mat srcIn; + if( (srcIn = imread(filename,IMREAD_GRAYSCALE)).empty() ) + { + help(); + return -1; + } + int nScale = 1; + if (parser.has("u")) + { + int theScale = parser.get("u"); + if (theScale > 1) + nScale = theScale; + } + + if (nScale == 1) + src = srcIn; + else + cv::resize(srcIn, src, cv::Size(srcIn.rows * nScale, srcIn.cols * nScale)); + + cout << "scale factor read " << nScale << endl; + + print_introduction(); + + //create windows for output images + namedWindow("Open/Close",1); + namedWindow("Erode/Dilate",1); + namedWindow("Threshold",1); + + open_close_pos = erode_dilate_pos = max_size - 10; + createTrackbar("size s.e.", "Open/Close",&open_close_pos,max_size*2+1,OpenClose); + createTrackbar("size s.e.", "Erode/Dilate",&erode_dilate_pos,max_size*2+1,ErodeDilate); + createTrackbar("threshold", "Threshold",&nThreshold,255, OnChangeThreshold); + OnChangeThreshold(0, 0); + rlePainted.create(cv::Size(src.cols, src.rows), CV_8UC1); + + for(;;) + { + OpenClose(open_close_pos, 0); + ErodeDilate(erode_dilate_pos, 0); + char c = (char)waitKey(0); + + if( c == 27 ) + break; + if( c == 'e' ) + element_shape = MORPH_ELLIPSE; + else if( c == 'r' ) + element_shape = MORPH_RECT; + else if( c == 'c' ) + element_shape = MORPH_CROSS; + else if( c == ' ' ) + element_shape = (element_shape + 1) % 3; + } + + return 0; +} \ No newline at end of file diff --git a/modules/ximgproc/src/run_length_morphology.cpp b/modules/ximgproc/src/run_length_morphology.cpp new file mode 100644 index 000000000..fb9bf76d7 --- /dev/null +++ b/modules/ximgproc/src/run_length_morphology.cpp @@ -0,0 +1,812 @@ +/* + * By downloading, copying, installing or using the software you agree to this license. + * If you do not agree to this license, do not download, install, + * copy or use the software. + * + * + * License Agreement + * For Open Source Computer Vision Library + * (3 - clause BSD License) + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met : + * + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * * Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and / or other materials provided with the distribution. + * + * * Neither the names of the copyright holders nor the names of the contributors + * may be used to endorse or promote products derived from this software + * without specific prior written permission. + * + * This software is provided by the copyright holders and contributors "as is" and + * any express or implied warranties, including, but not limited to, the implied + * warranties of merchantability and fitness for a particular purpose are disclaimed. + * In no event shall copyright holders or contributors be liable for any direct, + * indirect, incidental, special, exemplary, or consequential damages + * (including, but not limited to, procurement of substitute goods or services; + * loss of use, data, or profits; or business interruption) however caused + * and on any theory of liability, whether in contract, strict liability, + * or tort(including negligence or otherwise) arising in any way out of + * the use of this software, even if advised of the possibility of such damage. + */ +#include "precomp.hpp" +#include +#include +#include + + +namespace cv { +namespace ximgproc { +namespace rl { + +struct rlType +{ + int cb, ce, r; + rlType(int cbIn, int ceIn, int rIn): cb(cbIn), ce(ceIn), r(rIn) {} + rlType(): cb(0), ce(0), r(0) {} + bool operator < (const rlType& other) const { if (r < other.r || (r == other.r && cb < other.cb) + || (r == other.r && cb == other.cb && ce < other.ce)) return true; else return false; } +}; + +typedef std::vector rlVec; + +template +void _thresholdLine(T* pData, int nWidth, int nRow, T threshold, int type, rlVec& res) +{ + bool bOn = false; + int nStartSegment = 0; + for (int j = 0; j < nWidth; j++) + { + bool bAboveThreshold = (pData[j] > threshold); + bool bCurOn = (bAboveThreshold == (THRESH_BINARY == type)); + if (!bOn && bCurOn) + { + nStartSegment = j; + bOn = true; + } + else if (bOn && !bCurOn) + { + rlType chord(nStartSegment, j - 1, nRow); + res.push_back(chord); + bOn = false; + } + + } + if (bOn) + { + rlType chord(nStartSegment, nWidth - 1, nRow); + res.push_back(chord); + } +} + +static void _threshold(cv::Mat& img, rlVec& res, double threshold, int type) +{ + res.clear(); + switch (img.depth()) + { + case CV_8U: + for (int i = 0; i < img.rows; ++i) + _thresholdLine(img.ptr(i), img.cols, i, (uchar) threshold, type, res); + break; + case CV_8S: + for (int i = 0; i < img.rows; ++i) + _thresholdLine((schar*) img.ptr(i), img.cols, i, (schar) threshold, type, res); + break; + case CV_16U: + for (int i = 0; i < img.rows; ++i) + { + _thresholdLine((unsigned short*)img.ptr(i), img.cols, i, + (unsigned short)threshold, type, res); + } + break; + case CV_16S: + for (int i = 0; i < img.rows; ++i) + _thresholdLine((short*) img.ptr(i), img.cols, i, (short) threshold, type, res); + break; + case CV_32S: + for (int i = 0; i < img.rows; ++i) + _thresholdLine((int*) img.ptr(i), img.cols, i, (int) threshold, type, res); + break; + case CV_32F: + for (int i = 0; i < img.rows; ++i) + _thresholdLine((float*) img.ptr(i), img.cols, i, (float) threshold, type, res); + break; + case CV_64F: + for (int i = 0; i < img.rows; ++i) + _thresholdLine((double*) img.ptr(i), img.cols, i, threshold, type, res); + break; + default: + CV_Error( CV_StsUnsupportedFormat, "unsupported image type" ); + } +} + + +static void convertToOutputArray(rlVec& runs, Size size, OutputArray& res) +{ + size_t nRuns = runs.size(); + std::vector segments(nRuns + 1); + segments[0] = cv::Point3i(size.width, size.height, 0); + for (size_t i = 0; i < nRuns; ++i) + { + rlType& curRun = runs[i]; + segments[i + 1] = Point3i(curRun.cb, curRun.ce, curRun.r); + } + Mat(segments).copyTo(res); +} + + +CV_EXPORTS void threshold(InputArray src, OutputArray rlDest, double thresh, int type) +{ + CV_INSTRUMENT_REGION(); + + Mat image = src.getMat(); + CV_Assert(!image.empty() && image.channels() == 1); + CV_Assert(type == THRESH_BINARY || type == THRESH_BINARY_INV); + rlVec runs; + _threshold(image, runs, thresh, type); + Size size(image.cols, image.rows); + + convertToOutputArray(runs, size, rlDest); +} + + +template +void paint_impl(cv::Mat& img, rlType* pRuns, int nSize, T value) +{ + int i; + rlType* pCurRun; + for (pCurRun = pRuns, i = 0; i< nSize; ++pCurRun, ++i) + { + rlType& curRun = *pCurRun; + if (curRun.r < 0 || curRun.r >= img.rows || curRun.cb >= img.cols || curRun.ce < 0) + continue; + + T* rowPtr = (T*)img.ptr(curRun.r); + std::fill(rowPtr + std::max(curRun.cb, 0), rowPtr + std::min(curRun.ce + 1, img.cols), value); + } +} + + CV_EXPORTS void paint(InputOutputArray image, InputArray rlSrc, const Scalar& value) + { + Mat _runs; + _runs = rlSrc.getMat(); + int N = _runs.checkVector(3); + if (N <= 1) + return; + + double dValue = value[0]; + + cv::Mat _image = image.getMat(); + + rlType* pRuns = (rlType*) &(_runs.at(1)); + switch (_image.type()) + { + case CV_8UC1: + paint_impl(_image, pRuns, N - 1, (uchar)dValue); + break; + case CV_8SC1: + paint_impl(_image, pRuns, N - 1, (schar)dValue); + break; + case CV_16UC1: + paint_impl(_image, pRuns, N - 1, (unsigned short)dValue); + break; + case CV_16SC1: + paint_impl(_image, pRuns, N - 1, (short)dValue); + break; + case CV_32SC1: + paint_impl(_image, pRuns, N - 1, (int)dValue); + break; + case CV_32FC1: + paint_impl(_image, pRuns, N - 1, (float)dValue); + break; + case CV_64FC1: + paint_impl(_image, pRuns, N - 1, dValue); + break; + default: + CV_Error(CV_StsUnsupportedFormat, "unsupported image type"); + break; + } + } + +static void translateRegion(rlVec& reg, Point ptTrans) +{ + for (rlVec::iterator it=reg.begin();it!=reg.end();++it) + { + it->r += ptTrans.y; + it->cb += ptTrans.x; + it->ce += ptTrans.x; + } +} + +CV_EXPORTS Mat getStructuringElement(int shape, Size ksize) +{ + Mat mask = cv::getStructuringElement(shape, ksize); + + rlVec reg; + _threshold(mask, reg, 0.0, THRESH_BINARY); + + Point ptTrans = - Point(mask.cols / 2, mask.rows / 2); + translateRegion(reg, ptTrans); + Mat rlDest; + convertToOutputArray(reg, Size(mask.cols, mask.rows), rlDest); + + return rlDest; +} + +static void erode_rle (rlVec& regIn, rlVec& regOut, rlVec& se) +{ + using namespace std; + + regOut.clear(); + + if (regIn.size() == 0) + return; + + int nMinRow = regIn[0].r; + int nMaxRow = regIn.back().r; + + int nRows = nMaxRow - nMinRow + 1; + + + const int EMPTY = -1; + + // setup a table which holds the index of the first chord for each row + vector pIdxChord1(nRows); + vector pIdxNextRow(nRows); + + int i,j; + + for (i=1;i pCurIdxRow(nRowsSE); + + // loop through all possible rows + for (i=nMinRow - nMinRowSE; i<= nMaxRow - nMaxRowSE; i++) + { + // check whether all relevant rows are available + bool bNextRow = false; + + for (j=0; j < nRowsSE; j++) + { + // get idx of first chord in regIn for this row of the se + pCurIdxRow[j] = pIdxChord1[ j + nMinRowSE + i - nMinRow]; + if (pCurIdxRow[j] == -1) + { + bNextRow = true; + break; + } + } + + if (bNextRow) + continue; + + while (!bNextRow) + { + int nPossibleStart = std::numeric_limits::min(); + + // search for row with max( cb - se.cb) (the leftmost possible position of a result chord + for (j=0;j::max(); //INT_MAX; + + for (j=0;j next row + if (pCurIdxRow[j] == pIdxNextRow[ j + nMinRowSE + i - nMinRow]) + { + bNextRow = true; + bHaveResult = false; + break; + } + else if ( bHaveResult ) + { + // can the found chord contribute to a result ? + if (regIn[ pCurIdxRow[j] ].cb - se[j].cb <= nPossibleStart) + { + int nCurPossibleEnd = regIn[ pCurIdxRow[j] ].ce - se[j].ce; + if (nCurPossibleEnd < nChordEnd) + { + nChordEnd = nCurPossibleEnd; + nLimitingRow = j; + } + } + else + bHaveResult = false; + } + } + + if (bHaveResult) + { + regOut.push_back(rlType(nPossibleStart, nChordEnd, i)); + pCurIdxRow[nLimitingRow]++; + + if (pCurIdxRow[nLimitingRow] == pIdxNextRow[ nLimitingRow + nMinRowSE + i - nMinRow]) + bNextRow = true; + } + } // end while (!bNextRow + } // end for + +} + +static void convertInputArrayToRuns(InputArray& theArray, rlVec& runs, Size& theSize) +{ + Mat _runs; + _runs = theArray.getMat(); + int N = _runs.checkVector(3); + if (N == 0) + { + runs.clear(); + return; + } + runs.resize(N - 1); + Point3i pt = _runs.at(0); + theSize.width = pt.x; + theSize.height = pt.y; + + for (int i = 1; i < N; ++i) + { + pt = _runs.at(i); + runs[i-1] = rlType(pt.x, pt.y, pt.z); + } +} + +static void sortChords(rlVec& lChords) +{ + sort(lChords.begin(), lChords.end()); +} + +static void mergeNeighbouringChords(rlVec& rlIn, rlVec& rlOut) +{ + rlOut.clear(); + if (rlIn.size() == 0) + return; + + rlOut.push_back(rlIn[0]); + + for (int i = 1; i< (int)rlIn.size(); i++) + { + rlType& curIn = rlIn[i]; + rlType& lastAddedOut = rlOut.back(); + if (curIn.r == lastAddedOut.r && curIn.cb <= lastAddedOut.ce + 1) + lastAddedOut.ce = max(curIn.ce, lastAddedOut.ce); + else + rlOut.push_back(curIn); + } +} + +static void union_regions(rlVec& reg1, rlVec& reg2, rlVec& regUnion) +{ + rlVec lAllChords(reg1); + + lAllChords.insert(lAllChords.end(), reg2.begin(), reg2.end()); + + sortChords(lAllChords); + mergeNeighbouringChords(lAllChords, regUnion); +} + +static void intersect(rlVec& reg1, rlVec& reg2, rlVec& regRes) +{ + rlVec::iterator end1 = reg1.end(); + rlVec::iterator end2 = reg2.end(); + + rlVec::iterator cur1 = reg1.begin(); + rlVec::iterator cur2 = reg2.begin(); + regRes.clear(); + + while (cur1 != end1 && cur2 != end2) + { + if (cur1->r < cur2->r || (cur1->r == cur2->r && cur1->ce < cur2->cb)) + ++cur1; + else if (cur2->r < cur1->r || (cur1->r == cur2->r && cur2->ce < cur1->cb)) + ++cur2; + else + { + assert(cur1->r == cur2->r); + int nStart = max(cur1->cb, cur2->cb); + int nEnd = min(cur1->ce, cur2->ce); + if (nStart > nEnd) + { + assert(nStart <= nEnd); + } + regRes.push_back(rlType(nStart, nEnd, cur1->r)); + if (cur1->ce < cur2->ce) + ++cur1; + else + ++cur2; + } + + } +} + +static void addBoundary(rlVec& runsIn, int nWidth, int nHeight, int nBoundaryLeft, int nBoundaryTop, + int nBoundaryRight, int nBoundaryBottom, rlVec& res) +{ + rlVec boundary; + for (int i = -nBoundaryTop; i < 0; ++i) + boundary.push_back(rlType(-nBoundaryLeft, nWidth - 1 + nBoundaryRight, i)); + for (int i = 0; i < nHeight; ++i) + { + boundary.push_back(rlType(-nBoundaryLeft, -1, i)); + boundary.push_back(rlType(nWidth, nWidth - 1 + nBoundaryRight, i)); + } + + for (int i = nHeight; i < nHeight + nBoundaryBottom; ++i) + boundary.push_back(rlType(-nBoundaryLeft, nWidth - 1 + nBoundaryRight, i)); + + union_regions(runsIn, boundary, res); +} + +static cv::Rect getBoundingRectangle(rlVec& reg) +{ + using namespace std; + cv::Rect rect; + if (reg.empty()) + { + rect.x = rect.y = rect.width = rect.height = 0; + return rect; + } + + int minX = std::numeric_limits::max(); + int minY = std::numeric_limits::max(); + int maxX = std::numeric_limits::min(); + int maxY = std::numeric_limits::min(); + + int i; + for (i = 0; i<(int)reg.size(); i++) + { + minX = min(minX, reg[i].cb); + maxX = max(maxX, reg[i].ce); + minY = min(minY, reg[i].r); + maxY = max(maxY, reg[i].r); + } + + rect.x = minX; + rect.y = minY; + rect.width = maxX - minX + 1; + rect.height = maxY - minY + 1; + return rect; +} + +static void createUprightRectangle(cv::Rect rect, rlVec &rl) +{ + rl.clear(); + rlType curRL; + int j; + int cb = rect.x; + int ce = rect.x + rect.width - 1; + for (j = 0; j < rect.height; j++) + { + curRL.cb = cb; + curRL.ce = ce; + curRL.r = j + rect.y; + rl.push_back(curRL); + } +} + +static void erode_with_boundary_rle(rlVec& runsSource, int nWidth, int nHeight, rlVec& runsDestination, + rlVec& runsKernel) +{ + cv::Rect rect = getBoundingRectangle(runsKernel); + rlVec regExtended, regFrame, regResultRaw; + addBoundary(runsSource, nWidth, nHeight, max(0, -rect.x), max(0, -rect.y), + max(0, rect.x + rect.width), max(0, rect.y + rect.height), regExtended); + + erode_rle(regExtended, regResultRaw, runsKernel); + createUprightRectangle(cv::Rect(0, 0, nWidth, nHeight), regFrame); + intersect(regResultRaw, regFrame, runsDestination); +} + + +CV_EXPORTS void erode(InputArray rlSrc, OutputArray rlDest, InputArray rlKernel, bool bBoundaryOn, + Point anchor) +{ + rlVec runsSource, runsDestination, runsKernel; + Size sizeSource, sizeKernel; + convertInputArrayToRuns(rlSrc, runsSource, sizeSource); + convertInputArrayToRuns(rlKernel, runsKernel, sizeKernel); + + if (anchor != Point(0,0)) + translateRegion(runsKernel, -anchor); + + if (bBoundaryOn) + erode_with_boundary_rle(runsSource, sizeSource.width, sizeSource.height, runsDestination, runsKernel); + else + erode_rle(runsSource, runsDestination, runsKernel); + convertToOutputArray(runsDestination, sizeSource, rlDest); +} + + +static void subtract_rle( rlVec& regFrom, + rlVec& regSubtract, + rlVec& regRes) +{ + rlVec::iterator end1 = regFrom.end(); + rlVec::iterator end2 = regSubtract.end(); + + rlVec::iterator cur1 = regFrom.begin(); + rlVec::iterator cur2 = regSubtract.begin(); + regRes.clear(); + + while( cur1 != end1) + { + if (cur2 == end2) + { + regRes.insert( regRes.end(), cur1, end1); + return; + } + else if ( cur1->r < cur2->r || (cur1->r == cur2->r && cur1->ce < cur2->cb)) + { + regRes.push_back(*cur1); + ++cur1; + } + else if ( cur2->r < cur1->r || (cur1->r == cur2->r && cur2->ce < cur1->cb)) + ++cur2; + else + { + int curR = cur1->r; + assert(curR == cur2->r); + rlVec::iterator lastIncluded; + + bool bIncremented = false; + for (lastIncluded = cur2; + lastIncluded != end2 && lastIncluded->r == curR && lastIncluded->cb <= cur1->ce; + ++lastIncluded) + { + bIncremented = true; + } + + if (bIncremented) + --lastIncluded; + + // now all chords from cur2 to lastIncluded have an intersection with cur1 + if (cur1->cb < cur2->cb) + regRes.push_back(rlType(cur1->cb, cur2->cb - 1, curR)); + + // we add the gaps between the chords of reg2 to the result + while (cur2 < lastIncluded) + { + regRes.push_back(rlType(cur2->ce + 1, (cur2 + 1)->cb - 1, curR)); + if (regRes.back().cb > regRes.back().ce) + { + assert(false); + } + ++cur2; + } + + if (cur1->ce > lastIncluded->ce) + { + regRes.push_back(rlType(lastIncluded->ce + 1, cur1->ce, curR)); + assert(regRes.back().cb <= regRes.back().ce); + } + ++cur1; + } + + } +} + + + + +static void invertRegion(rlVec& runsIn, rlVec& runsOut) +{ + // if there is only one chord in row -> do not insert anything for this row + // otherwise insert chords for the spaces between chords + runsOut.clear(); + int nCurRow = std::numeric_limits::min(); + int nLastRight = nCurRow; + for (rlVec::iterator it = runsIn.begin(); it != runsIn.end(); ++it) + { + rlType run = *it; + if (run.r != nCurRow) + { + nCurRow = run.r; + nLastRight = run.ce; + } + else + { + assert(run.cb > nLastRight + 1); + runsOut.push_back(rlType(nLastRight + 1, run.cb - 1, nCurRow)); + nLastRight = run.ce; + } + } +} + + +static void dilate_rle(rlVec& runsSource, + rlVec& runsDestination, + rlVec& runsKernel) +{ + cv::Rect rectSource = getBoundingRectangle(runsSource); + cv::Rect rectKernel = getBoundingRectangle(runsKernel); + + cv::Rect background; + background.x = rectSource.x - 2 * rectKernel.width; + background.y = rectSource.y - 2 * rectKernel.height; + background.width = rectSource.width + 4 * rectKernel.width; + background.height = rectSource.height + 4 * rectKernel.height; + + rlVec rlBackground, rlSourceInverse, rlResultInverse; + createUprightRectangle(background, rlBackground); + subtract_rle(rlBackground, runsSource, rlSourceInverse); + + erode_rle(rlSourceInverse, rlResultInverse, runsKernel); + + invertRegion(rlResultInverse, runsDestination); +} + + + +CV_EXPORTS void dilate(InputArray rlSrc, OutputArray rlDest, InputArray rlKernel, Point anchor) +{ + rlVec runsSource, runsDestination, runsKernel; + Size sizeSource, sizeKernel; + convertInputArrayToRuns(rlSrc, runsSource, sizeSource); + convertInputArrayToRuns(rlKernel, runsKernel, sizeKernel); + + if (anchor != Point(0, 0)) + translateRegion(runsKernel, -anchor); + + dilate_rle(runsSource, runsDestination, runsKernel); + + convertToOutputArray(runsDestination, sizeSource, rlDest); +} + +CV_EXPORTS bool isRLMorphologyPossible(InputArray rlStructuringElement) +{ + rlVec runsKernel; + Size sizeKernel; + convertInputArrayToRuns(rlStructuringElement, runsKernel, sizeKernel); + + for (int i = 1; i < (int) runsKernel.size(); ++i) + if (runsKernel[i].r != runsKernel[i-1].r + 1) + return false; + + return true; +} + +CV_EXPORTS void createRLEImage(std::vector& runs, OutputArray res, Size size) +{ + size_t nRuns = runs.size(); + rlVec runsConverted(nRuns); + for (size_t i = 0u; i < nRuns; ++i) + { + Point3i &curIn = runs[i]; + runsConverted[i] = rlType(curIn.x, curIn.y, curIn.z); + } + sortChords(runsConverted); + + if (size.width == 0 || size.height == 0) + { + Rect boundingRect = getBoundingRectangle(runsConverted); + size.width = std::max(0, boundingRect.x + boundingRect.width); + size.height = std::max(0, boundingRect.y + boundingRect.height); + } + convertToOutputArray(runsConverted, size, res); +} + + +CV_EXPORTS void morphologyEx(InputArray rlSrc, OutputArray rlDest, int op, InputArray rlKernel, + bool bBoundaryOnForErosion, Point anchor) +{ + if (op == MORPH_ERODE) + rl::erode(rlSrc, rlDest, rlKernel, bBoundaryOnForErosion, anchor); + else if (op == MORPH_DILATE) + rl::dilate(rlSrc, rlDest, rlKernel, anchor); + else + { + rlVec runsSource, runsKernel, runsDestination; + Size sizeSource, sizeKernel; + convertInputArrayToRuns(rlKernel, runsKernel, sizeKernel); + convertInputArrayToRuns(rlSrc, runsSource, sizeSource); + + if (anchor != Point(0, 0)) + translateRegion(runsKernel, -anchor); + + switch (op) + { + case MORPH_OPEN: + { + rlVec runsEroded; + + if (bBoundaryOnForErosion) + erode_with_boundary_rle(runsSource, sizeSource.width, sizeSource.height, runsEroded, runsKernel); + else + erode_rle(runsSource, runsEroded, runsKernel); + dilate_rle(runsEroded, runsDestination, runsKernel); + } + break; + case MORPH_CLOSE: + { + rlVec runsDilated; + + dilate_rle(runsSource, runsDilated, runsKernel); + if (bBoundaryOnForErosion) + erode_with_boundary_rle(runsDilated, sizeSource.width, sizeSource.height, runsDestination, runsKernel); + else + erode_rle(runsDilated, runsDestination, runsKernel); + } + break; + case MORPH_GRADIENT: + { + rlVec runsEroded, runsDilated; + if (bBoundaryOnForErosion) + erode_with_boundary_rle(runsSource, sizeSource.width, sizeSource.height, runsEroded, runsKernel); + else + erode_rle(runsSource, runsEroded, runsKernel); + dilate_rle(runsSource, runsDilated, runsKernel); + subtract_rle(runsDilated, runsEroded, runsDestination); + } + break; + case MORPH_TOPHAT: + { + rlVec runsEroded, runsOpened; + + if (bBoundaryOnForErosion) + erode_with_boundary_rle(runsSource, sizeSource.width, sizeSource.height, runsEroded, runsKernel); + else + erode_rle(runsSource, runsEroded, runsKernel); + dilate_rle(runsEroded, runsOpened, runsKernel); + subtract_rle(runsSource, runsOpened, runsDestination); + } + break; + + case MORPH_BLACKHAT: + { + rlVec runsClosed, runsDilated; + + dilate_rle(runsSource, runsDilated, runsKernel); + if (bBoundaryOnForErosion) + erode_with_boundary_rle(runsDilated, sizeSource.width, sizeSource.height, runsClosed, runsKernel); + else + erode_rle(runsDilated, runsClosed, runsKernel); + + subtract_rle(runsClosed, runsSource, runsDestination); + } + break; + default: + case MORPH_HITMISS: + CV_Error(CV_StsBadArg, "unknown or unsupported morphological operation"); + } + convertToOutputArray(runsDestination, sizeSource, rlDest); + } +} + +} +} //end of cv::ximgproc +} //end of cv diff --git a/modules/ximgproc/test/test_run_length_morphology.cpp b/modules/ximgproc/test/test_run_length_morphology.cpp new file mode 100644 index 000000000..f4e39f48d --- /dev/null +++ b/modules/ximgproc/test/test_run_length_morphology.cpp @@ -0,0 +1,249 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. +#include "test_precomp.hpp" +#include "opencv2/ximgproc/run_length_morphology.hpp" +#include "opencv2/imgproc.hpp" + +namespace opencv_test { +namespace { + +const Size img_size(640, 480); +const int tile_size(20); +typedef tuple RLMParams; +typedef tuple RLMSParams; + +class RLTestBase +{ +public: + RLTestBase() { } + +protected: + std::vector test_image; + std::vector test_image_rle; + + void generateCheckerBoard(Mat& image); + void generateRandomImage(Mat& image); + + bool areImagesIdentical(Mat& pixelImage, Mat& rleImage); + bool arePixelImagesIdentical(Mat& image1, Mat& image2); + + void setUp_impl(); +}; + +void RLTestBase::generateCheckerBoard(Mat& image) +{ + image.create(img_size, CV_8UC1); + for (int iy = 0; iy < img_size.height; iy += tile_size) + { + Range rowRange(iy, std::min(iy + tile_size, img_size.height)); + for (int ix = 0; ix < img_size.width; ix += tile_size) + { + Range colRange(ix, std::min(ix + tile_size, img_size.width)); + Mat tile(image, rowRange, colRange); + bool bBright = ((iy + ix) % (2 * tile_size) == 0); + tile = (bBright ? Scalar(255) : Scalar(0)); + } + } +} + +void RLTestBase::generateRandomImage(Mat& image) +{ + image.create(img_size, CV_8UC1); + randu(image, Scalar::all(0), Scalar::all(255)); +} + + +void RLTestBase::setUp_impl() +{ + test_image.resize(2); + test_image_rle.resize(2); + generateCheckerBoard(test_image[0]); + rl::threshold(test_image[0], test_image_rle[0], 100.0, THRESH_BINARY); + + cv::Mat theRandom; + generateRandomImage(theRandom); + double dThreshold = 254.0; + cv::threshold(theRandom, test_image[1], dThreshold, 255.0, THRESH_BINARY); + + rl::threshold(theRandom, test_image_rle[1], dThreshold, THRESH_BINARY); + +} + +bool RLTestBase::areImagesIdentical(Mat& pixelImage, Mat& rleImage) +{ + cv::Mat rleConverted; + rleConverted = cv::Mat::zeros(pixelImage.rows, pixelImage.cols, CV_8UC1); + rl::paint(rleConverted, rleImage, Scalar(255.0)); + return arePixelImagesIdentical(pixelImage, rleConverted); +} + +bool RLTestBase::arePixelImagesIdentical(Mat& image1, Mat& image2) +{ + cv::Mat diff; + cv::absdiff(image1, image2, diff); + int nDiff = cv::countNonZero(diff); + return (nDiff == 0); +} + + + +class RL_Identical_Result_Simple : public RLTestBase, public ::testing::TestWithParam +{ +public: + RL_Identical_Result_Simple() { } +protected: + virtual void SetUp() { setUp_impl(); } +}; + +TEST_P(RL_Identical_Result_Simple, simple) +{ + Mat resPix, resRLE; + RLMSParams param = GetParam(); + cv::MorphTypes elementType = get<0>(param); + int nSize = get<1>(param); + int image = get<2>(param); + int op = get<3>(param); + Mat element = getStructuringElement(elementType, Size(nSize * 2 + 1, nSize * 2 + 1), + Point(nSize, nSize)); + + + morphologyEx(test_image[image], resPix, op, element); + + Mat elementRLE = rl::getStructuringElement(elementType, Size(nSize * 2 + 1, nSize * 2 + 1)); + rl::morphologyEx(test_image_rle[image], resRLE, op, elementRLE); + + ASSERT_TRUE(areImagesIdentical(resPix, resRLE)); +} + +INSTANTIATE_TEST_CASE_P(TypicalSET, RL_Identical_Result_Simple, Combine(Values(MORPH_RECT, MORPH_CROSS, MORPH_ELLIPSE), + Values(1, 5, 11), Values(0, 1), Values(MORPH_ERODE, MORPH_DILATE, MORPH_OPEN, MORPH_CLOSE, MORPH_GRADIENT, MORPH_TOPHAT, MORPH_BLACKHAT))); + + +class RL_Identical_Result : public RLTestBase, public ::testing::TestWithParam +{ +public: + RL_Identical_Result() { } +protected: + virtual void SetUp() { setUp_impl(); } +}; + + +TEST_P(RL_Identical_Result, erosion_no_boundary) +{ + Mat resPix, resRLE; + RLMParams param = GetParam(); + cv::MorphTypes elementType = get<0>(param); + int nSize = get<1>(param); + int image = get<2>(param); + Mat element = getStructuringElement(elementType, Size(nSize * 2 + 1, nSize * 2 + 1), + Point(nSize, nSize)); + + erode(test_image[image], resPix, element, cv::Point(-1,-1), 1, BORDER_CONSTANT, cv::Scalar(0)); + + Mat elementRLE = rl::getStructuringElement(elementType, Size(nSize * 2 + 1, nSize * 2 + 1)); + rl::erode(test_image_rle[image], resRLE, elementRLE, false); + + ASSERT_TRUE(areImagesIdentical(resPix, resRLE)); +} + +TEST_P(RL_Identical_Result, erosion_with_offset) +{ + Mat resPix, resRLE; + RLMParams param = GetParam(); + cv::MorphTypes elementType = get<0>(param); + int nSize = get<1>(param); + int image = get<2>(param); + int nOffset = nSize - 1; + Mat element = getStructuringElement(elementType, Size(nSize * 2 + 1, nSize * 2 + 1), + Point(nSize, nSize)); + + erode(test_image[image], resPix, element, cv::Point(nSize + nOffset, nSize + nOffset)); + + Mat elementRLE = rl::getStructuringElement(elementType, Size(nSize * 2 + 1, nSize * 2 + 1)); + rl::erode(test_image_rle[image], resRLE, elementRLE, true, Point(nOffset, nOffset)); + + ASSERT_TRUE(areImagesIdentical(resPix, resRLE)); +} + +TEST_P(RL_Identical_Result, dilation_with_offset) +{ + Mat resPix, resRLE; + RLMParams param = GetParam(); + cv::MorphTypes elementType = get<0>(param); + int nSize = get<1>(param); + int image = get<2>(param); + int nOffset = nSize - 1; + Mat element = getStructuringElement(elementType, Size(nSize * 2 + 1, nSize * 2 + 1), + Point(nSize, nSize)); + + dilate(test_image[image], resPix, element, cv::Point(nSize + nOffset, nSize + nOffset)); + + Mat elementRLE = rl::getStructuringElement(elementType, Size(nSize * 2 + 1, nSize * 2 + 1)); + rl::dilate(test_image_rle[image], resRLE, elementRLE, Point(nOffset, nOffset)); + + ASSERT_TRUE(areImagesIdentical(resPix, resRLE)); +} + +INSTANTIATE_TEST_CASE_P(TypicalSET, RL_Identical_Result, Combine(Values(MORPH_RECT, MORPH_CROSS, MORPH_ELLIPSE), Values(1,5,11), Values(0,1))); + +class RL_CreateCustomKernel : public RLTestBase, public testing::Test +{ +public: + RL_CreateCustomKernel() { } +protected: + virtual void SetUp() { setUp_impl(); } +}; + + +TEST_F(RL_CreateCustomKernel, check_valid) +{ + // create a diamond + int nSize = 21; + std::vector runs; + for (int i = 0; i < nSize; ++i) + { + runs.emplace_back(Point3i(-i, i, -nSize + i)); + runs.emplace_back(Point3i(-i, i, nSize - i)); + } + runs.emplace_back(Point3i(-nSize, nSize, 0)); + Mat kernel, dest; + rl::createRLEImage(runs, kernel); + ASSERT_TRUE(rl::isRLMorphologyPossible(kernel)); + + rl::erode(test_image_rle[0], dest, kernel); + //only one row means: no runs, all pixels off + ASSERT_TRUE(dest.rows == 1); +} + +typedef tuple RLPParams; + +class RL_Paint : public RLTestBase, public ::testing::TestWithParam +{ +public: +RL_Paint() { } +protected: + virtual void SetUp() { setUp_impl(); } +}; + +TEST_P(RL_Paint, same_result) +{ + Mat converted, pixBinary, painted; + RLPParams param = GetParam(); + int rType = get<0>(param); + + double dThreshold = 100.0; + double dMaxValue = 105.0; + test_image[1].convertTo(converted, rType); + cv::threshold(converted, pixBinary, dThreshold, dMaxValue, THRESH_BINARY); + + painted.create(test_image[1].rows, test_image[1].cols, rType); + painted = cv::Scalar(0.0); + rl::paint(painted, test_image_rle[1], Scalar(dMaxValue)); + ASSERT_TRUE(arePixelImagesIdentical(pixBinary, painted)); +} + +INSTANTIATE_TEST_CASE_P(TypicalSET, RL_Paint, Values(CV_8U, CV_16U, CV_16S, CV_32F, CV_64F)); + +} +} \ No newline at end of file From 96953843be2896390457864e974e466e5d959797 Mon Sep 17 00:00:00 2001 From: simonreich Date: Thu, 2 Aug 2018 16:08:53 +0200 Subject: [PATCH 10/97] Merge pull request #1690 from simonreich:epf Adds Edge-Preserving Filter (#1690) * Module EPF - Edge-Preserving Filter added * Changed name from template to epf * Removed clang-format file * Added header Files. Eliminated showWindow function. Used CommandLineParser. * Moved filter from epf module to ximgproc * Removed header files from sample * Minor bug fix in demo. Pointers in demo removed. * Pointers removed. InputArray/OutputArray added * License header added * License header from sample file removed * Unit test for performance added * Replaced manual mean computation with cv::mean * Beautified code via clang-format and https://raw.githubusercontent.com/opencv/opencv_contrib/master/modules/cvv/.clang-format * Merged historic if... else if statement into one if statement * Trailing whitespace removed and .. changed into . * Tabs replaced with 4 spaces. * Removed subwindow = src(roi); * Moved type test to beginning of code * Removed indentation from namespace and added //! @} * Added name to header * git cleanup introduced some errors fixed here * Changed path testdata/perf/320x260.png to perf/320x260.png * Fixed warning declaration of 'subwindow1' hides previous local declaration * Fixed warning 'const' qualifier on reference type 'cv::InputArray' (aka 'const cv::_InputArray &') has no effect * Accuracy test added/ * Renamed void edgepreservingFilter to void edgePreservingFilter --- modules/ximgproc/include/opencv2/ximgproc.hpp | 1 + .../ximgproc/edgepreserving_filter.hpp | 33 +++ .../perf/perf_edgepreserving_filter.cpp | 45 ++++ .../samples/edgepreserving_filter_demo.cpp | 42 ++++ .../ximgproc/src/edgepreserving_filter.cpp | 236 ++++++++++++++++++ .../test/test_edgepreserving_filter.cpp | 35 +++ 6 files changed, 392 insertions(+) create mode 100644 modules/ximgproc/include/opencv2/ximgproc/edgepreserving_filter.hpp create mode 100644 modules/ximgproc/perf/perf_edgepreserving_filter.cpp create mode 100644 modules/ximgproc/samples/edgepreserving_filter_demo.cpp create mode 100644 modules/ximgproc/src/edgepreserving_filter.cpp create mode 100644 modules/ximgproc/test/test_edgepreserving_filter.cpp diff --git a/modules/ximgproc/include/opencv2/ximgproc.hpp b/modules/ximgproc/include/opencv2/ximgproc.hpp index 874bf63e0..5ff7b3f70 100644 --- a/modules/ximgproc/include/opencv2/ximgproc.hpp +++ b/modules/ximgproc/include/opencv2/ximgproc.hpp @@ -57,6 +57,7 @@ #include "ximgproc/ridgefilter.hpp" #include "ximgproc/brightedges.hpp" #include "ximgproc/run_length_morphology.hpp" +#include "ximgproc/edgepreserving_filter.hpp" /** @defgroup ximgproc Extended Image Processing diff --git a/modules/ximgproc/include/opencv2/ximgproc/edgepreserving_filter.hpp b/modules/ximgproc/include/opencv2/ximgproc/edgepreserving_filter.hpp new file mode 100644 index 000000000..f5685ce39 --- /dev/null +++ b/modules/ximgproc/include/opencv2/ximgproc/edgepreserving_filter.hpp @@ -0,0 +1,33 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. + +#ifndef __OPENCV_EDGEPRESERVINGFILTER_HPP__ +#define __OPENCV_EDGEPRESERVINGFILTER_HPP__ + +#include + +namespace cv { namespace ximgproc { + +//! @addtogroup ximgproc +//! @{ + + /** + * @brief Smoothes an image using the Edge-Preserving filter. + * + * The function smoothes Gaussian noise as well as salt & pepper noise. + * For more details about this implementation, please see + * [ReiWoe18] Reich, S. and Wörgötter, F. and Dellen, B. (2018). A Real-Time Edge-Preserving Denoising Filter. Proceedings of the 13th International Joint Conference on Computer Vision, Imaging and Computer Graphics Theory and Applications (VISIGRAPP): Visapp, 85-94, 4. DOI: 10.5220/0006509000850094. + * + * @param src Source 8-bit 3-channel image. + * @param dst Destination image of the same size and type as src. + * @param d Diameter of each pixel neighborhood that is used during filtering. Must be greater or equal 3. + * @param threshold Threshold, which distinguishes between noise, outliers, and data. + */ + CV_EXPORTS_W void edgePreservingFilter( InputArray src, OutputArray dst, int d, double threshold ); + +}} // namespace + +//! @} + +#endif diff --git a/modules/ximgproc/perf/perf_edgepreserving_filter.cpp b/modules/ximgproc/perf/perf_edgepreserving_filter.cpp new file mode 100644 index 000000000..7d86d165f --- /dev/null +++ b/modules/ximgproc/perf/perf_edgepreserving_filter.cpp @@ -0,0 +1,45 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level +// directory of this distribution and at http://opencv.org/license.html. +// +// Created by Simon Reich +// +#include "perf_precomp.hpp" + +namespace opencv_test +{ +namespace +{ + +/* 1. Define parameter type and test fixture */ +typedef tuple RGFTestParam; +typedef TestBaseWithParam EdgepreservingFilterTest; + +/* 2. Declare the testsuite */ +PERF_TEST_P(EdgepreservingFilterTest, perf, + Combine(Values(-20, 0, 10), Values(-100, 0, 20))) +{ + /* 3. Get actual test parameters */ + RGFTestParam params = GetParam(); + int kernelSize = get<0>(params); + double threshold = get<1>(params); + + /* 4. Allocate and initialize arguments for tested function */ + std::string filename = getDataPath("perf/320x260.png"); + Mat src = imread(filename, 1); + Mat dst(src.size(), src.type()); + + /* 5. Manifest your expectations about this test */ + declare.in(src).out(dst); + + /* 6. Collect the samples! */ + PERF_SAMPLE_BEGIN(); + ximgproc::edgePreservingFilter(src, dst, kernelSize, threshold); + PERF_SAMPLE_END(); + + /* 7. Do not check anything */ + SANITY_CHECK_NOTHING(); +} + +} // namespace +} // namespace opencv_test diff --git a/modules/ximgproc/samples/edgepreserving_filter_demo.cpp b/modules/ximgproc/samples/edgepreserving_filter_demo.cpp new file mode 100644 index 000000000..faa89b43d --- /dev/null +++ b/modules/ximgproc/samples/edgepreserving_filter_demo.cpp @@ -0,0 +1,42 @@ +#include +#include +#include +#include + +using namespace cv; + +int main(int argc, char **argv) +{ + cv::CommandLineParser parser( + argc, argv, + "{help h ? | | help message}" + "{@image | | Image filename to process }"); + if (parser.has("help") || !parser.has("@image")) + { + parser.printMessage(); + return 0; + } + + // Load image from first parameter + std::string filename = parser.get("@image"); + Mat image = imread(filename, 1), res; + + if (!image.data) + { + std::cerr << "No image data at " << filename << std::endl; + throw; + } + + // Before filtering + imshow("Original image", image); + waitKey(0); + + // Initialize filter. Kernel size 5x5, threshold 20 + ximgproc::edgePreservingFilter(image, res, 9, 20); + + // After filtering + imshow("Filtered image", res); + waitKey(0); + + return 0; +} diff --git a/modules/ximgproc/src/edgepreserving_filter.cpp b/modules/ximgproc/src/edgepreserving_filter.cpp new file mode 100644 index 000000000..ea9dfb65e --- /dev/null +++ b/modules/ximgproc/src/edgepreserving_filter.cpp @@ -0,0 +1,236 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level +// directory of this distribution and at http://opencv.org/license.html. +// +// Created by Simon Reich +// + +#include "precomp.hpp" + +namespace cv +{ +namespace ximgproc +{ +using namespace std; + +void edgePreservingFilter(InputArray _src, OutputArray _dst, int d, + double threshold) +{ + CV_Assert(_src.type() == CV_8UC3); + + Mat src = _src.getMat(); + + // [re]create the output array so that it has the proper size and type. + _dst.create(src.size(), src.type()); + Mat dst = _dst.getMat(); + src.copyTo(dst); + + if (d < 3) + d = 3; + int subwindowX = d, subwindowY = d; + + if (threshold < 0) + threshold = 0; + + // number of image channels + int nChannel = src.channels(); + + vector pixel(nChannel, 0); + vector> line1(src.rows, pixel); + vector>> weight(src.cols, + line1); // global weights + vector>> imageResult( + src.cols, line1); // global normalized image + + // do algorithm + cv::Mat subwindow, subwindow1; + for (int posX = 0; posX < src.cols - subwindowX; posX++) + { + for (int posY = 0; posY < src.rows - subwindowY; posY++) + { + cv::Rect roi = + cv::Rect(posX, posY, subwindowX, subwindowY); + subwindow1 = src(roi); + cv::GaussianBlur(subwindow1, subwindow, cv::Size(5, 5), + 0.3, 0.3); + + // compute arithmetic mean of subwindow + cv::Scalar ArithmeticMean = cv::mean(subwindow); + + // compute pixelwise distance + vector> pixelwiseDist; + + for (int subPosX = 0; subPosX < subwindow.cols; + subPosX++) + { + vector line; + for (int subPosY = 0; subPosY < subwindow.rows; + subPosY++) + { + cv::Vec3b intensity = + subwindow.at(subPosY, + subPosX); + double distance = + ((double)intensity.val[0] - + ArithmeticMean[0]) * + ((double)intensity.val[0] - + ArithmeticMean[0]) + + ((double)intensity.val[1] - + ArithmeticMean[1]) * + ((double)intensity.val[1] - + ArithmeticMean[1]) + + ((double)intensity.val[2] - + ArithmeticMean[2]) * + ((double)intensity.val[2] - + ArithmeticMean[2]); + distance = sqrt(distance); + + line.push_back(distance); + }; + + pixelwiseDist.push_back(line); + }; + + // compute mean pixelwise distance + double meanPixelwiseDist = 0; + + for (int i = 0; i < (int)pixelwiseDist.size(); i++) + for (int j = 0; + j < (int)pixelwiseDist[i].size(); j++) + meanPixelwiseDist += + pixelwiseDist[i][j]; + + meanPixelwiseDist /= ((int)pixelwiseDist.size() * + (int)pixelwiseDist[0].size()); + + // detect edge + for (int subPosX = 0; subPosX < subwindow.cols; + subPosX++) + { + for (int subPosY = 0; subPosY < subwindow.rows; + subPosY++) + { + if ((meanPixelwiseDist <= threshold && + pixelwiseDist[subPosX][subPosY] <= + threshold) || + (meanPixelwiseDist <= threshold && + pixelwiseDist[subPosX][subPosY] > + threshold)) + { + // global Position + int globalPosX = posX + subPosX; + int globalPosY = posY + subPosY; + + // compute global weight + cv::Vec3b intensity = + subwindow.at( + subPosY, subPosX); + weight[globalPosX][globalPosY] + [0] += + intensity.val[0] * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + (threshold - + pixelwiseDist[subPosX] + [subPosY]); + weight[globalPosX][globalPosY] + [1] += + intensity.val[1] * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + (threshold - + pixelwiseDist[subPosX] + [subPosY]); + weight[globalPosX][globalPosY] + [2] += + intensity.val[2] * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + (threshold - + pixelwiseDist[subPosX] + [subPosY]); + + // compute final image + imageResult[globalPosX] + [globalPosY][0] += + intensity.val[0] * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + ArithmeticMean[0]; + imageResult[globalPosX] + [globalPosY][1] += + intensity.val[1] * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + ArithmeticMean[1]; + imageResult[globalPosX] + [globalPosY][2] += + intensity.val[2] * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + (threshold - + pixelwiseDist[subPosX] + [subPosY]) * + ArithmeticMean[2]; + }; + }; + }; + }; + }; + + // compute final image + for (int globalPosX = 0; globalPosX < (int)imageResult.size(); + globalPosX++) + { + for (int globalPosY = 0; + globalPosY < (int)imageResult[globalPosX].size(); + globalPosY++) + { + // cout << "globalPosX: " << globalPosX << "/" + // << dst.cols << "," << imageResult.size () << + // "\tglobalPosY: " << globalPosY << "/" << + // dst.rows << "," <(globalPosY, globalPosX); + imageResult[globalPosX][globalPosY][0] += + (double)intensity.val[0]; + imageResult[globalPosX][globalPosY][1] += + (double)intensity.val[1]; + imageResult[globalPosX][globalPosY][2] += + (double)intensity.val[2]; + + // normalize using weight + imageResult[globalPosX][globalPosY][0] /= + (weight[globalPosX][globalPosY][0] + 1); + imageResult[globalPosX][globalPosY][1] /= + (weight[globalPosX][globalPosY][1] + 1); + imageResult[globalPosX][globalPosY][2] /= + (weight[globalPosX][globalPosY][2] + 1); + + // copy to output image frame + dst.at(globalPosY, globalPosX)[0] = + (uchar)imageResult[globalPosX][globalPosY][0]; + dst.at(globalPosY, globalPosX)[1] = + (uchar)imageResult[globalPosX][globalPosY][1]; + dst.at(globalPosY, globalPosX)[2] = + (uchar)imageResult[globalPosX][globalPosY][2]; + }; + }; +} +} // namespace ximgproc +} // namespace cv diff --git a/modules/ximgproc/test/test_edgepreserving_filter.cpp b/modules/ximgproc/test/test_edgepreserving_filter.cpp new file mode 100644 index 000000000..8f6059b7d --- /dev/null +++ b/modules/ximgproc/test/test_edgepreserving_filter.cpp @@ -0,0 +1,35 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. +// +// Created by Simon Reich +// +#include "test_precomp.hpp" + +namespace opencv_test { namespace { + +TEST(ximgproc_EdgepreservingFilter, regression) +{ + // Load original image + std::string filename = string(cvtest::TS::ptr()->get_data_path()) + "perf/320x260.png"; + cv::Mat src, dst, noise, original = imread(filename, 1); + + ASSERT_FALSE(original.empty()) << "Could not load input image " << filename; + ASSERT_EQ(3, original.channels()) << "Load color input image " << filename; + + // add noise + noise = Mat(original.size(), original.type()); + cv::randn(noise, 0, 5); + src = original + noise; + + // Filter + int kernel = 9; + double threshold = 20; + ximgproc::edgePreservingFilter(src, dst, kernel, threshold); + + double psnr = cvtest::PSNR(original, dst); + //printf("psnr=%.2f\n", psnr); + ASSERT_LT(psnr, 25.0); +} + +}} // namespace From 09c5e8cc81b9b421a9921fd1b8096ce334d96b1f Mon Sep 17 00:00:00 2001 From: Jiri Horner Date: Sat, 18 Aug 2018 21:50:38 +0200 Subject: [PATCH 11/97] replace internal usage of deprecated estimateRigidTransform in face * face module now links to calib3d instead of video module --- modules/face/CMakeLists.txt | 2 +- modules/face/src/trainFacemark.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/modules/face/CMakeLists.txt b/modules/face/CMakeLists.txt index 2d5f8075a..ce3d88874 100644 --- a/modules/face/CMakeLists.txt +++ b/modules/face/CMakeLists.txt @@ -2,7 +2,7 @@ set(the_description "Face recognition etc") ocv_define_module(face opencv_core opencv_imgproc opencv_objdetect - opencv_video # estimateRigidTransform() (trainFacemark) + opencv_calib3d # estimateAffinePartial2D() (trainFacemark) opencv_photo # seamlessClone() (face_swap sample) WRAP python java ) diff --git a/modules/face/src/trainFacemark.cpp b/modules/face/src/trainFacemark.cpp index 3e9ecf57d..2675772da 100644 --- a/modules/face/src/trainFacemark.cpp +++ b/modules/face/src/trainFacemark.cpp @@ -4,7 +4,7 @@ #include "precomp.hpp" #include "face_alignmentimpl.hpp" -#include "opencv2/video/tracking.hpp" +#include "opencv2/calib3d.hpp" #include using namespace std; @@ -123,7 +123,7 @@ bool FacemarkKazemiImpl :: getRelativePixels(vector sample,vector Date: Tue, 4 Jul 2017 12:31:02 +0300 Subject: [PATCH 12/97] text: remove duplicated create method in OCRHMMDecoder class --- modules/text/include/opencv2/text/ocr.hpp | 8 -------- modules/text/src/ocr_hmm_decoder.cpp | 10 ---------- 2 files changed, 18 deletions(-) diff --git a/modules/text/include/opencv2/text/ocr.hpp b/modules/text/include/opencv2/text/ocr.hpp index b70b30af7..f8a8e8cc2 100644 --- a/modules/text/include/opencv2/text/ocr.hpp +++ b/modules/text/include/opencv2/text/ocr.hpp @@ -290,14 +290,6 @@ public: @param mode HMM Decoding algorithm. Only OCR_DECODER_VITERBI is available for the moment (). */ - static Ptr create(const Ptr classifier,// The character classifier with built in feature extractor - const std::string& vocabulary, // The language vocabulary (chars when ASCII English text) - // size() must be equal to the number of classes - InputArray transition_probabilities_table, // Table with transition probabilities between character pairs - // cols == rows == vocabulary.size() - InputArray emission_probabilities_table, // Table with observation emission probabilities - // cols == rows == vocabulary.size() - decoder_mode mode = OCR_DECODER_VITERBI); // HMM Decoding algorithm (only Viterbi for the moment) CV_WRAP static Ptr create(const Ptr classifier,// The character classifier with built in feature extractor const String& vocabulary, // The language vocabulary (chars when ASCII English text) diff --git a/modules/text/src/ocr_hmm_decoder.cpp b/modules/text/src/ocr_hmm_decoder.cpp index 598aeb31c..6d61578bd 100644 --- a/modules/text/src/ocr_hmm_decoder.cpp +++ b/modules/text/src/ocr_hmm_decoder.cpp @@ -665,16 +665,6 @@ public: } }; -Ptr OCRHMMDecoder::create( Ptr _classifier, - const string& _vocabulary, - InputArray transition_p, - InputArray emission_p, - decoder_mode _mode) -{ - return makePtr(_classifier, _vocabulary, transition_p, emission_p, _mode); -} - - Ptr OCRHMMDecoder::create( Ptr _classifier, const String& _vocabulary, InputArray transition_p, From d11ab6859f2b9904dee959b05cf79cdb510b02f3 Mon Sep 17 00:00:00 2001 From: Suleyman TURKMEN Date: Sun, 26 Aug 2018 03:26:49 +0300 Subject: [PATCH 13/97] update TrackerCSRT --- modules/tracking/include/opencv2/tracking/tracker.hpp | 2 +- modules/tracking/src/trackerCSRT.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/modules/tracking/include/opencv2/tracking/tracker.hpp b/modules/tracking/include/opencv2/tracking/tracker.hpp index 37545bfee..aa1c5fd76 100644 --- a/modules/tracking/include/opencv2/tracking/tracker.hpp +++ b/modules/tracking/include/opencv2/tracking/tracker.hpp @@ -1522,7 +1522,7 @@ public: CV_WRAP static Ptr create(); - virtual void setInitialMask(const Mat mask) = 0; + CV_WRAP virtual void setInitialMask(InputArray mask) = 0; virtual ~TrackerCSRT() CV_OVERRIDE {} }; diff --git a/modules/tracking/src/trackerCSRT.cpp b/modules/tracking/src/trackerCSRT.cpp index d34b8562b..0b5e0a9c4 100644 --- a/modules/tracking/src/trackerCSRT.cpp +++ b/modules/tracking/src/trackerCSRT.cpp @@ -35,7 +35,7 @@ protected: TrackerCSRT::Params params; bool initImpl(const Mat& image, const Rect2d& boundingBox) CV_OVERRIDE; - virtual void setInitialMask(const Mat mask) CV_OVERRIDE; + virtual void setInitialMask(InputArray mask) CV_OVERRIDE; bool updateImpl(const Mat& image, Rect2d& boundingBox) CV_OVERRIDE; void update_csr_filter(const Mat &image, const Mat &my_mask); void update_histograms(const Mat &image, const Rect ®ion); @@ -99,9 +99,9 @@ void TrackerCSRTImpl::write(cv::FileStorage& fs) const params.write(fs); } -void TrackerCSRTImpl::setInitialMask(const Mat mask) +void TrackerCSRTImpl::setInitialMask(InputArray mask) { - preset_mask = mask; + preset_mask = mask.getMat(); } bool TrackerCSRTImpl::check_mask_area(const Mat &mat, const double obj_area) From 8e840c8642c9b1011480b1d58e0a3fec51f04c3b Mon Sep 17 00:00:00 2001 From: Hamdi Sahloul Date: Sat, 25 Aug 2018 05:31:49 +0900 Subject: [PATCH 14/97] Fix enum wrapper --- modules/aruco/include/opencv2/aruco/dictionary.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/aruco/include/opencv2/aruco/dictionary.hpp b/modules/aruco/include/opencv2/aruco/dictionary.hpp index 18fb572f3..27c7e5dd7 100644 --- a/modules/aruco/include/opencv2/aruco/dictionary.hpp +++ b/modules/aruco/include/opencv2/aruco/dictionary.hpp @@ -138,7 +138,7 @@ class CV_EXPORTS_W Dictionary { * - DICT_ARUCO_ORIGINAL: standard ArUco Library Markers. 1024 markers, 5x5 bits, 0 minimum distance */ -enum CV_EXPORTS_W_SIMPLE PREDEFINED_DICTIONARY_NAME { +enum PREDEFINED_DICTIONARY_NAME { DICT_4X4_50 = 0, DICT_4X4_100, DICT_4X4_250, From 2b4c35766a4b182ac37f594e1cc9b16a62614e16 Mon Sep 17 00:00:00 2001 From: Alexander Alekhin Date: Mon, 27 Aug 2018 19:35:54 +0000 Subject: [PATCH 15/97] hdf5: fix atread(string) no need to append null-terminated symbol --- modules/hdf/src/hdf5.cpp | 7 +++++-- modules/hdf/test/test_hdf5.cpp | 24 +++++++++++++++++++++--- 2 files changed, 26 insertions(+), 5 deletions(-) diff --git a/modules/hdf/src/hdf5.cpp b/modules/hdf/src/hdf5.cpp index a24092a4e..2769bdf77 100644 --- a/modules/hdf/src/hdf5.cpp +++ b/modules/hdf/src/hdf5.cpp @@ -441,10 +441,13 @@ void HDF5Impl::atread(String* value, const String& atlabel) CV_Error_(Error::StsInternal, ("Attribute '%s' is not of string type!", atlabel.c_str())); } size_t size = H5Tget_size(atype); - *value = String(size, 0); // allocate space + AutoBuffer buf(size); hid_t atype_mem = H5Tget_native_type(atype, H5T_DIR_ASCEND); - H5Aread(attr, atype_mem, const_cast(value->c_str())); + H5Aread(attr, atype_mem, buf.data()); + if (size > 0 && buf[size - 1] == '\0') + size--; + value->assign(buf.data(), size); H5Tclose(atype_mem); H5Tclose(atype); diff --git a/modules/hdf/test/test_hdf5.cpp b/modules/hdf/test/test_hdf5.cpp index a7610f72c..52348c0f2 100644 --- a/modules/hdf/test/test_hdf5.cpp +++ b/modules/hdf/test/test_hdf5.cpp @@ -284,9 +284,27 @@ TEST_F(HDF5_Test, test_attribute_String) m_hdf_io->atwrite(attr_value, attr_name); - String expected_attr_value; - m_hdf_io->atread(&expected_attr_value, attr_name); - EXPECT_EQ(attr_value.compare(expected_attr_value), 0); + String got_attr_value; + m_hdf_io->atread(&got_attr_value, attr_name); + EXPECT_EQ(attr_value, got_attr_value); + + m_hdf_io->close(); +} + +TEST_F(HDF5_Test, test_attribute_String_empty) +{ + reset(); + + String attr_name = "test-empty-string"; + String attr_value; + + m_hdf_io = hdf::open(m_filename); + + m_hdf_io->atwrite(attr_value, attr_name); + + String got_attr_value; + m_hdf_io->atread(&got_attr_value, attr_name); + EXPECT_EQ(attr_value, got_attr_value); m_hdf_io->close(); } From 0bf687bc33df326042548a5bdc76612df04d9361 Mon Sep 17 00:00:00 2001 From: Alexander Alekhin Date: Fri, 7 Sep 2018 17:41:19 +0300 Subject: [PATCH 16/97] xfeatures2d(test): update extraction/invariance tests --- modules/xfeatures2d/CMakeLists.txt | 4 + modules/xfeatures2d/test/test_features2d.cpp | 973 +------------- .../test_rotation_and_scale_invariance.cpp | 1151 ++++------------- 3 files changed, 237 insertions(+), 1891 deletions(-) diff --git a/modules/xfeatures2d/CMakeLists.txt b/modules/xfeatures2d/CMakeLists.txt index 79565b20b..84c8f1056 100644 --- a/modules/xfeatures2d/CMakeLists.txt +++ b/modules/xfeatures2d/CMakeLists.txt @@ -12,3 +12,7 @@ if(NOT boost_status OR NOT vgg_status) endif() ocv_module_include_directories("${DOWNLOAD_DIR}") + +if(TARGET opencv_test_${name}) + ocv_target_include_directories(opencv_test_${name} "${OpenCV_SOURCE_DIR}/modules") # use common files from features2d tests +endif() diff --git a/modules/xfeatures2d/test/test_features2d.cpp b/modules/xfeatures2d/test/test_features2d.cpp index 2b17896f1..d923147c7 100644 --- a/modules/xfeatures2d/test/test_features2d.cpp +++ b/modules/xfeatures2d/test/test_features2d.cpp @@ -42,953 +42,19 @@ #include "test_precomp.hpp" namespace opencv_test { namespace { - const string FEATURES2D_DIR = "features2d"; const string DETECTOR_DIR = FEATURES2D_DIR + "/feature_detectors"; const string DESCRIPTOR_DIR = FEATURES2D_DIR + "/descriptor_extractors"; const string IMAGE_FILENAME = "tsukuba.png"; +}} // namespace -/****************************************************************************************\ -* Regression tests for feature detectors comparing keypoints. * -\****************************************************************************************/ - -class CV_FeatureDetectorTest : public cvtest::BaseTest -{ -public: - CV_FeatureDetectorTest( const string& _name, const Ptr& _fdetector ) : - name(_name), fdetector(_fdetector) {} - -protected: - bool isSimilarKeypoints( const KeyPoint& p1, const KeyPoint& p2 ); - void compareKeypointSets( const vector& validKeypoints, const vector& calcKeypoints ); - - void emptyDataTest(); - void regressionTest(); // TODO test of detect() with mask - - virtual void run( int ); - - string name; - Ptr fdetector; -}; - -void CV_FeatureDetectorTest::emptyDataTest() -{ - // One image. - Mat image; - vector keypoints; - try - { - fdetector->detect( image, keypoints ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "detect() on empty image must not generate exception (1).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - - if( !keypoints.empty() ) - { - ts->printf( cvtest::TS::LOG, "detect() on empty image must return empty keypoints vector (1).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - return; - } - - // Several images. - vector images; - vector > keypointCollection; - try - { - fdetector->detect( images, keypointCollection ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "detect() on empty image vector must not generate exception (2).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } -} - -bool CV_FeatureDetectorTest::isSimilarKeypoints( const KeyPoint& p1, const KeyPoint& p2 ) -{ - const float maxPtDif = 1.f; - const float maxSizeDif = 1.f; - const float maxAngleDif = 2.f; - const float maxResponseDif = 0.1f; - - float dist = (float)cv::norm(p1.pt - p2.pt); - return (dist < maxPtDif && - fabs(p1.size - p2.size) < maxSizeDif && - abs(p1.angle - p2.angle) < maxAngleDif && - abs(p1.response - p2.response) < maxResponseDif && - p1.octave == p2.octave && - p1.class_id == p2.class_id); -} - -void CV_FeatureDetectorTest::compareKeypointSets( const vector& validKeypoints, const vector& calcKeypoints ) -{ - const float maxCountRatioDif = 0.01f; - - // Compare counts of validation and calculated keypoints. - float countRatio = (float)validKeypoints.size() / (float)calcKeypoints.size(); - if( countRatio < 1 - maxCountRatioDif || countRatio > 1.f + maxCountRatioDif ) - { - ts->printf( cvtest::TS::LOG, "Bad keypoints count ratio (validCount = %d, calcCount = %d).\n", - validKeypoints.size(), calcKeypoints.size() ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - return; - } - - int progress = 0, progressCount = (int)(validKeypoints.size() * calcKeypoints.size()); - int badPointCount = 0, commonPointCount = max((int)validKeypoints.size(), (int)calcKeypoints.size()); - for( size_t v = 0; v < validKeypoints.size(); v++ ) - { - int nearestIdx = -1; - float minDist = std::numeric_limits::max(); - - for( size_t c = 0; c < calcKeypoints.size(); c++ ) - { - progress = update_progress( progress, (int)(v*calcKeypoints.size() + c), progressCount, 0 ); - float curDist = (float)cv::norm(calcKeypoints[c].pt - validKeypoints[v].pt); - if( curDist < minDist ) - { - minDist = curDist; - nearestIdx = (int)c; - } - } - - assert( minDist >= 0 ); - if( !isSimilarKeypoints( validKeypoints[v], calcKeypoints[nearestIdx] ) ) - badPointCount++; - } - ts->printf( cvtest::TS::LOG, "badPointCount = %d; validPointCount = %d; calcPointCount = %d\n", - badPointCount, validKeypoints.size(), calcKeypoints.size() ); - if( badPointCount > 0.9 * commonPointCount ) - { - ts->printf( cvtest::TS::LOG, " - Bad accuracy!\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_BAD_ACCURACY ); - return; - } - ts->printf( cvtest::TS::LOG, " - OK\n" ); -} - -void CV_FeatureDetectorTest::regressionTest() -{ - assert( !fdetector.empty() ); - string imgFilename = string(ts->get_data_path()) + FEATURES2D_DIR + "/" + IMAGE_FILENAME; - string resFilename = string(ts->get_data_path()) + DETECTOR_DIR + "/" + string(name) + ".xml.gz"; - - // Read the test image. - Mat image = imread( imgFilename ); - if( image.empty() ) - { - ts->printf( cvtest::TS::LOG, "Image %s can not be read.\n", imgFilename.c_str() ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - - FileStorage fs( resFilename, FileStorage::READ ); - - // Compute keypoints. - vector calcKeypoints; - fdetector->detect( image, calcKeypoints ); - - if( fs.isOpened() ) // Compare computed and valid keypoints. - { - // TODO compare saved feature detector params with current ones - - // Read validation keypoints set. - vector validKeypoints; - read( fs["keypoints"], validKeypoints ); - if( validKeypoints.empty() ) - { - ts->printf( cvtest::TS::LOG, "Keypoints can not be read.\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - - compareKeypointSets( validKeypoints, calcKeypoints ); - } - else // Write detector parameters and computed keypoints as validation data. - { - fs.open( resFilename, FileStorage::WRITE ); - if( !fs.isOpened() ) - { - ts->printf( cvtest::TS::LOG, "File %s can not be opened to write.\n", resFilename.c_str() ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - else - { - fs << "detector_params" << "{"; - fdetector->write( fs ); - fs << "}"; - - write( fs, "keypoints", calcKeypoints ); - } - } -} - -void CV_FeatureDetectorTest::run( int /*start_from*/ ) -{ - if( !fdetector ) - { - ts->printf( cvtest::TS::LOG, "Feature detector is empty.\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - - emptyDataTest(); - regressionTest(); - - ts->set_failed_test_info( cvtest::TS::OK ); -} - -/****************************************************************************************\ -* Regression tests for descriptor extractors. * -\****************************************************************************************/ -static void writeMatInBin( const Mat& mat, const string& filename ) -{ - FILE* f = fopen( filename.c_str(), "wb"); - if( f ) - { - int type = mat.type(); - fwrite( (void*)&mat.rows, sizeof(int), 1, f ); - fwrite( (void*)&mat.cols, sizeof(int), 1, f ); - fwrite( (void*)&type, sizeof(int), 1, f ); - int dataSize = (int)(mat.step * mat.rows * mat.channels()); - fwrite( (void*)&dataSize, sizeof(int), 1, f ); - fwrite( (void*)mat.data, 1, dataSize, f ); - fclose(f); - } -} - -static Mat readMatFromBin( const string& filename ) -{ - FILE* f = fopen( filename.c_str(), "rb" ); - if( f ) - { - int rows, cols, type, dataSize; - size_t elements_read1 = fread( (void*)&rows, sizeof(int), 1, f ); - size_t elements_read2 = fread( (void*)&cols, sizeof(int), 1, f ); - size_t elements_read3 = fread( (void*)&type, sizeof(int), 1, f ); - size_t elements_read4 = fread( (void*)&dataSize, sizeof(int), 1, f ); - CV_Assert(elements_read1 == 1 && elements_read2 == 1 && elements_read3 == 1 && elements_read4 == 1); - - int step = dataSize / rows / CV_ELEM_SIZE(type); - CV_Assert(step >= cols); - - Mat m = Mat( rows, step, type).colRange(0, cols); - - size_t elements_read = fread( m.ptr(), 1, dataSize, f ); - CV_Assert(elements_read == (size_t)(dataSize)); - fclose(f); - - return m; - } - return Mat(); -} - -template -class CV_DescriptorExtractorTest : public cvtest::BaseTest -{ -public: - typedef typename Distance::ValueType ValueType; - typedef typename Distance::ResultType DistanceType; - - CV_DescriptorExtractorTest( const string _name, DistanceType _maxDist, const Ptr& _dextractor, - int imgMode = IMREAD_COLOR, Distance d = Distance()): - name(_name), maxDist(_maxDist), dextractor(_dextractor), imgLoadMode(imgMode), distance(d) {} -protected: - virtual void createDescriptorExtractor() {} - - void compareDescriptors( const Mat& validDescriptors, const Mat& calcDescriptors ) - { - if( validDescriptors.size != calcDescriptors.size || validDescriptors.type() != calcDescriptors.type() ) - { - ts->printf(cvtest::TS::LOG, "Valid and computed descriptors matrices must have the same size and type.\n"); - ts->printf(cvtest::TS::LOG, "Valid size is (%d x %d) actual size is (%d x %d).\n", validDescriptors.rows, validDescriptors.cols, calcDescriptors.rows, calcDescriptors.cols); - ts->printf(cvtest::TS::LOG, "Valid type is %d actual type is %d.\n", validDescriptors.type(), calcDescriptors.type()); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - - CV_Assert( DataType::type == validDescriptors.type() ); - - int dimension = validDescriptors.cols; - DistanceType curMaxDist = std::numeric_limits::min(); - for( int y = 0; y < validDescriptors.rows; y++ ) - { - DistanceType dist = distance( validDescriptors.ptr(y), calcDescriptors.ptr(y), dimension ); - if( dist > curMaxDist ) - curMaxDist = dist; - } - - std::stringstream ss; - ss << "Max distance between valid and computed descriptors " << curMaxDist; - if( curMaxDist <= maxDist ) - ss << "." << endl; - else - { - ss << ">" << maxDist << " - bad accuracy!"<< endl; - ts->set_failed_test_info( cvtest::TS::FAIL_BAD_ACCURACY ); - } - ts->printf(cvtest::TS::LOG, ss.str().c_str() ); - } - - void emptyDataTest() - { - assert( !dextractor.empty() ); - - // One image. - Mat image; - vector keypoints; - Mat descriptors; - - try - { - dextractor->compute( image, keypoints, descriptors ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "compute() on empty image and empty keypoints must not generate exception (1).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - } - - if(imgLoadMode == IMREAD_GRAYSCALE) - image.create( 256, 256, CV_8UC1 ); - else - image.create( 256, 256, CV_8UC3 ); - try - { - dextractor->compute( image, keypoints, descriptors ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "compute() on nonempty image and empty keypoints must not generate exception (1).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - } - - // Several images. - vector images; - vector > keypointsCollection; - vector descriptorsCollection; - try - { - dextractor->compute( images, keypointsCollection, descriptorsCollection ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "compute() on empty images and empty keypoints collection must not generate exception (2).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - } - } - - void regressionTest() - { - assert( !dextractor.empty() ); - - // Read the test image. - string imgFilename = string(ts->get_data_path()) + FEATURES2D_DIR + "/" + IMAGE_FILENAME; - - Mat img = imread( imgFilename, imgLoadMode ); - if( img.empty() ) - { - ts->printf( cvtest::TS::LOG, "Image %s can not be read.\n", imgFilename.c_str() ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - - vector keypoints; - FileStorage fs( string(ts->get_data_path()) + FEATURES2D_DIR + "/keypoints.xml.gz", FileStorage::READ ); - if( fs.isOpened() ) - { - read( fs.getFirstTopLevelNode(), keypoints ); - - Mat calcDescriptors; - double t = (double)getTickCount(); -#ifdef HAVE_OPENCL - if(cv::ocl::useOpenCL()) - { - cv::UMat uimg; - img.copyTo(uimg); - dextractor->compute(uimg, keypoints, calcDescriptors); - } - else -#endif - { - dextractor->compute(img, keypoints, calcDescriptors); - } - t = getTickCount() - t; - ts->printf(cvtest::TS::LOG, "\nAverage time of computing one descriptor = %g ms.\n", t/((double)getTickFrequency()*1000.)/calcDescriptors.rows ); - - if( calcDescriptors.rows != (int)keypoints.size() ) - { - ts->printf( cvtest::TS::LOG, "Count of computed descriptors and keypoints count must be equal.\n" ); - ts->printf( cvtest::TS::LOG, "Count of keypoints is %d.\n", (int)keypoints.size() ); - ts->printf( cvtest::TS::LOG, "Count of computed descriptors is %d.\n", calcDescriptors.rows ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - return; - } - - if( calcDescriptors.cols != dextractor->descriptorSize() || calcDescriptors.type() != dextractor->descriptorType() ) - { - ts->printf( cvtest::TS::LOG, "Incorrect descriptor size or descriptor type.\n" ); - ts->printf( cvtest::TS::LOG, "Expected size is %d.\n", dextractor->descriptorSize() ); - ts->printf( cvtest::TS::LOG, "Calculated size is %d.\n", calcDescriptors.cols ); - ts->printf( cvtest::TS::LOG, "Expected type is %d.\n", dextractor->descriptorType() ); - ts->printf( cvtest::TS::LOG, "Calculated type is %d.\n", calcDescriptors.type() ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - return; - } - - // TODO read and write descriptor extractor parameters and check them - Mat validDescriptors = readDescriptors(); - if( !validDescriptors.empty() ) - compareDescriptors( validDescriptors, calcDescriptors ); - else - { - if( !writeDescriptors( calcDescriptors ) ) - { - ts->printf( cvtest::TS::LOG, "Descriptors can not be written.\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - } - } - else - { - ts->printf( cvtest::TS::LOG, "Compute and write keypoints.\n" ); - fs.open( string(ts->get_data_path()) + FEATURES2D_DIR + "/keypoints.xml.gz", FileStorage::WRITE ); - if( fs.isOpened() ) - { - Ptr fd = SURF::create(); - fd->detect(img, keypoints); - write( fs, "keypoints", keypoints ); - } - else - { - ts->printf(cvtest::TS::LOG, "File for writting keypoints can not be opened.\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - } - } - - void run(int) - { - createDescriptorExtractor(); - if( !dextractor ) - { - ts->printf(cvtest::TS::LOG, "Descriptor extractor is empty.\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_TEST_DATA ); - return; - } - - emptyDataTest(); - regressionTest(); - - ts->set_failed_test_info( cvtest::TS::OK ); - } - - virtual Mat readDescriptors() - { - Mat res = readMatFromBin( string(ts->get_data_path()) + DESCRIPTOR_DIR + "/" + string(name) ); - return res; - } - - virtual bool writeDescriptors( Mat& descs ) - { - writeMatInBin( descs, string(ts->get_data_path()) + DESCRIPTOR_DIR + "/" + string(name) ); - return true; - } - - string name; - const DistanceType maxDist; - Ptr dextractor; - int imgLoadMode; - Distance distance; - -private: - CV_DescriptorExtractorTest& operator=(const CV_DescriptorExtractorTest&) { return *this; } -}; - -/*template -class CV_CalonderDescriptorExtractorTest : public CV_DescriptorExtractorTest -{ -public: - CV_CalonderDescriptorExtractorTest( const char* testName, float _normDif, float _prevTime ) : - CV_DescriptorExtractorTest( testName, _normDif, Ptr(), _prevTime ) - {} - -protected: - virtual void createDescriptorExtractor() - { - CV_DescriptorExtractorTest::dextractor = - new CalonderDescriptorExtractor( string(CV_DescriptorExtractorTest::ts->get_data_path()) + - FEATURES2D_DIR + "/calonder_classifier.rtc"); - } -};*/ - -/****************************************************************************************\ -* Algorithmic tests for descriptor matchers * -\****************************************************************************************/ -class CV_DescriptorMatcherTest : public cvtest::BaseTest -{ -public: - CV_DescriptorMatcherTest( const string& _name, const Ptr& _dmatcher, float _badPart ) : - badPart(_badPart), name(_name), dmatcher(_dmatcher) - {} -protected: - static const int dim = 500; - static const int queryDescCount = 300; // must be even number because we split train data in some cases in two - static const int countFactor = 4; // do not change it - const float badPart; - - virtual void run( int ); - void generateData( Mat& query, Mat& train ); - - //void emptyDataTest(); - void matchTest( const Mat& query, const Mat& train ); - void knnMatchTest( const Mat& query, const Mat& train ); - void radiusMatchTest( const Mat& query, const Mat& train ); - - string name; - Ptr dmatcher; - -private: - CV_DescriptorMatcherTest& operator=(const CV_DescriptorMatcherTest&) { return *this; } -}; - -#if 0 // not used -void CV_DescriptorMatcherTest::emptyDataTest() -{ - assert( !dmatcher.empty() ); - Mat queryDescriptors, trainDescriptors, mask; - vector trainDescriptorCollection, masks; - vector matches; - vector > vmatches; - - try - { - dmatcher->match( queryDescriptors, trainDescriptors, matches, mask ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "match() on empty descriptors must not generate exception (1).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - - try - { - dmatcher->knnMatch( queryDescriptors, trainDescriptors, vmatches, 2, mask ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "knnMatch() on empty descriptors must not generate exception (1).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - - try - { - dmatcher->radiusMatch( queryDescriptors, trainDescriptors, vmatches, 10.f, mask ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "radiusMatch() on empty descriptors must not generate exception (1).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - - try - { - dmatcher->add( trainDescriptorCollection ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "add() on empty descriptors must not generate exception.\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - - try - { - dmatcher->match( queryDescriptors, matches, masks ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "match() on empty descriptors must not generate exception (2).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - - try - { - dmatcher->knnMatch( queryDescriptors, vmatches, 2, masks ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "knnMatch() on empty descriptors must not generate exception (2).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - - try - { - dmatcher->radiusMatch( queryDescriptors, vmatches, 10.f, masks ); - } - catch(...) - { - ts->printf( cvtest::TS::LOG, "radiusMatch() on empty descriptors must not generate exception (2).\n" ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } -} -#endif - -void CV_DescriptorMatcherTest::generateData( Mat& query, Mat& train ) -{ - RNG& rng = theRNG(); - - // Generate query descriptors randomly. - // Descriptor vector elements are integer values. - Mat buf( queryDescCount, dim, CV_32SC1 ); - rng.fill( buf, RNG::UNIFORM, Scalar::all(0), Scalar(3) ); - buf.convertTo( query, CV_32FC1 ); - - // Generate train decriptors as follows: - // copy each query descriptor to train set countFactor times - // and perturb some one element of the copied descriptors in - // in ascending order. General boundaries of the perturbation - // are (0.f, 1.f). - train.create( query.rows*countFactor, query.cols, CV_32FC1 ); - float step = 1.f / countFactor; - for( int qIdx = 0; qIdx < query.rows; qIdx++ ) - { - Mat queryDescriptor = query.row(qIdx); - for( int c = 0; c < countFactor; c++ ) - { - int tIdx = qIdx * countFactor + c; - Mat trainDescriptor = train.row(tIdx); - queryDescriptor.copyTo( trainDescriptor ); - int elem = rng(dim); - float diff = rng.uniform( step*c, step*(c+1) ); - trainDescriptor.at(0, elem) += diff; - } - } -} - -void CV_DescriptorMatcherTest::matchTest( const Mat& query, const Mat& train ) -{ - dmatcher->clear(); - - // test const version of match() - { - vector matches; - dmatcher->match( query, train, matches ); - - if( (int)matches.size() != queryDescCount ) - { - ts->printf(cvtest::TS::LOG, "Incorrect matches count while test match() function (1).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - else - { - int badCount = 0; - for( size_t i = 0; i < matches.size(); i++ ) - { - DMatch match = matches[i]; - if( (match.queryIdx != (int)i) || (match.trainIdx != (int)i*countFactor) || (match.imgIdx != 0) ) - badCount++; - } - if( (float)badCount > (float)queryDescCount*badPart ) - { - ts->printf( cvtest::TS::LOG, "%f - too large bad matches part while test match() function (1).\n", - (float)badCount/(float)queryDescCount ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - } - } - - // test version of match() with add() - { - vector matches; - // make add() twice to test such case - dmatcher->add( vector(1,train.rowRange(0, train.rows/2)) ); - dmatcher->add( vector(1,train.rowRange(train.rows/2, train.rows)) ); - // prepare masks (make first nearest match illegal) - vector masks(2); - for(int mi = 0; mi < 2; mi++ ) - { - masks[mi] = Mat(query.rows, train.rows/2, CV_8UC1, Scalar::all(1)); - for( int di = 0; di < queryDescCount/2; di++ ) - masks[mi].col(di*countFactor).setTo(Scalar::all(0)); - } - - dmatcher->match( query, matches, masks ); - - if( (int)matches.size() != queryDescCount ) - { - ts->printf(cvtest::TS::LOG, "Incorrect matches count while test match() function (2).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - else - { - int badCount = 0; - for( size_t i = 0; i < matches.size(); i++ ) - { - DMatch match = matches[i]; - int shift = dmatcher->isMaskSupported() ? 1 : 0; - { - if( i < queryDescCount/2 ) - { - if( (match.queryIdx != (int)i) || (match.trainIdx != (int)i*countFactor + shift) || (match.imgIdx != 0) ) - badCount++; - } - else - { - if( (match.queryIdx != (int)i) || (match.trainIdx != ((int)i-queryDescCount/2)*countFactor + shift) || (match.imgIdx != 1) ) - badCount++; - } - } - } - if( (float)badCount > (float)queryDescCount*badPart ) - { - ts->printf( cvtest::TS::LOG, "%f - too large bad matches part while test match() function (2).\n", - (float)badCount/(float)queryDescCount ); - ts->set_failed_test_info( cvtest::TS::FAIL_BAD_ACCURACY ); - } - } - } -} - -void CV_DescriptorMatcherTest::knnMatchTest( const Mat& query, const Mat& train ) -{ - dmatcher->clear(); - - // test const version of knnMatch() - { - const int knn = 3; - - vector > matches; - dmatcher->knnMatch( query, train, matches, knn ); - - if( (int)matches.size() != queryDescCount ) - { - ts->printf(cvtest::TS::LOG, "Incorrect matches count while test knnMatch() function (1).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - else - { - int badCount = 0; - for( size_t i = 0; i < matches.size(); i++ ) - { - if( (int)matches[i].size() != knn ) - badCount++; - else - { - int localBadCount = 0; - for( int k = 0; k < knn; k++ ) - { - DMatch match = matches[i][k]; - if( (match.queryIdx != (int)i) || (match.trainIdx != (int)i*countFactor+k) || (match.imgIdx != 0) ) - localBadCount++; - } - badCount += localBadCount > 0 ? 1 : 0; - } - } - if( (float)badCount > (float)queryDescCount*badPart ) - { - ts->printf( cvtest::TS::LOG, "%f - too large bad matches part while test knnMatch() function (1).\n", - (float)badCount/(float)queryDescCount ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - } - } - - // test version of knnMatch() with add() - { - const int knn = 2; - vector > matches; - // make add() twice to test such case - dmatcher->add( vector(1,train.rowRange(0, train.rows/2)) ); - dmatcher->add( vector(1,train.rowRange(train.rows/2, train.rows)) ); - // prepare masks (make first nearest match illegal) - vector masks(2); - for(int mi = 0; mi < 2; mi++ ) - { - masks[mi] = Mat(query.rows, train.rows/2, CV_8UC1, Scalar::all(1)); - for( int di = 0; di < queryDescCount/2; di++ ) - masks[mi].col(di*countFactor).setTo(Scalar::all(0)); - } - - dmatcher->knnMatch( query, matches, knn, masks ); - - if( (int)matches.size() != queryDescCount ) - { - ts->printf(cvtest::TS::LOG, "Incorrect matches count while test knnMatch() function (2).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - else - { - int badCount = 0; - int shift = dmatcher->isMaskSupported() ? 1 : 0; - for( size_t i = 0; i < matches.size(); i++ ) - { - if( (int)matches[i].size() != knn ) - badCount++; - else - { - int localBadCount = 0; - for( int k = 0; k < knn; k++ ) - { - DMatch match = matches[i][k]; - { - if( i < queryDescCount/2 ) - { - if( (match.queryIdx != (int)i) || (match.trainIdx != (int)i*countFactor + k + shift) || - (match.imgIdx != 0) ) - localBadCount++; - } - else - { - if( (match.queryIdx != (int)i) || (match.trainIdx != ((int)i-queryDescCount/2)*countFactor + k + shift) || - (match.imgIdx != 1) ) - localBadCount++; - } - } - } - badCount += localBadCount > 0 ? 1 : 0; - } - } - if( (float)badCount > (float)queryDescCount*badPart ) - { - ts->printf( cvtest::TS::LOG, "%f - too large bad matches part while test knnMatch() function (2).\n", - (float)badCount/(float)queryDescCount ); - ts->set_failed_test_info( cvtest::TS::FAIL_BAD_ACCURACY ); - } - } - } -} - -void CV_DescriptorMatcherTest::radiusMatchTest( const Mat& query, const Mat& train ) -{ - dmatcher->clear(); - // test const version of match() - { - const float radius = 1.f/countFactor; - vector > matches; - dmatcher->radiusMatch( query, train, matches, radius ); - - if( (int)matches.size() != queryDescCount ) - { - ts->printf(cvtest::TS::LOG, "Incorrect matches count while test radiusMatch() function (1).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - else - { - int badCount = 0; - for( size_t i = 0; i < matches.size(); i++ ) - { - if( (int)matches[i].size() != 1 ) - badCount++; - else - { - DMatch match = matches[i][0]; - if( (match.queryIdx != (int)i) || (match.trainIdx != (int)i*countFactor) || (match.imgIdx != 0) ) - badCount++; - } - } - if( (float)badCount > (float)queryDescCount*badPart ) - { - ts->printf( cvtest::TS::LOG, "%f - too large bad matches part while test radiusMatch() function (1).\n", - (float)badCount/(float)queryDescCount ); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - } - } - - // test version of match() with add() - { - int n = 3; - const float radius = 1.f/countFactor * n; - vector > matches; - // make add() twice to test such case - dmatcher->add( vector(1,train.rowRange(0, train.rows/2)) ); - dmatcher->add( vector(1,train.rowRange(train.rows/2, train.rows)) ); - // prepare masks (make first nearest match illegal) - vector masks(2); - for(int mi = 0; mi < 2; mi++ ) - { - masks[mi] = Mat(query.rows, train.rows/2, CV_8UC1, Scalar::all(1)); - for( int di = 0; di < queryDescCount/2; di++ ) - masks[mi].col(di*countFactor).setTo(Scalar::all(0)); - } - - dmatcher->radiusMatch( query, matches, radius, masks ); - - //int curRes = cvtest::TS::OK; - if( (int)matches.size() != queryDescCount ) - { - ts->printf(cvtest::TS::LOG, "Incorrect matches count while test radiusMatch() function (1).\n"); - ts->set_failed_test_info( cvtest::TS::FAIL_INVALID_OUTPUT ); - } - - int badCount = 0; - int shift = dmatcher->isMaskSupported() ? 1 : 0; - int needMatchCount = dmatcher->isMaskSupported() ? n-1 : n; - for( size_t i = 0; i < matches.size(); i++ ) - { - if( (int)matches[i].size() != needMatchCount ) - badCount++; - else - { - int localBadCount = 0; - for( int k = 0; k < needMatchCount; k++ ) - { - DMatch match = matches[i][k]; - { - if( i < queryDescCount/2 ) - { - if( (match.queryIdx != (int)i) || (match.trainIdx != (int)i*countFactor + k + shift) || - (match.imgIdx != 0) ) - localBadCount++; - } - else - { - if( (match.queryIdx != (int)i) || (match.trainIdx != ((int)i-queryDescCount/2)*countFactor + k + shift) || - (match.imgIdx != 1) ) - localBadCount++; - } - } - } - badCount += localBadCount > 0 ? 1 : 0; - } - } - if( (float)badCount > (float)queryDescCount*badPart ) - { - ts->printf( cvtest::TS::LOG, "%f - too large bad matches part while test radiusMatch() function (2).\n", - (float)badCount/(float)queryDescCount ); - ts->set_failed_test_info( cvtest::TS::FAIL_BAD_ACCURACY ); - } - } -} - -void CV_DescriptorMatcherTest::run( int ) -{ - Mat query, train; - generateData( query, train ); - - matchTest( query, train ); - - knnMatchTest( query, train ); - - radiusMatchTest( query, train ); -} - -/****************************************************************************************\ -* Tests registrations * -\****************************************************************************************/ +#include "features2d/test/test_detectors_regression.impl.hpp" +#include "features2d/test/test_descriptors_regression.impl.hpp" -/* - * Detectors - */ +namespace opencv_test { namespace { #ifdef OPENCV_ENABLE_NONFREE -TEST( Features2d_Detector_SIFT, regression ) +TEST( Features2d_Detector_SIFT, regression) { CV_FeatureDetectorTest test( "detector-sift", SIFT::create() ); test.safe_run(); @@ -1077,9 +143,8 @@ TEST( Features2d_DescriptorExtractor_DAISY, regression ) TEST( Features2d_DescriptorExtractor_FREAK, regression ) { - // TODO adjust the parameters below - CV_DescriptorExtractorTest test( "descriptor-freak", (CV_DescriptorExtractorTest::DistanceType)12.f, - FREAK::create(), IMREAD_GRAYSCALE ); + CV_DescriptorExtractorTest test("descriptor-freak", (CV_DescriptorExtractorTest::DistanceType)12.f, + FREAK::create()); test.safe_run(); } @@ -1190,23 +255,6 @@ TEST( Features2d_DescriptorExtractor_BINBOOST_256, regression ) } -/*#if CV_SSE2 -TEST( Features2d_DescriptorExtractor_Calonder_uchar, regression ) -{ - CV_CalonderDescriptorExtractorTest > test( "descriptor-calonder-uchar", - std::numeric_limits::epsilon() + 1, - 0.0132175f ); - test.safe_run(); -} - -TEST( Features2d_DescriptorExtractor_Calonder_float, regression ) -{ - CV_CalonderDescriptorExtractorTest > test( "descriptor-calonder-float", - std::numeric_limits::epsilon(), - 0.0221308f ); - test.safe_run(); -} -#endif*/ // CV_SSE2 #ifdef OPENCV_ENABLE_NONFREE TEST(Features2d_BruteForceDescriptorMatcher_knnMatch, regression) { @@ -1259,13 +307,6 @@ TEST(Features2d_BruteForceDescriptorMatcher_knnMatch, regression) } #endif -/*TEST(Features2d_DescriptorExtractorParamTest, regression) -{ - Ptr s = DescriptorExtractor::create("SURF"); - ASSERT_STREQ(s->paramHelp("extended").c_str(), ""); -} -*/ - class CV_DetectPlanarTest : public cvtest::BaseTest { public: diff --git a/modules/xfeatures2d/test/test_rotation_and_scale_invariance.cpp b/modules/xfeatures2d/test/test_rotation_and_scale_invariance.cpp index 869c2547d..820c477b0 100644 --- a/modules/xfeatures2d/test/test_rotation_and_scale_invariance.cpp +++ b/modules/xfeatures2d/test/test_rotation_and_scale_invariance.cpp @@ -1,850 +1,262 @@ -/*M/////////////////////////////////////////////////////////////////////////////////////// -// -// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. -// -// By downloading, copying, installing or using the software you agree to this license. -// If you do not agree to this license, do not download, install, -// copy or use the software. -// -// -// Intel License Agreement -// For Open Source Computer Vision Library -// -// Copyright (C) 2000, Intel Corporation, all rights reserved. -// Third party copyrights are property of their respective owners. -// -// Redistribution and use in source and binary forms, with or without modification, -// are permitted provided that the following conditions are met: -// -// * Redistribution's of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// -// * Redistribution's in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// * The name of Intel Corporation may not be used to endorse or promote products -// derived from this software without specific prior written permission. -// -// This software is provided by the copyright holders and contributors "as is" and -// any express or implied warranties, including, but not limited to, the implied -// warranties of merchantability and fitness for a particular purpose are disclaimed. -// In no event shall the Intel Corporation or contributors be liable for any direct, -// indirect, incidental, special, exemplary, or consequential damages -// (including, but not limited to, procurement of substitute goods or services; -// loss of use, data, or profits; or business interruption) however caused -// and on any theory of liability, whether in contract, strict liability, -// or tort (including negligence or otherwise) arising in any way out of -// the use of this software, even if advised of the possibility of such damage. -// -//M*/ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html #include "test_precomp.hpp" -namespace opencv_test { namespace { - -const string IMAGE_TSUKUBA = "/features2d/tsukuba.png"; -const string IMAGE_BIKES = "/detectors_descriptors_evaluation/images_datasets/bikes/img1.png"; - -#define SHOW_DEBUG_LOG 0 - -static -Mat generateHomography(float angle) -{ - // angle - rotation around Oz in degrees - float angleRadian = static_cast(angle * CV_PI / 180); - Mat H = Mat::eye(3, 3, CV_32FC1); - H.at(0,0) = H.at(1,1) = std::cos(angleRadian); - H.at(0,1) = -std::sin(angleRadian); - H.at(1,0) = std::sin(angleRadian); - - return H; -} - -static -Mat rotateImage(const Mat& srcImage, float angle, Mat& dstImage, Mat& dstMask) -{ - // angle - rotation around Oz in degrees - float diag = std::sqrt(static_cast(srcImage.cols * srcImage.cols + srcImage.rows * srcImage.rows)); - Mat LUShift = Mat::eye(3, 3, CV_32FC1); // left up - LUShift.at(0,2) = static_cast(-srcImage.cols/2); - LUShift.at(1,2) = static_cast(-srcImage.rows/2); - Mat RDShift = Mat::eye(3, 3, CV_32FC1); // right down - RDShift.at(0,2) = diag/2; - RDShift.at(1,2) = diag/2; - Size sz(cvRound(diag), cvRound(diag)); - - Mat srcMask(srcImage.size(), CV_8UC1, Scalar(255)); - - Mat H = RDShift * generateHomography(angle) * LUShift; - warpPerspective(srcImage, dstImage, H, sz); - warpPerspective(srcMask, dstMask, H, sz); - - return H; -} - -void rotateKeyPoints(const vector& src, const Mat& H, float angle, vector& dst) -{ - // suppose that H is rotation given from rotateImage() and angle has value passed to rotateImage() - vector srcCenters, dstCenters; - KeyPoint::convert(src, srcCenters); - - perspectiveTransform(srcCenters, dstCenters, H); - - dst = src; - for(size_t i = 0; i < dst.size(); i++) - { - dst[i].pt = dstCenters[i]; - float dstAngle = src[i].angle + angle; - if(dstAngle >= 360.f) - dstAngle -= 360.f; - dst[i].angle = dstAngle; - } -} - -void scaleKeyPoints(const vector& src, vector& dst, float scale) -{ - dst.resize(src.size()); - for(size_t i = 0; i < src.size(); i++) - dst[i] = KeyPoint(src[i].pt.x * scale, src[i].pt.y * scale, src[i].size * scale, src[i].angle); -} - -static -float calcCirclesIntersectArea(const Point2f& p0, float r0, const Point2f& p1, float r1) -{ - float c = static_cast(cv::norm(p0 - p1)), sqr_c = c * c; - - float sqr_r0 = r0 * r0; - float sqr_r1 = r1 * r1; - - if(r0 + r1 <= c) - return 0; +#include "features2d/test/test_detectors_invariance.impl.hpp" // main OpenCV repo +#include "features2d/test/test_descriptors_invariance.impl.hpp" // main OpenCV repo - float minR = std::min(r0, r1); - float maxR = std::max(r0, r1); - if(c + minR <= maxR) - return static_cast(CV_PI * minR * minR); - - float cos_halfA0 = (sqr_r0 + sqr_c - sqr_r1) / (2 * r0 * c); - float cos_halfA1 = (sqr_r1 + sqr_c - sqr_r0) / (2 * r1 * c); - - float A0 = 2 * acos(cos_halfA0); - float A1 = 2 * acos(cos_halfA1); - - return 0.5f * sqr_r0 * (A0 - sin(A0)) + - 0.5f * sqr_r1 * (A1 - sin(A1)); -} - -static -float calcIntersectRatio(const Point2f& p0, float r0, const Point2f& p1, float r1) -{ - float intersectArea = calcCirclesIntersectArea(p0, r0, p1, r1); - float unionArea = static_cast(CV_PI) * (r0 * r0 + r1 * r1) - intersectArea; - return intersectArea / unionArea; -} - -static -void matchKeyPoints(const vector& keypoints0, const Mat& H, - const vector& keypoints1, - vector& matches) -{ - vector points0; - KeyPoint::convert(keypoints0, points0); - Mat points0t; - if(H.empty()) - points0t = Mat(points0); - else - perspectiveTransform(Mat(points0), points0t, H); - - matches.clear(); - vector usedMask(keypoints1.size(), 0); - for(int i0 = 0; i0 < static_cast(keypoints0.size()); i0++) - { - int nearestPointIndex = -1; - float maxIntersectRatio = 0.f; - const float r0 = 0.5f * keypoints0[i0].size; - for(size_t i1 = 0; i1 < keypoints1.size(); i1++) - { - float r1 = 0.5f * keypoints1[i1].size; - float intersectRatio = calcIntersectRatio(points0t.at(i0), r0, - keypoints1[i1].pt, r1); - if(intersectRatio > maxIntersectRatio) - { - maxIntersectRatio = intersectRatio; - nearestPointIndex = static_cast(i1); - } - } - - matches.push_back(DMatch(i0, nearestPointIndex, maxIntersectRatio)); - if(nearestPointIndex >= 0) - usedMask[nearestPointIndex] = 1; - } -} - -static void removeVerySmallKeypoints(vector& keypoints) -{ - size_t i, j = 0, n = keypoints.size(); - for( i = 0; i < n; i++ ) - { - if( (keypoints[i].octave & 128) != 0 ) - ; - else - keypoints[j++] = keypoints[i]; - } - keypoints.resize(j); -} +namespace opencv_test { namespace { +static const char* const IMAGE_TSUKUBA = "features2d/tsukuba.png"; +static const char* const IMAGE_BIKES = "detectors_descriptors_evaluation/images_datasets/bikes/img1.png"; -class DetectorRotationInvarianceTest : public cvtest::BaseTest -{ -public: - DetectorRotationInvarianceTest(const Ptr& _featureDetector, - float _minKeyPointMatchesRatio, - float _minAngleInliersRatio) : - featureDetector(_featureDetector), - minKeyPointMatchesRatio(_minKeyPointMatchesRatio), - minAngleInliersRatio(_minAngleInliersRatio) - { - CV_Assert(featureDetector); - } +// ========================== ROTATION INVARIANCE ============================= -protected: +#ifdef OPENCV_ENABLE_NONFREE - void run(int) - { - const string imageFilename = string(ts->get_data_path()) + IMAGE_TSUKUBA; - - // Read test data - Mat image0 = imread(imageFilename), image1, mask1; - if(image0.empty()) - { - ts->printf(cvtest::TS::LOG, "Image %s can not be read.\n", imageFilename.c_str()); - ts->set_failed_test_info(cvtest::TS::FAIL_INVALID_TEST_DATA); - return; - } - - vector keypoints0; - featureDetector->detect(image0, keypoints0); - removeVerySmallKeypoints(keypoints0); - if(keypoints0.size() < 15) - CV_Error(Error::StsAssert, "Detector gives too few points in a test image\n"); - - const int maxAngle = 360, angleStep = 15; - for(int angle = 0; angle < maxAngle; angle += angleStep) - { - Mat H = rotateImage(image0, static_cast(angle), image1, mask1); - - vector keypoints1; - featureDetector->detect(image1, keypoints1, mask1); - removeVerySmallKeypoints(keypoints1); - - vector matches; - matchKeyPoints(keypoints0, H, keypoints1, matches); - - int angleInliersCount = 0; - - const float minIntersectRatio = 0.5f; - int keyPointMatchesCount = 0; - for(size_t m = 0; m < matches.size(); m++) - { - if(matches[m].distance < minIntersectRatio) - continue; - - keyPointMatchesCount++; - - // Check does this inlier have consistent angles - const float maxAngleDiff = 15.f; // grad - float angle0 = keypoints0[matches[m].queryIdx].angle; - float angle1 = keypoints1[matches[m].trainIdx].angle; - if(angle0 == -1 || angle1 == -1) - CV_Error(Error::StsBadArg, "Given FeatureDetector is not rotation invariant, it can not be tested here.\n"); - CV_Assert(angle0 >= 0.f && angle0 < 360.f); - CV_Assert(angle1 >= 0.f && angle1 < 360.f); - - float rotAngle0 = angle0 + angle; - if(rotAngle0 >= 360.f) - rotAngle0 -= 360.f; - - float angleDiff = std::max(rotAngle0, angle1) - std::min(rotAngle0, angle1); - angleDiff = std::min(angleDiff, static_cast(360.f - angleDiff)); - CV_Assert(angleDiff >= 0.f); - bool isAngleCorrect = angleDiff < maxAngleDiff; - if(isAngleCorrect) - angleInliersCount++; - } - - float keyPointMatchesRatio = static_cast(keyPointMatchesCount) / keypoints0.size(); - if(keyPointMatchesRatio < minKeyPointMatchesRatio) - { - ts->printf(cvtest::TS::LOG, "Incorrect keyPointMatchesRatio: curr = %f, min = %f.\n", - keyPointMatchesRatio, minKeyPointMatchesRatio); - ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY); - return; - } - - if(keyPointMatchesCount) - { - float angleInliersRatio = static_cast(angleInliersCount) / keyPointMatchesCount; - if(angleInliersRatio < minAngleInliersRatio) - { - ts->printf(cvtest::TS::LOG, "Incorrect angleInliersRatio: curr = %f, min = %f.\n", - angleInliersRatio, minAngleInliersRatio); - ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY); - return; - } - } -#if SHOW_DEBUG_LOG - std::cout << "keyPointMatchesRatio - " << keyPointMatchesRatio - << " - angleInliersRatio " << static_cast(angleInliersCount) / keyPointMatchesCount << std::endl; -#endif - } - ts->set_failed_test_info( cvtest::TS::OK ); - } +INSTANTIATE_TEST_CASE_P(SURF, DetectorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, SURF::create(), 0.40f, 0.76f) +)); - Ptr featureDetector; - float minKeyPointMatchesRatio; - float minAngleInliersRatio; -}; +INSTANTIATE_TEST_CASE_P(SIFT, DetectorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, SIFT::create(), 0.45f, 0.70f) +)); -class DescriptorRotationInvarianceTest : public cvtest::BaseTest -{ -public: - DescriptorRotationInvarianceTest(const Ptr& _featureDetector, - const Ptr& _descriptorExtractor, - int _normType, - float _minDescInliersRatio, int imgLoad = IMREAD_COLOR) : - featureDetector(_featureDetector), - descriptorExtractor(_descriptorExtractor), - normType(_normType), - minDescInliersRatio(_minDescInliersRatio), - imgLoadMode(imgLoad) - { - CV_Assert(featureDetector); - CV_Assert(descriptorExtractor); - } +INSTANTIATE_TEST_CASE_P(SURF, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, SURF::create(), SURF::create(), 0.83f) +)); -protected: +INSTANTIATE_TEST_CASE_P(SIFT, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, SIFT::create(), SIFT::create(), 0.98f) +)); - void run(int) - { - const string imageFilename = string(ts->get_data_path()) + IMAGE_TSUKUBA; - - // Read test data - Mat image0 = imread(imageFilename, imgLoadMode), image1, mask1; - if(image0.empty()) - { - ts->printf(cvtest::TS::LOG, "Image %s can not be read.\n", imageFilename.c_str()); - ts->set_failed_test_info(cvtest::TS::FAIL_INVALID_TEST_DATA); - return; - } - - vector keypoints0; - Mat descriptors0; - featureDetector->detect(image0, keypoints0); - removeVerySmallKeypoints(keypoints0); - if(keypoints0.size() < 15) - CV_Error(Error::StsAssert, "Detector gives too few points in a test image\n"); - descriptorExtractor->compute(image0, keypoints0, descriptors0); - - BFMatcher bfmatcher(normType); - - const float minIntersectRatio = 0.5f; - const int maxAngle = 360, angleStep = 15; - for(int angle = 0; angle < maxAngle; angle += angleStep) - { - Mat H = rotateImage(image0, static_cast(angle), image1, mask1); - - vector keypoints1; - rotateKeyPoints(keypoints0, H, static_cast(angle), keypoints1); - Mat descriptors1; - descriptorExtractor->compute(image1, keypoints1, descriptors1); - - vector descMatches; - bfmatcher.match(descriptors0, descriptors1, descMatches); - - int descInliersCount = 0; - for(size_t m = 0; m < descMatches.size(); m++) - { - const KeyPoint& transformed_p0 = keypoints1[descMatches[m].queryIdx]; - const KeyPoint& p1 = keypoints1[descMatches[m].trainIdx]; - if(calcIntersectRatio(transformed_p0.pt, 0.5f * transformed_p0.size, - p1.pt, 0.5f * p1.size) >= minIntersectRatio) - { - descInliersCount++; - } - } - - float descInliersRatio = static_cast(descInliersCount) / keypoints0.size(); - if(descInliersRatio < minDescInliersRatio) - { - ts->printf(cvtest::TS::LOG, "Incorrect descInliersRatio: curr = %f, min = %f.\n", - descInliersRatio, minDescInliersRatio); - ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY); - return; - } -#if SHOW_DEBUG_LOG - std::cout << "descInliersRatio " << static_cast(descInliersCount) / keypoints0.size() << std::endl; -#endif - } - ts->set_failed_test_info( cvtest::TS::OK ); - } +INSTANTIATE_TEST_CASE_P(LATCH, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, SIFT::create(), LATCH::create(), 0.9999f) +)); - Ptr featureDetector; - Ptr descriptorExtractor; - int normType; - float minDescInliersRatio; - int imgLoadMode; -}; +#endif // NONFREE +INSTANTIATE_TEST_CASE_P(DAISY, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + BRISK::create(), + DAISY::create(15, 3, 8, 8, DAISY::NRM_NONE, noArray(), true, true), + 0.79f) +)); +INSTANTIATE_TEST_CASE_P(VGG120, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + KAZE::create(), + VGG::create(VGG::VGG_120, 1.4f, true, true, 48.0f, false), + 0.97f) +)); +INSTANTIATE_TEST_CASE_P(VGG80, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + KAZE::create(), + VGG::create(VGG::VGG_80, 1.4f, true, true, 48.0f, false), + 0.97f) +)); +INSTANTIATE_TEST_CASE_P(VGG64, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + KAZE::create(), + VGG::create(VGG::VGG_64, 1.4f, true, true, 48.0f, false), + 0.97f) +)); +INSTANTIATE_TEST_CASE_P(VGG48, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + KAZE::create(), + VGG::create(VGG::VGG_48, 1.4f, true, true, 48.0f, false), + 0.97f) +)); -class DetectorScaleInvarianceTest : public cvtest::BaseTest -{ -public: - DetectorScaleInvarianceTest(const Ptr& _featureDetector, - float _minKeyPointMatchesRatio, - float _minScaleInliersRatio) : - featureDetector(_featureDetector), - minKeyPointMatchesRatio(_minKeyPointMatchesRatio), - minScaleInliersRatio(_minScaleInliersRatio) - { - CV_Assert(featureDetector); - } -protected: +#ifdef OPENCV_ENABLE_NONFREE - void run(int) - { - const string imageFilename = string(ts->get_data_path()) + IMAGE_BIKES; - - // Read test data - Mat image0 = imread(imageFilename); - if(image0.empty()) - { - ts->printf(cvtest::TS::LOG, "Image %s can not be read.\n", imageFilename.c_str()); - ts->set_failed_test_info(cvtest::TS::FAIL_INVALID_TEST_DATA); - return; - } - - vector keypoints0; - featureDetector->detect(image0, keypoints0); - removeVerySmallKeypoints(keypoints0); - if(keypoints0.size() < 15) - CV_Error(Error::StsAssert, "Detector gives too few points in a test image\n"); - - for(int scaleIdx = 1; scaleIdx <= 3; scaleIdx++) - { - float scale = 1.f + scaleIdx * 0.5f; - Mat image1; - resize(image0, image1, Size(), 1./scale, 1./scale, INTER_LINEAR_EXACT); - - vector keypoints1, osiKeypoints1; // osi - original size image - featureDetector->detect(image1, keypoints1); - removeVerySmallKeypoints(keypoints1); - if(keypoints1.size() < 15) - CV_Error(Error::StsAssert, "Detector gives too few points in a test image\n"); - - if(keypoints1.size() > keypoints0.size()) - { - ts->printf(cvtest::TS::LOG, "Strange behavior of the detector. " - "It gives more points count in an image of the smaller size.\n" - "original size (%d, %d), keypoints count = %d\n" - "reduced size (%d, %d), keypoints count = %d\n", - image0.cols, image0.rows, keypoints0.size(), - image1.cols, image1.rows, keypoints1.size()); - ts->set_failed_test_info(cvtest::TS::FAIL_INVALID_OUTPUT); - return; - } - - scaleKeyPoints(keypoints1, osiKeypoints1, scale); - - vector matches; - // image1 is query image (it's reduced image0) - // image0 is train image - matchKeyPoints(osiKeypoints1, Mat(), keypoints0, matches); - - const float minIntersectRatio = 0.5f; - int keyPointMatchesCount = 0; - int scaleInliersCount = 0; - - for(size_t m = 0; m < matches.size(); m++) - { - if(matches[m].distance < minIntersectRatio) - continue; - - keyPointMatchesCount++; - - // Check does this inlier have consistent sizes - const float maxSizeDiff = 0.8f;//0.9f; // grad - float size0 = keypoints0[matches[m].trainIdx].size; - float size1 = osiKeypoints1[matches[m].queryIdx].size; - CV_Assert(size0 > 0 && size1 > 0); - if(std::min(size0, size1) > maxSizeDiff * std::max(size0, size1)) - scaleInliersCount++; - } - - float keyPointMatchesRatio = static_cast(keyPointMatchesCount) / keypoints1.size(); - if(keyPointMatchesRatio < minKeyPointMatchesRatio) - { - ts->printf(cvtest::TS::LOG, "Incorrect keyPointMatchesRatio: curr = %f, min = %f.\n", - keyPointMatchesRatio, minKeyPointMatchesRatio); - ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY); - return; - } - - if(keyPointMatchesCount) - { - float scaleInliersRatio = static_cast(scaleInliersCount) / keyPointMatchesCount; - if(scaleInliersRatio < minScaleInliersRatio) - { - ts->printf(cvtest::TS::LOG, "Incorrect scaleInliersRatio: curr = %f, min = %f.\n", - scaleInliersRatio, minScaleInliersRatio); - ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY); - return; - } - } -#if SHOW_DEBUG_LOG - std::cout << "keyPointMatchesRatio - " << keyPointMatchesRatio - << " - scaleInliersRatio " << static_cast(scaleInliersCount) / keyPointMatchesCount << std::endl; +INSTANTIATE_TEST_CASE_P(BRIEF_64, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BriefDescriptorExtractor::create(64,true), + 0.98f) +)); + +INSTANTIATE_TEST_CASE_P(BRIEF_32, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BriefDescriptorExtractor::create(32,true), + 0.97f) +)); + +INSTANTIATE_TEST_CASE_P(BRIEF_16, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BriefDescriptorExtractor::create(16, true), + 0.98f) +)); + +INSTANTIATE_TEST_CASE_P(FREAK, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + FREAK::create(), + 0.90f) +)); + +INSTANTIATE_TEST_CASE_P(BoostDesc_BGM, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BoostDesc::create(BoostDesc::BGM, true, 6.25f), + 0.999f) +)); + +INSTANTIATE_TEST_CASE_P(BoostDesc_BGM_HARD, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BoostDesc::create(BoostDesc::BGM_HARD, true, 6.25f), + 0.98f) +)); + +INSTANTIATE_TEST_CASE_P(BoostDesc_BGM_BILINEAR, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BoostDesc::create(BoostDesc::BGM_BILINEAR, true, 6.25f), + 0.98f) +)); + +INSTANTIATE_TEST_CASE_P(BoostDesc_BGM_LBGM, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BoostDesc::create(BoostDesc::LBGM, true, 6.25f), + 0.999f) +)); + +INSTANTIATE_TEST_CASE_P(BoostDesc_BINBOOST_64, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BoostDesc::create(BoostDesc::BINBOOST_64, true, 6.25f), + 0.98f) +)); + +INSTANTIATE_TEST_CASE_P(BoostDesc_BINBOOST_128, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BoostDesc::create(BoostDesc::BINBOOST_128, true, 6.25f), + 0.98f) +)); + +INSTANTIATE_TEST_CASE_P(BoostDesc_BINBOOST_256, DescriptorRotationInvariance, Values( + make_tuple(IMAGE_TSUKUBA, + SURF::create(), + BoostDesc::create(BoostDesc::BINBOOST_256, true, 6.25f), + 0.999f) +)); #endif - } - ts->set_failed_test_info( cvtest::TS::OK ); - } - Ptr featureDetector; - float minKeyPointMatchesRatio; - float minScaleInliersRatio; -}; -class DescriptorScaleInvarianceTest : public cvtest::BaseTest -{ -public: - DescriptorScaleInvarianceTest(const Ptr& _featureDetector, - const Ptr& _descriptorExtractor, - int _normType, - float _minDescInliersRatio) : - featureDetector(_featureDetector), - descriptorExtractor(_descriptorExtractor), - normType(_normType), - minDescInliersRatio(_minDescInliersRatio) - { - CV_Assert(featureDetector); - CV_Assert(descriptorExtractor); - } -protected: +// ============================ SCALE INVARIANCE ============================== - void run(int) - { - const string imageFilename = string(ts->get_data_path()) + IMAGE_BIKES; - - // Read test data - Mat image0 = imread(imageFilename); - if(image0.empty()) - { - ts->printf(cvtest::TS::LOG, "Image %s can not be read.\n", imageFilename.c_str()); - ts->set_failed_test_info(cvtest::TS::FAIL_INVALID_TEST_DATA); - return; - } - - vector keypoints0; - featureDetector->detect(image0, keypoints0); - removeVerySmallKeypoints(keypoints0); - if(keypoints0.size() < 15) - CV_Error(Error::StsAssert, "Detector gives too few points in a test image\n"); - Mat descriptors0; - descriptorExtractor->compute(image0, keypoints0, descriptors0); - - BFMatcher bfmatcher(normType); - for(int scaleIdx = 1; scaleIdx <= 3; scaleIdx++) - { - float scale = 1.f + scaleIdx * 0.5f; - - Mat image1; - resize(image0, image1, Size(), 1./scale, 1./scale, INTER_LINEAR_EXACT); - - vector keypoints1; - scaleKeyPoints(keypoints0, keypoints1, 1.0f/scale); - Mat descriptors1; - descriptorExtractor->compute(image1, keypoints1, descriptors1); - - vector descMatches; - bfmatcher.match(descriptors0, descriptors1, descMatches); - - const float minIntersectRatio = 0.5f; - int descInliersCount = 0; - for(size_t m = 0; m < descMatches.size(); m++) - { - const KeyPoint& transformed_p0 = keypoints0[descMatches[m].queryIdx]; - const KeyPoint& p1 = keypoints0[descMatches[m].trainIdx]; - if(calcIntersectRatio(transformed_p0.pt, 0.5f * transformed_p0.size, - p1.pt, 0.5f * p1.size) >= minIntersectRatio) - { - descInliersCount++; - } - } - - float descInliersRatio = static_cast(descInliersCount) / keypoints0.size(); - if(descInliersRatio < minDescInliersRatio) - { - ts->printf(cvtest::TS::LOG, "Incorrect descInliersRatio: curr = %f, min = %f.\n", - descInliersRatio, minDescInliersRatio); - ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY); - return; - } -#if SHOW_DEBUG_LOG - std::cout << "descInliersRatio " << static_cast(descInliersCount) / keypoints0.size() << std::endl; -#endif - } - ts->set_failed_test_info( cvtest::TS::OK ); - } - Ptr featureDetector; - Ptr descriptorExtractor; - int normType; - float minKeyPointMatchesRatio; - float minDescInliersRatio; -}; - -// Tests registration - -/* - * Detector's rotation invariance check - */ #ifdef OPENCV_ENABLE_NONFREE -TEST(Features2d_RotationInvariance_Detector_SURF, regression) -{ - DetectorRotationInvarianceTest test(SURF::create(), - 0.65f, - 0.76f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Detector_SIFT, DISABLED_regression) -{ - DetectorRotationInvarianceTest test(SIFT::create(), - 0.45f, - 0.70f); - test.safe_run(); -} +INSTANTIATE_TEST_CASE_P(SURF, DetectorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, SURF::create(), 0.64f, 0.84f) +)); + +INSTANTIATE_TEST_CASE_P(SIFT, DetectorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, SIFT::create(), 0.55f, 0.99f) +)); + +INSTANTIATE_TEST_CASE_P(SURF, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, SURF::create(), SURF::create(), 0.7f) +)); +INSTANTIATE_TEST_CASE_P(SIFT, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, SIFT::create(), SIFT::create(), 0.3f) +)); +#endif // NONFREE -/* - * Descriptors's rotation invariance check - */ -TEST(Features2d_RotationInvariance_Descriptor_SURF, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - SURF::create(), - NORM_L1, - 0.83f); - test.safe_run(); -} -TEST(Features2d_RotationInvariance_Descriptor_SIFT, regression) -{ - DescriptorRotationInvarianceTest test(SIFT::create(), - SIFT::create(), - NORM_L1, - 0.98f); - test.safe_run(); -} +#if 0 // DAISY is not scale invariant +INSTANTIATE_TEST_CASE_P(DISABLED_DAISY, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + BRISK::create(), + DAISY::create(15, 3, 8, 8, DAISY::NRM_NONE, noArray(), true, true), + 0.1f) +)); +#endif -TEST(Features2d_RotationInvariance_Descriptor_LATCH, regression) -{ - DescriptorRotationInvarianceTest test(SIFT::create(), - LATCH::create(), - NORM_HAMMING, - 0.9999f); - test.safe_run(); -} +INSTANTIATE_TEST_CASE_P(VGG120, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + KAZE::create(), + VGG::create(VGG::VGG_120, 1.4f, true, true, 48.0f, false), + 0.98f) +)); +INSTANTIATE_TEST_CASE_P(VGG80, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + KAZE::create(), + VGG::create(VGG::VGG_80, 1.4f, true, true, 48.0f, false), + 0.98f) +)); +INSTANTIATE_TEST_CASE_P(VGG64, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + KAZE::create(), + VGG::create(VGG::VGG_64, 1.4f, true, true, 48.0f, false), + 0.97f) +)); +INSTANTIATE_TEST_CASE_P(VGG48, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + KAZE::create(), + VGG::create(VGG::VGG_48, 1.4f, true, true, 48.0f, false), + 0.93f) +)); + +#ifdef OPENCV_ENABLE_NONFREE // SURF detector is used in tests +INSTANTIATE_TEST_CASE_P(BoostDesc_BGM, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + SURF::create(), + BoostDesc::create(BoostDesc::BGM, true, 6.25f), + 0.98f) +)); +INSTANTIATE_TEST_CASE_P(BoostDesc_BGM_HARD, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + SURF::create(), + BoostDesc::create(BoostDesc::BGM_HARD, true, 6.25f), + 0.75f) +)); +INSTANTIATE_TEST_CASE_P(BoostDesc_BGM_BILINEAR, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + SURF::create(), + BoostDesc::create(BoostDesc::BGM_BILINEAR, true, 6.25f), + 0.95f) +)); +INSTANTIATE_TEST_CASE_P(BoostDesc_LBGM, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + SURF::create(), + BoostDesc::create(BoostDesc::LBGM, true, 6.25f), + 0.95f) +)); +INSTANTIATE_TEST_CASE_P(BoostDesc_BINBOOST_64, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + SURF::create(), + BoostDesc::create(BoostDesc::BINBOOST_64, true, 6.25f), + 0.75f) +)); +INSTANTIATE_TEST_CASE_P(BoostDesc_BINBOOST_128, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + SURF::create(), + BoostDesc::create(BoostDesc::BINBOOST_128, true, 6.25f), + 0.95f) +)); +INSTANTIATE_TEST_CASE_P(BoostDesc_BINBOOST_256, DescriptorScaleInvariance, Values( + make_tuple(IMAGE_BIKES, + SURF::create(), + BoostDesc::create(BoostDesc::BINBOOST_256, true, 6.25f), + 0.98f) +)); #endif // NONFREE -TEST(DISABLED_Features2d_RotationInvariance_Descriptor_DAISY, regression) -{ - DescriptorRotationInvarianceTest test(BRISK::create(), - DAISY::create(15, 3, 8, 8, DAISY::NRM_NONE, noArray(), true, true), - NORM_L1, - 0.79f); - test.safe_run(); -} -TEST(Features2d_RotationInvariance_Descriptor_VGG120, regression) -{ - DescriptorRotationInvarianceTest test(KAZE::create(), - VGG::create(VGG::VGG_120, 1.4f, true, true, 48.0f, false), - NORM_L1, - 1.00f); - test.safe_run(); -} -TEST(Features2d_RotationInvariance_Descriptor_VGG80, regression) -{ - DescriptorRotationInvarianceTest test(KAZE::create(), - VGG::create(VGG::VGG_80, 1.4f, true, true, 48.0f, false), - NORM_L1, - 1.00f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_VGG64, regression) -{ - DescriptorRotationInvarianceTest test(KAZE::create(), - VGG::create(VGG::VGG_64, 1.4f, true, true, 48.0f, false), - NORM_L1, - 1.00f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_VGG48, regression) -{ - DescriptorRotationInvarianceTest test(KAZE::create(), - VGG::create(VGG::VGG_48, 1.4f, true, true, 48.0f, false), - NORM_L1, - 1.00f); - test.safe_run(); -} +// ============================== OTHER TESTS ================================= #ifdef OPENCV_ENABLE_NONFREE -TEST(Features2d_RotationInvariance_Descriptor_BRIEF_64, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BriefDescriptorExtractor::create(64,true), - NORM_L1, - 0.98f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BRIEF_32, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BriefDescriptorExtractor::create(32,true), - NORM_L1, - 0.97f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BRIEF_16, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BriefDescriptorExtractor::create(16,true), - NORM_L1, - 0.85f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_FREAK, regression) -{ - Ptr f2d = FREAK::create(); - DescriptorRotationInvarianceTest test(SURF::create(), - f2d, - f2d->defaultNorm(), - 0.9f, IMREAD_GRAYSCALE); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BoostDesc_BGM, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BGM,true,6.25f), - NORM_HAMMING, - 0.999f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BoostDesc_BGM_HARD, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BGM_HARD,true,6.25f), - NORM_HAMMING, - 0.98f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BoostDesc_BGM_BILINEAR, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BGM_BILINEAR,true,6.25f), - NORM_HAMMING, - 0.98f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BoostDesc_LBGM, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::LBGM,true,6.25f), - NORM_L1, - 0.999f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BoostDesc_BINBOOST_64, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BINBOOST_64,true,6.25f), - NORM_HAMMING, - 0.98f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BoostDesc_BINBOOST_128, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BINBOOST_128,true,6.25f), - NORM_HAMMING, - 0.98f); - test.safe_run(); -} - -TEST(Features2d_RotationInvariance_Descriptor_BoostDesc_BINBOOST_256, regression) -{ - DescriptorRotationInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BINBOOST_256,true,6.25f), - NORM_HAMMING, - 0.999f); - test.safe_run(); -} - -/* - * Detector's scale invariance check - */ -TEST(Features2d_ScaleInvariance_Detector_SURF, regression) -{ - DetectorScaleInvarianceTest test(SURF::create(), - 0.64f, - 0.84f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Detector_SIFT, regression) -{ - DetectorScaleInvarianceTest test(SIFT::create(), - 0.69f, - 0.99f); - test.safe_run(); -} - -/* - * Descriptor's scale invariance check - */ -TEST(Features2d_ScaleInvariance_Descriptor_SURF, regression) -{ - DescriptorScaleInvarianceTest test(SURF::create(), - SURF::create(), - NORM_L1, - 0.61f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_SIFT, regression) -{ - DescriptorScaleInvarianceTest test(SIFT::create(), - SIFT::create(), - NORM_L1, - 0.78f); - test.safe_run(); -} - - TEST(Features2d_RotationInvariance2_Detector_SURF, regression) { Mat cross(100, 100, CV_8UC1, Scalar(255)); @@ -872,117 +284,6 @@ TEST(Features2d_RotationInvariance2_Detector_SURF, regression) ASSERT_LT(fabs(keypoints[i1].response - keypoints[i].response) / keypoints[i1].response, 1e-6); } } - -#endif // NONFREE - -TEST(DISABLED_Features2d_ScaleInvariance_Descriptor_DAISY, regression) -{ - DescriptorScaleInvarianceTest test(BRISK::create(), - DAISY::create(15, 3, 8, 8, DAISY::NRM_NONE, noArray(), true, true), - NORM_L1, - 0.075f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_VGG120, regression) -{ - DescriptorScaleInvarianceTest test(KAZE::create(), - VGG::create(VGG::VGG_120, 1.4f, true, true, 48.0f, false), - NORM_L1, - 0.99f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_VGG80, regression) -{ - DescriptorScaleInvarianceTest test(KAZE::create(), - VGG::create(VGG::VGG_80, 1.4f, true, true, 48.0f, false), - NORM_L1, - 0.98f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_VGG64, regression) -{ - DescriptorScaleInvarianceTest test(KAZE::create(), - VGG::create(VGG::VGG_64, 1.4f, true, true, 48.0f, false), - NORM_L1, - 0.97f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_VGG48, regression) -{ - DescriptorScaleInvarianceTest test(KAZE::create(), - VGG::create(VGG::VGG_48, 1.4f, true, true, 48.0f, false), - NORM_L1, - 0.93f); - test.safe_run(); -} - -#ifdef OPENCV_ENABLE_NONFREE -TEST(Features2d_ScaleInvariance_Descriptor_BoostDesc_BGM, regression) -{ - DescriptorScaleInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BGM, true, 6.25f), - NORM_HAMMING, - 0.98f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_BoostDesc_BGM_HARD, regression) -{ - DescriptorScaleInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BGM_HARD, true, 6.25f), - NORM_HAMMING, - 0.75f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_BoostDesc_BGM_BILINEAR, regression) -{ - DescriptorScaleInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BGM_BILINEAR, true, 6.25f), - NORM_HAMMING, - 0.95f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_BoostDesc_LBGM, regression) -{ - DescriptorScaleInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::LBGM, true, 6.25f), - NORM_L1, - 0.95f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_BoostDesc_BINBOOST_64, regression) -{ - DescriptorScaleInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BINBOOST_64, true, 6.25f), - NORM_HAMMING, - 0.75f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_BoostDesc_BINBOOST_128, regression) -{ - DescriptorScaleInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BINBOOST_128, true, 6.25f), - NORM_HAMMING, - 0.95f); - test.safe_run(); -} - -TEST(Features2d_ScaleInvariance_Descriptor_BoostDesc_BINBOOST_256, regression) -{ - DescriptorScaleInvarianceTest test(SURF::create(), - BoostDesc::create(BoostDesc::BINBOOST_256, true, 6.25f), - NORM_HAMMING, - 0.98f); - test.safe_run(); -} #endif // NONFREE }} // namespace From 9312f745407a05655c35d2e14a34db4ab45fb247 Mon Sep 17 00:00:00 2001 From: Alexander Alekhin Date: Fri, 7 Sep 2018 18:51:12 +0300 Subject: [PATCH 17/97] xfeatures2d(test): update GMS test thresholds --- modules/xfeatures2d/test/test_gms_matcher.cpp | 43 +++++++++---------- 1 file changed, 20 insertions(+), 23 deletions(-) diff --git a/modules/xfeatures2d/test/test_gms_matcher.cpp b/modules/xfeatures2d/test/test_gms_matcher.cpp index ab1484326..b0923c9ac 100644 --- a/modules/xfeatures2d/test/test_gms_matcher.cpp +++ b/modules/xfeatures2d/test/test_gms_matcher.cpp @@ -27,21 +27,20 @@ CV_GMSMatcherTest::CV_GMSMatcherTest() combinations[2][0] = true; combinations[2][1] = false; combinations[3][0] = true; combinations[3][1] = true; - //Threshold = truncate(min(acc_win32, acc_win64)) - eps[0][0] = 0.9313; - eps[0][1] = 0.9223; - eps[0][2] = 0.9313; - eps[0][3] = 0.9223; - - eps[1][0] = 0.8199; - eps[1][1] = 0.7964; - eps[1][2] = 0.8199; - eps[1][3] = 0.7964; - - eps[2][0] = 0.7098; - eps[2][1] = 0.6659; - eps[2][2] = 0.6939; - eps[2][3] = 0.6457; + eps[0][0] = 0.91; + eps[0][1] = 0.91; + eps[0][2] = 0.91; + eps[0][3] = 0.91; + + eps[1][0] = 0.80; + eps[1][1] = 0.78; + eps[1][2] = 0.80; + eps[1][3] = 0.78; + + eps[2][0] = 0.70; + eps[2][1] = 0.66; + eps[2][2] = 0.68; + eps[2][3] = 0.63; correctMatchDistThreshold = 5.0; } @@ -66,7 +65,8 @@ void CV_GMSMatcherTest::run( int ) const int nImgs = 3; for (int num = startImg; num < startImg+nImgs; num++) { - string imgPath = string(ts->get_data_path()) + format("detectors_descriptors_evaluation/images_datasets/graf/img%d.png", num); + string fileName = cv::format("img%d.png", num); + string imgPath = string(ts->get_data_path()) + "detectors_descriptors_evaluation/images_datasets/graf/" + fileName; Mat imgCur = imread(imgPath); orb->detectAndCompute(imgCur, noArray(), keypointsCur, descriptorsCur); @@ -102,14 +102,11 @@ void CV_GMSMatcherTest::run( int ) } double ratio = nbCorrectMatches / (double) matchesGMS.size(); - if (ratio < eps[num-startImg][comb]) - { - ts->printf( cvtest::TS::LOG, "Invalid accuracy for image %s and combination withRotation=%d withScale=%d, " - "matches ratio is %f, ratio threshold is %f, distance threshold is %f.\n", - imgPath.substr(imgPath.size()-8).c_str(), combinations[comb][0], combinations[comb][1], ratio, + EXPECT_GT(ratio, eps[num-startImg][comb]) << + cv::format("Invalid accuracy for image %s and combination withRotation=%d withScale=%d, " + "matches ratio is %g, ratio threshold is %g, distance threshold is %g.", + fileName.c_str(), combinations[comb][0], combinations[comb][1], ratio, eps[num-startImg][comb], correctMatchDistThreshold); - ts->set_failed_test_info(cvtest::TS::FAIL_BAD_ACCURACY); - } } } } From abb211d06411b8d8aedfc4c36185ef016f543dcf Mon Sep 17 00:00:00 2001 From: Alexander Alekhin Date: Sat, 8 Sep 2018 18:37:30 +0000 Subject: [PATCH 18/97] avoid `Ptr<> == NULL` checks --- modules/bioinspired/src/retina.cpp | 4 ++-- modules/rgbd/src/odometry.cpp | 4 ++-- modules/text/src/erfilter.cpp | 8 ++++---- modules/tracking/samples/tracker.cpp | 2 +- modules/tracking/samples/tracker_dataset.cpp | 2 +- modules/tracking/src/multiTracker.cpp | 2 +- modules/tracking/src/tracker.cpp | 2 +- modules/tracking/src/trackerFeatureSet.cpp | 2 +- modules/tracking/src/trackerModel.cpp | 6 +++--- modules/tracking/src/trackerSampler.cpp | 4 ++-- modules/xfeatures2d/test/test_features2d.cpp | 6 +++--- 11 files changed, 21 insertions(+), 21 deletions(-) diff --git a/modules/bioinspired/src/retina.cpp b/modules/bioinspired/src/retina.cpp index f856683bc..11c8e7624 100644 --- a/modules/bioinspired/src/retina.cpp +++ b/modules/bioinspired/src/retina.cpp @@ -562,7 +562,7 @@ bool RetinaImpl::ocl_run(InputArray inputMatToConvert) void RetinaImpl::run(InputArray inputMatToConvert) { - CV_OCL_RUN((_ocl_retina != 0 && inputMatToConvert.isUMat()), ocl_run(inputMatToConvert)); + CV_OCL_RUN((_ocl_retina && inputMatToConvert.isUMat()), ocl_run(inputMatToConvert)); _wasOCLRunCalled = false; // first convert input image to the compatible format : std::valarray @@ -830,7 +830,7 @@ bool RetinaImpl::_convertCvMat2ValarrayBuffer(InputArray inputMat, std::valarray void RetinaImpl::clearBuffers() { #ifdef HAVE_OPENCL - if (_ocl_retina != 0) + if (_ocl_retina) _ocl_retina->clearBuffers(); #endif diff --git a/modules/rgbd/src/odometry.cpp b/modules/rgbd/src/odometry.cpp index ac9d80cf2..e95e225e6 100755 --- a/modules/rgbd/src/odometry.cpp +++ b/modules/rgbd/src/odometry.cpp @@ -1055,8 +1055,8 @@ bool Odometry::compute(Ptr& srcFrame, Ptr& dstFram Size Odometry::prepareFrameCache(Ptr &frame, int /*cacheType*/) const { - if(frame == 0) - CV_Error(Error::StsBadArg, "Null frame pointer.\n"); + if (!frame) + CV_Error(Error::StsBadArg, "Null frame pointer."); return Size(); } diff --git a/modules/text/src/erfilter.cpp b/modules/text/src/erfilter.cpp index 529aced13..0f6ed1e78 100644 --- a/modules/text/src/erfilter.cpp +++ b/modules/text/src/erfilter.cpp @@ -665,12 +665,12 @@ void ERFilterNM::er_merge(ERStat *parent, ERStat *child) child->level = child->level*thresholdDelta; // before saving calculate P(child|character) and filter if possible - if (classifier != NULL) + if (classifier) { child->probability = classifier->eval(*child); } - if ( (((classifier!=NULL)?(child->probability >= minProbability):true)||(nonMaxSuppression)) && + if ( (((classifier)?(child->probability >= minProbability):true)||(nonMaxSuppression)) && ((child->area >= (minArea*region_mask.rows*region_mask.cols)) && (child->area <= (maxArea*region_mask.rows*region_mask.cols)) && (child->rect.width > 2) && (child->rect.height > 2)) ) @@ -858,12 +858,12 @@ ERStat* ERFilterNM::er_tree_filter ( InputArray image, ERStat * stat, ERStat *pa // calculate P(child|character) and filter if possible - if ( (classifier != NULL) && (stat->parent != NULL) ) + if (classifier && (stat->parent != NULL)) { stat->probability = classifier->eval(*stat); } - if ( ( ((classifier != NULL)?(stat->probability >= minProbability):true) && + if ( ( ((classifier)?(stat->probability >= minProbability):true) && ((stat->area >= minArea*region_mask.rows*region_mask.cols) && (stat->area <= maxArea*region_mask.rows*region_mask.cols)) ) || (stat->parent == NULL) ) diff --git a/modules/tracking/samples/tracker.cpp b/modules/tracking/samples/tracker.cpp index 5191da216..ab862554b 100644 --- a/modules/tracking/samples/tracker.cpp +++ b/modules/tracking/samples/tracker.cpp @@ -93,7 +93,7 @@ int main( int argc, char** argv ){ //instantiates the specific Tracker Ptr tracker = createTrackerByName(tracker_algorithm); - if( tracker == NULL ) + if (!tracker) { cout << "***Error in the instantiation of the tracker...***\n"; return -1; diff --git a/modules/tracking/samples/tracker_dataset.cpp b/modules/tracking/samples/tracker_dataset.cpp index 24d3dfc13..1dbeb4c84 100644 --- a/modules/tracking/samples/tracker_dataset.cpp +++ b/modules/tracking/samples/tracker_dataset.cpp @@ -145,7 +145,7 @@ int main(int argc, char *argv[]) //Create Tracker Ptr tracker = createTrackerByName(tracker_algorithm); - if (tracker == NULL) + if (!tracker) { cout << "***Error in the instantiation of the tracker...***\n"; getchar(); diff --git a/modules/tracking/src/multiTracker.cpp b/modules/tracking/src/multiTracker.cpp index 04e1c0c00..45ca19ccd 100644 --- a/modules/tracking/src/multiTracker.cpp +++ b/modules/tracking/src/multiTracker.cpp @@ -47,7 +47,7 @@ namespace cv bool MultiTracker_Alt::addTarget(InputArray image, const Rect2d& boundingBox, Ptr tracker_algorithm) { Ptr tracker = tracker_algorithm; - if (tracker == NULL) + if (!tracker) return false; if (!tracker->init(image, boundingBox)) diff --git a/modules/tracking/src/tracker.cpp b/modules/tracking/src/tracker.cpp index ad4765d82..f692b5d62 100644 --- a/modules/tracking/src/tracker.cpp +++ b/modules/tracking/src/tracker.cpp @@ -70,7 +70,7 @@ bool Tracker::init( InputArray image, const Rect2d& boundingBox ) bool initTracker = initImpl( image.getMat(), boundingBox ); //check if the model component is initialized - if( model == 0 ) + if (!model) { CV_Error( -1, "The model is not initialized" ); } diff --git a/modules/tracking/src/trackerFeatureSet.cpp b/modules/tracking/src/trackerFeatureSet.cpp index 99ec4944b..9896f0ffa 100644 --- a/modules/tracking/src/trackerFeatureSet.cpp +++ b/modules/tracking/src/trackerFeatureSet.cpp @@ -101,7 +101,7 @@ bool TrackerFeatureSet::addTrackerFeature( String trackerFeatureType ) } Ptr feature = TrackerFeature::create( trackerFeatureType ); - if( feature == 0 ) + if (!feature) { return false; } diff --git a/modules/tracking/src/trackerModel.cpp b/modules/tracking/src/trackerModel.cpp index bfee5bf9e..023b3b67d 100644 --- a/modules/tracking/src/trackerModel.cpp +++ b/modules/tracking/src/trackerModel.cpp @@ -61,7 +61,7 @@ TrackerModel::~TrackerModel() bool TrackerModel::setTrackerStateEstimator( Ptr trackerStateEstimator ) { - if( stateEstimator != 0 ) + if (stateEstimator.get()) { return false; } @@ -109,12 +109,12 @@ void TrackerModel::modelUpdate() bool TrackerModel::runStateEstimator() { - if( stateEstimator == 0 ) + if (!stateEstimator) { CV_Error( -1, "Tracker state estimator is not setted" ); } Ptr targetState = stateEstimator->estimate( confidenceMaps ); - if( targetState == 0 ) + if (!targetState) return false; setLastTargetState( targetState ); diff --git a/modules/tracking/src/trackerSampler.cpp b/modules/tracking/src/trackerSampler.cpp index 2a0b591ff..38ea52317 100644 --- a/modules/tracking/src/trackerSampler.cpp +++ b/modules/tracking/src/trackerSampler.cpp @@ -96,7 +96,7 @@ bool TrackerSampler::addTrackerSamplerAlgorithm( String trackerSamplerAlgorithmT } Ptr sampler = TrackerSamplerAlgorithm::create( trackerSamplerAlgorithmType ); - if( sampler == 0 ) + if (!sampler) { return false; } @@ -113,7 +113,7 @@ bool TrackerSampler::addTrackerSamplerAlgorithm( Ptr& s return false; } - if( sampler == 0 ) + if (!sampler) { return false; } diff --git a/modules/xfeatures2d/test/test_features2d.cpp b/modules/xfeatures2d/test/test_features2d.cpp index d923147c7..cb3e11712 100644 --- a/modules/xfeatures2d/test/test_features2d.cpp +++ b/modules/xfeatures2d/test/test_features2d.cpp @@ -262,14 +262,14 @@ TEST(Features2d_BruteForceDescriptorMatcher_knnMatch, regression) const int k = 3; Ptr ext = SURF::create(); - ASSERT_TRUE(ext != NULL); + ASSERT_TRUE(ext); Ptr det = SURF::create(); //"%YAML:1.0\nhessianThreshold: 8000.\noctaves: 3\noctaveLayers: 4\nupright: 0\n" - ASSERT_TRUE(det != NULL); + ASSERT_TRUE(det); Ptr matcher = DescriptorMatcher::create("BruteForce"); - ASSERT_TRUE(matcher != NULL); + ASSERT_TRUE(matcher); Mat imgT(256, 256, CV_8U, Scalar(255)); line(imgT, Point(20, sz/2), Point(sz-21, sz/2), Scalar(100), 2); From 7f5bb96dcc9132bf1ee91f21d4ac25a89d21528f Mon Sep 17 00:00:00 2001 From: LaurentBerger Date: Tue, 11 Sep 2018 08:36:23 +0200 Subject: [PATCH 19/97] Merge pull request #1750 from LaurentBerger:oilpainting * Oil painting effect * license * try auto * Insert test * template * review * indentation in namespace * remove back to future --- modules/xphoto/doc/xphoto.bib | 6 + modules/xphoto/include/opencv2/xphoto.hpp | 1 + .../include/opencv2/xphoto/oilpainting.hpp | 41 +++++ modules/xphoto/samples/oil.cpp | 103 +++++++++++ modules/xphoto/src/oilpainting.cpp | 172 ++++++++++++++++++ modules/xphoto/test/test_oil_painting.cpp | 108 +++++++++++ modules/xphoto/tutorials/Images/baboon.jpg | Bin 0 -> 179920 bytes .../Images/baboon_oil_painting_effect.jpg | Bin 0 -> 114971 bytes .../tutorials/oil_painting_effect.markdown | 23 +++ 9 files changed, 454 insertions(+) create mode 100644 modules/xphoto/include/opencv2/xphoto/oilpainting.hpp create mode 100644 modules/xphoto/samples/oil.cpp create mode 100644 modules/xphoto/src/oilpainting.cpp create mode 100644 modules/xphoto/test/test_oil_painting.cpp create mode 100644 modules/xphoto/tutorials/Images/baboon.jpg create mode 100644 modules/xphoto/tutorials/Images/baboon_oil_painting_effect.jpg create mode 100644 modules/xphoto/tutorials/oil_painting_effect.markdown diff --git a/modules/xphoto/doc/xphoto.bib b/modules/xphoto/doc/xphoto.bib index b57471ceb..d4c47e1ee 100644 --- a/modules/xphoto/doc/xphoto.bib +++ b/modules/xphoto/doc/xphoto.bib @@ -14,3 +14,9 @@ pages={1000--1008}, year={2015} } + +@book{Holzmann1988, + title={Beyond Photography: The Digital Darkroom}, + author={GerPublished by ard J. Holzmann}, + publisher={Prentice Hall in 1988} +} \ No newline at end of file diff --git a/modules/xphoto/include/opencv2/xphoto.hpp b/modules/xphoto/include/opencv2/xphoto.hpp index 73b1e0bb3..ec65b5eea 100644 --- a/modules/xphoto/include/opencv2/xphoto.hpp +++ b/modules/xphoto/include/opencv2/xphoto.hpp @@ -50,4 +50,5 @@ #include "xphoto/white_balance.hpp" #include "xphoto/dct_image_denoising.hpp" #include "xphoto/bm3d_image_denoising.hpp" +#include "xphoto/oilpainting.hpp" #endif diff --git a/modules/xphoto/include/opencv2/xphoto/oilpainting.hpp b/modules/xphoto/include/opencv2/xphoto/oilpainting.hpp new file mode 100644 index 000000000..6d5c6cf13 --- /dev/null +++ b/modules/xphoto/include/opencv2/xphoto/oilpainting.hpp @@ -0,0 +1,41 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. + + +#ifndef __OPENCV_OIL_PAINTING_HPP__ +#define __OPENCV_OIL_PAINTING_HPP__ + +#include +#include + +namespace cv +{ +namespace xphoto +{ + +//! @addtogroup xphoto +//! @{ + +/** @brief oilPainting +See the book @cite Holzmann1988 for details. +@param src Input three-channel or one channel image (either CV_8UC3 or CV_8UC1) +@param dst Output image of the same size and type as src. +@param size neighbouring size is 2-size+1 +@param dynRatio image is divided by dynRatio before histogram processing +@param code color space conversion code(see ColorConversionCodes). Histogram will used only first plane +*/ +CV_EXPORTS_W void oilPainting(InputArray src, OutputArray dst, int size, int dynRatio, int code); +/** @brief oilPainting +See the book @cite Holzmann1988 for details. +@param src Input three-channel or one channel image (either CV_8UC3 or CV_8UC1) +@param dst Output image of the same size and type as src. +@param size neighbouring size is 2-size+1 +@param dynRatio image is divided by dynRatio before histogram processing +*/ +CV_EXPORTS_W void oilPainting(InputArray src, OutputArray dst, int size, int dynRatio); +//! @} +} +} + +#endif // __OPENCV_OIL_PAINTING_HPP__ diff --git a/modules/xphoto/samples/oil.cpp b/modules/xphoto/samples/oil.cpp new file mode 100644 index 000000000..f06756ef1 --- /dev/null +++ b/modules/xphoto/samples/oil.cpp @@ -0,0 +1,103 @@ +#include +#include +#include +#include +#include "opencv2/xphoto/oilpainting.hpp" +#include + +using namespace cv; +using namespace std; + +static void TrackSlider(int , void *); +static void addSlider(String sliderName, String windowName, int minSlider, int maxSlider, int valDefault, int *valSlider, void(*f)(int, void *), void *r); +vector colorSpace = { COLOR_BGR2GRAY,COLOR_BGR2HSV,COLOR_BGR2YUV,COLOR_BGR2XYZ }; + +struct OilImage { + String winName = "Oil painting"; + int size; + int dynRatio; + int colorSpace; + Mat img; +}; + +const String keys = +"{Help h usage ? help | | Print this message }" +"{v | 0 | video index }" +"{a | 700 | API index }" +"{s | 10 | neighbouring size }" +"{d | 1 | dynamic ratio }" +"{c | 0 | color space }" +"{@arg1 | | file path}" +; + + +int main(int argc, char* argv[]) +{ + CommandLineParser parser(argc, argv, keys); + + if (parser.has("help")) + { + parser.printMessage(); + return 0; + } + String filename = parser.get(0); + OilImage p; + p.dynRatio = parser.get("d"); + p.size = parser.get("s"); + p.colorSpace = parser.get("c"); + if (p.colorSpace < 0 || p.colorSpace >= static_cast(colorSpace.size())) + { + std::cout << "Color space must be >= 0 and <"<< colorSpace.size()<<"\n"; + return EXIT_FAILURE; + } + if (!filename.empty()) + { + p.img = imread(filename); + if (p.img.empty()) + { + std::cout << "Check file path!\n"; + return EXIT_FAILURE; + } + Mat dst; + xphoto::oilPainting(p.img, dst, p.size, p.dynRatio, colorSpace[p.colorSpace]); + imshow("oil painting effect", dst); + waitKey(); + return 0; + } + VideoCapture v(parser.get("v")+ parser.get("a")); + v>> p.img; + p.winName="Oil Painting"; + namedWindow(p.winName); + addSlider("DynRatio", p.winName, 1,127,p.dynRatio,&p.dynRatio, TrackSlider, &p); + addSlider("Size", p.winName, 1, 100, p.size, &p.size, TrackSlider, &p); + addSlider("ColorSpace", p.winName, 0, static_cast(colorSpace.size()-1), p.colorSpace, &p.colorSpace, TrackSlider, &p); + while (waitKey(20) != 27) + { + v>>p.img; + imshow("Original", p.img); + TrackSlider(0, &p); + waitKey(10); + } + return 0; +} + +void addSlider(String sliderName, String windowName, int minSlider, int maxSlider, int valDefault, int *valSlider, void(*f)(int, void *), void *r) +{ + createTrackbar(sliderName, windowName, valSlider, 1, f, r); + setTrackbarMin(sliderName, windowName, minSlider); + setTrackbarMax(sliderName, windowName, maxSlider); + setTrackbarPos(sliderName, windowName, valDefault); +} + +void TrackSlider(int , void *r) +{ + OilImage *p = (OilImage *)r; + Mat dst; + p->img = p->img / p->dynRatio; + p->img = p->img*p->dynRatio; + xphoto::oilPainting(p->img, dst, p->size, p->dynRatio,colorSpace[p->colorSpace]); + if (!dst.empty()) + { + imshow(p->winName, dst); + } +} diff --git a/modules/xphoto/src/oilpainting.cpp b/modules/xphoto/src/oilpainting.cpp new file mode 100644 index 000000000..21e62414c --- /dev/null +++ b/modules/xphoto/src/oilpainting.cpp @@ -0,0 +1,172 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html + +#include "opencv2/xphoto.hpp" +#include +#include + +template +class Vec3fTo { +public : + cv::Vec3f a; + Vec3fTo(cv::Vec3f x) { + a = x; + }; + T extract(); + cv::Vec3f make(int); +}; + +template<> +uchar Vec3fTo::extract() +{ + return static_cast(a[0]); +} + +template<> +cv::Vec3b Vec3fTo::extract() +{ + return a; +} + +template<> +cv::Vec3f Vec3fTo::make(int x) +{ + return cv::Vec3f((a*x)/x); +} + +template<> +cv::Vec3f Vec3fTo::make(int x) +{ + return cv::Vec3f(static_cast(static_cast(a[0]*x)/x), + static_cast(static_cast(a[1] * x) / x), + static_cast(static_cast(a[2] * x) / x)); +} + +namespace cv +{ +namespace xphoto +{ +template +class ParallelOilPainting : public ParallelLoopBody +{ +private: + Mat & imgSrc; + Mat &dst; + Mat &imgLuminance; + int halfsize; + int dynRatio; + +public: + ParallelOilPainting(Mat& img, Mat &d, Mat &iLuminance, int r,int k) : + imgSrc(img), + dst(d), + imgLuminance(iLuminance), + halfsize(r), + dynRatio(k) + {} + virtual void operator()(const Range& range) const CV_OVERRIDE + { + std::vector histogram(256); + std::vector meanBGR(256); + + for (int y = range.start; y < range.end; y++) + { + Type *vDst = dst.ptr(y); + for (int x = 0; x < imgSrc.cols; x++, vDst++) + { + if (x == 0) + { + histogram.assign(256, 0); + meanBGR.assign(256, Vec3f(0,0,0)); + for (int yy = -halfsize; yy <= halfsize; yy++) + { + if (y + yy >= 0 && y + yy < imgSrc.rows) + { + Type *vPtr = imgSrc.ptr(y + yy) + x - 0; + uchar *uc = imgLuminance.ptr(y + yy) + x - 0; + for (int xx = 0; xx <= halfsize; xx++, vPtr++, uc++) + { + if (x + xx >= 0 && x + xx < imgSrc.cols) + { + histogram[*uc]++; + meanBGR[*uc] += Vec3fTo(*vPtr).make(dynRatio); + } + } + } + } + + } + else + { + for (int yy = -halfsize; yy <= halfsize; yy++) + { + if (y + yy >= 0 && y + yy < imgSrc.rows) + { + Type *vPtr = imgSrc.ptr(y + yy) + x - halfsize - 1; + uchar *uc = imgLuminance.ptr(y + yy) + x - halfsize - 1; + int xx = -halfsize - 1; + if (x + xx >= 0 && x + xx < imgSrc.cols) + { + histogram[*uc]--; + meanBGR[*uc] -= Vec3fTo(*vPtr).make(dynRatio); + } + vPtr = imgSrc.ptr(y + yy) + x + halfsize; + uc = imgLuminance.ptr(y + yy) + x + halfsize; + xx = halfsize; + if (x + xx >= 0 && x + xx < imgSrc.cols) + { + histogram[*uc]++; + meanBGR[*uc] += Vec3fTo(*vPtr).make(dynRatio); + } + } + } + } + auto pos = distance(histogram.begin(), std::max_element(histogram.begin(), histogram.end())); + *vDst = Vec3fTo(meanBGR[pos] / histogram[pos]).extract(); + } + } + } +}; + +void oilPainting(InputArray src, OutputArray dst, int size, int dynValue) +{ + oilPainting(src, dst, size, dynValue, COLOR_BGR2GRAY); +} + +void oilPainting(InputArray _src, OutputArray _dst, int size, int dynValue,int code) +{ + CV_CheckType(_src.type(), _src.type() == CV_8UC1 || _src.type() == CV_8UC3, "only 1 or 3 channels (CV_8UC)"); + CV_Assert(_src.kind() == _InputArray::MAT); + CV_Assert(size >= 1); + CV_CheckGT(dynValue , 0,"dynValue must be 0"); + CV_CheckLT(dynValue, 128, "dynValue must less than 128 "); + Mat src = _src.getMat(); + Mat lum,dst(_src.size(),_src.type()); + if (src.type() == CV_8UC3) + { + cvtColor(_src, lum, code); + if (lum.channels() > 1) + { + extractChannel(lum, lum, 0); + } + } + else + lum = src.clone(); + double dratio = 1 / double(dynValue); + lum.forEach([=](uchar &pixel, const int * /*position*/) { pixel = saturate_cast(cvRound(pixel * dratio)); }); + if (_src.type() == CV_8UC1) + { + ParallelOilPainting oilAlgo(src, dst, lum, size, dynValue); + parallel_for_(Range(0, src.rows), oilAlgo); + } + else + { + ParallelOilPainting oilAlgo(src, dst, lum, size, dynValue); + parallel_for_(Range(0, src.rows), oilAlgo); + } + dst.copyTo(_dst); + dst = (dst / dynValue) * dynValue; +} +} +} diff --git a/modules/xphoto/test/test_oil_painting.cpp b/modules/xphoto/test/test_oil_painting.cpp new file mode 100644 index 000000000..e7ef2fc16 --- /dev/null +++ b/modules/xphoto/test/test_oil_painting.cpp @@ -0,0 +1,108 @@ +// This file is part of OpenCV project. +// It is subject to the license terms in the LICENSE file found in the top-level directory +// of this distribution and at http://opencv.org/license.html. +#include "test_precomp.hpp" + +namespace opencv_test { namespace { + +Mat testOilPainting(Mat imgSrc, int halfSize, int dynRatio, int colorSpace) +{ + vector histogramme; + vector moyenneRGB; + Mat dst(imgSrc.size(), imgSrc.type()); + Mat lum; + if (imgSrc.channels() != 1) + { + cvtColor(imgSrc, lum, colorSpace); + if (lum.channels() > 1) + { + extractChannel(lum, lum, 0); + } + } + else + lum = imgSrc.clone(); + lum = lum / dynRatio; + if (dst.channels() == 3) + for (int y = 0; y < imgSrc.rows; y++) + { + Vec3b *vDst = dst.ptr(y); + for (int x = 0; x < imgSrc.cols; x++, vDst++) //for each pixel + { + Mat mask(lum.size(), CV_8UC1, Scalar::all(0)); + Rect r(Point(x - halfSize, y - halfSize), Size(2 * halfSize + 1, 2 * halfSize + 1)); + r = r & Rect(Point(0, 0), lum.size()); + mask(r).setTo(255); + int histSize[] = { 256 }; + float hranges[] = { 0, 256 }; + const float* ranges[] = { hranges }; + Mat hist; + int channels[] = { 0 }; + calcHist(&lum, 1, channels, mask, hist, 1, histSize, ranges, true, false); + double maxVal = 0; + Point pMin, pMax; + minMaxLoc(hist, 0, &maxVal, &pMin, &pMax); + mask.setTo(0, lum != static_cast(pMax.y)); + Scalar v = mean(imgSrc, mask); + *vDst = Vec3b(static_cast(v[0]), static_cast(v[1]), static_cast(v[2])); + } + } + else + for (int y = 0; y < imgSrc.rows; y++) + { + uchar *vDst = dst.ptr(y); + for (int x = 0; x < imgSrc.cols; x++, vDst++) //for each pixel + { + Mat mask(lum.size(), CV_8UC1, Scalar::all(0)); + Rect r(Point(x - halfSize, y - halfSize), Size(2 * halfSize + 1, 2 * halfSize + 1)); + r = r & Rect(Point(0, 0), lum.size()); + mask(r).setTo(255); + int histSize[] = { 256 }; + float hranges[] = { 0, 256 }; + const float* ranges[] = { hranges }; + Mat hist; + int channels[] = { 0 }; + calcHist(&lum, 1, channels, mask, hist, 1, histSize, ranges, true, false); + double maxVal = 0; + Point pMin, pMax; + minMaxLoc(hist, 0, &maxVal, &pMin, &pMax); + mask.setTo(0, lum != static_cast(pMax.y)); + Scalar v = mean(imgSrc, mask); + *vDst = static_cast(v[0]); + } + } + return dst; +} + +TEST(xphoto_oil_painting, regression) +{ + string folder = string(cvtest::TS::ptr()->get_data_path()) + "cv/inpaint/"; + Mat orig = imread(folder+"exp1.png", IMREAD_COLOR); + ASSERT_TRUE(!orig.empty()); + resize(orig, orig, Size(100, 100)); + Mat dst1, dst2, dd; + xphoto::oilPainting(orig, dst1, 3, 5, COLOR_BGR2GRAY); + dst2 = testOilPainting(orig, 3, 5, COLOR_BGR2GRAY); + absdiff(dst1, dst2, dd); + vector plane; + split(dd, plane); + for (auto p : plane) + { + double maxVal; + Point pIdx; + minMaxLoc(p, NULL, &maxVal, NULL, &pIdx); + ASSERT_LE(p.at(pIdx), 2); + } + Mat orig2 = imread(folder + "exp1.png",IMREAD_GRAYSCALE); + ASSERT_TRUE(!orig2.empty()); + resize(orig2, orig2, Size(100, 100)); + Mat dst3, dst4, ddd; + xphoto::oilPainting(orig2, dst3, 3, 5, COLOR_BGR2GRAY); + dst4 = testOilPainting(orig2, 3, 5, COLOR_BGR2GRAY); + absdiff(dst3, dst4, ddd); + double maxVal; + Point pIdx; + minMaxLoc(ddd, NULL, &maxVal, NULL, &pIdx); + ASSERT_LE(ddd.at(pIdx), 2); +} + +}} // namespace diff --git a/modules/xphoto/tutorials/Images/baboon.jpg b/modules/xphoto/tutorials/Images/baboon.jpg new file mode 100644 index 0000000000000000000000000000000000000000..2f98d8359b8d9776b54ba71f6168f2da80aaba96 GIT binary patch literal 179920 zcmbSycUTkA*JcnzrASeF?@9;hO;PF6JAoh|H6--jLRom*0OhzRfAB_g`LO~|bcKty$ynnO&P_>sQNJx-6u z;^8UZ?{mGZ?VvFj+v9#_>-pgU2`wEx10xSF-;<~O5|UEVGO}{7UaP38scUE&8X23I znweYJy|Z_4baHm_^7ird^A8A&_!t=#{V66kH7z|OGwbu0?1I9g;*!#`@`}28IHCdB z*o5lr>h9_N)z?2TJ~25pjs7!(Sy)_JURhoHyS}l1aCmfla(Z@tL3K;{4$xY^iK5PE1ww8}4%)8GQ18E5N|3EDB$pcvxYdp28RK(Ap zBi##A42JOn)xs0UN&IfZ7#!^9ap}`ea0Rd$i9Bvk(e1^c<64X>&CgSJKt z9zP7_>v!o@Ap=Xy$-wu~+=QUP#Sn{O^g{mowx>=O+L4LXuFn@(r?=SNCh3KbR&vA@ z#s0eI#6a+gn`TMDnBK7TW#m(!DIH|n(Xqgy)DahG+3z`-f%*sd*}mY|o@12&hEQ~Y zcpJtY_EyWril+Sp7S4s=8YljJ!m-tIyg4tFO1y(Gc>QQr3dVpJi-e3GNlC&8N5!gSMvQl_3-RO-6l;& z@N+U*1Sms}rhI%n4`uG$nypb>+Pzyd1ixTDs3;^lM{Ul%Mh~twr=IP0E%jg^?eX3~ zD?ZR9^qFI+ivuq6U}tH-!Km^6%a|z}A6uiU*j6L}i-L7k=6`xl?0x-k9ItJmE$px_ zZvI2S2U-U`+}2#b z1Q_<~VsxlwLW$*!r^>r>+hC!vt_AsFXTxq8b|N{hO{OCHn5Al;F!7bJ+N|W*8L(rT zm3d!(?|Ln%2<;t4?c51|B}bpS=t)f}go`0lXsH=Xt$Iu?O@bwr(P5p2L-VGCcz9}1 zS5hdPb$>k{BYZJeG4%TM2)p9;Ot;4(I#TG0NjRs<$?uL8lTp~i;ndeVXxeVI!$`s} z!D&sFPy6-0U3DT9L@kKp7LIEwX{J`wg$hG7IPdr&6AeA=0}I*YXp}5J`n`%hvePN5 z9H1PNcFXF#@PV6FHhoNgI_BJrz1Z=1PK|)ktm|!{1C4*9Les7*X;vba4I8sDe_wIa znS7&h?KvPOasNgzGWbi381X$=T6+JlH0Qy__+OBUVh@J?SU&aVd0bPQn)*&`F7_33 z{F=;B`9uP5wn-aIZLK8BLK^JbG$QP(qNH94hUI6KRG**!bqH47$2ipue)rFL4Xmcn zZ>>d5;ssLUPpUc{4km-!W%)_Vhi#5zD_NiHl}5YeVa@gw3_)hILyjd{j*>-&^5%=O zS`7CgRpTn0SIa5w%unxB8>D7`@NLB$PqliZd{w>Ajh|?{;#-A~j%{;$t0S?&obBXo zlpW;^B9a1Dw)?yyoHUL2tM0$+$whbeH04mWT(YFbaM(R(jNl){Btwhz67c@>y5lD# zf>LrtVo-l>Ql#Kd>K7QxHGUnhz8|9oK3pt3HO)@PQz9$Pmsi7W&QsA6)s7)3pfTDJ zS~Ail9~Kjs+ox^|&+0OG;p!tmu6(r_2mVy>?iV|CYJPIc1ks&mX=MIWWrA>*jnZhN>wzS7{K;4~BgA^(Kx?8Y z!MtRyzHM{(1P9wZ5R-t#OP#dwP6WTI_J^Xirfm}>$U)O&e(dqaanCwEf z{s9E82MbzybJY1&q>&0+frJp#$`V%dqZ<0r)nTB80to4S}U{JB8tAOtySyFiW zZw0yVgWO;A_jvOcl0KobIx79Uy)a$xYCs)%8t;&8iDB&=oPzBc8Gi@ir`uK!udYTd zT(%*8L6Rk?fWYkDXCC@xJ6KS*kn}-2&Wl2y5#60jtFE9@fPaBf5T>w}s@_Tj6?l?xYgP zbO>$j{R5zq;8rxSl|fceTf1M%h_PWsYdUE75)77_x`vc4zXKy17`ZH*4RQYf&U-u^||sucKBA$Pn-vb&tA24sotez0xBKfp&9JZ7!y#3Ha52cLi@ zd^=dA6iYCr+BR|WCtNunVW3H{d~Fn9&{pnTvt4?CTo3t_A-i zo^q9_gzqz_Zb)5tqdvHVLBK*IZMHuK>S^8G|EB$5`00AsOtaA|Lb1vEU|-P7zhGEE z(aR)i=l6?f*O`xZohHC_iz)$3Zr;#PTW~$8$=A}$!5+}2kI$|(EH^(@x1?!0eyf-q zgq<^**mjfHJtJxp+4GItTWR6&Sd44c7`kqae`E<1)u4Sq*w8~lUvd6fmWz*2akFC2 z^1{`^@*@9(%}wu*JlSfuzWXt>!eZ2w!M&IBO2hF-x7IQ0S zUnUcrlqb_&YjA1S85hsB;R8T8@IK2QTnOpm<7XC0oy-<>@TW#7!i#4FJ^)FzH-Pp(YQH>2u_hWvk4unYQg z5!KtR{PFtP(JazU!R8-2q0cIwx{3xiIl)|u@>cxZ;+58O)rM(^Nh+V{bxRLL5;9g4 zSYB4nfrdAa9c|syTT?*?$aBPsom^NVE5`(T^Z1qQ!nM+Yz+!@rmz&Ft+2_i0u*6Vi zMjc^t0H3VP;+GQeMN${e(O~@MX~0EB9gy4fREtYJRsF`n5|yxaXCWD&ba2>5TxaYk z;;ZGBaq|zLnqQvN)hUt@Y=F7I_MbO@!Hb@KnZGs=xYS~~|99g2$#n0*GfyGTY&=d% zm7p`ZQUIzz-o>1jpsfX(^jGmwo$(c;igJIoeqZyA2(BdIM>je|5S2H;a^!digR@~yHZ)6y`C_O z$61NaDvbXkXLiwYf6)tI5%|7GlN5WLaR01sse4QaUs+j=#Z)MwusEf@g;`^rW2#1X zMWc|deWM>x{gte+PH7A5np+A@MXyk!p9UDe-QKRdX>GcJ<5I^q$t=UlX@^f zl=9W$yRE`c_g_O!Uo-hN45u5DV)O4oT2#LITMTww%u0>n!EPasZHg03#beCt%*x0Q z(%{=NCg+Vb>p}7sZbQJ``XFz=O=QZ*%fj#a+Reo^7p>1L{{gy~LKV*P7bv1mrcJUH zCrwX5l!#0`2FDeU8Pr++8EIepg@^37*+H2!vx({ZV2?@{3$pCpgwmEDZS|yp##Cyh z;diMT4*WTZJ;us#(ep35@|t%2`EqILf>qlGCV#JX{{e`$jLypsjY1E{L^jcV*}%^d z|2p&yRkQq%24Y0Ou!(q`9L{4$#$}k97VP?mJ5}^sChzyNu#&U2U*czRJxc6} zzR2ksMznT)N@ULc&Yk48`9*FFWnFyoV>i#A_YOTC7xV5+qlB|JMb>xyR_qGW*BhHE zH%pf)kC4Yr^@~Y&oI`0^$0eU$*%Ys9v4cZc@7>MDOY7o6L@TxnqLDHDrMbh#ucEuy zB9&+&gPj-2)j`hL-eN9fP+@bv_OH}sNJjD>a*Pox?!7qT=>BggSnu4z47Nx zMiBF6XP>sb1R)yCx-UZR+pbK9H+E#_;5v}uM$y@4kX)R_uq!a3x4P^N^pR$I_h}`R zNhl=PKbDiyp3{}Tp75~t+%Bp2(OI3=b0Q}>$(|yUOfkYDp`ThZoC#UMZi4bf$;+uL z4PJ2Z%(oP|CZ3gA`ClxgH!GV>d;_g!B#@>XzN#egRXNB7q)tq`ctgt4kbqXy2{@mO zx3bErR|w+mM$w%)%}JJ=pz!UXW&GpdlYz2X7j0dmQE&9#b#K#>Y)#1*7&)TI!nO95 zw}v)W%Z8TbNm(g})N&@In^`f{`}}F|RsSx^1c$$9KL9cu$_(s>33>kmM3j1c*-u1N zm|M4f(?JyOv`7B>;~)qnU{i=;&Tm6ye7-6w>r^EPEyM*J8SgT6lAy6#AVU8H$82!xw3{n&-t4hFF7S? zA9Q_v`Va8lzYRJ6Y60i_`o|=!MYjTIv6HuH`F0ela&B+1Y;R}yUj5HQQ4JEZP==(Q z?2%8r4ST}XwrH^e-O97r#U;^SvX+oTpzrCRjfujNP<*QUG;jL%5s=iFQ>qJkEFd6c z_q9dNSLUjgZJ#iaU)Bc-hAPcXd+i?}_UIiL_o!s4No%bWsZ6%4Z>_tIv4vC`nCxmV zK0Hw=VyeY{p`GGyDBbAxV*Mnwv9`P}8eTTOzA}-*a;nWBAF+MtSGGYqU$c~_0HrnC z7&Xe#Psd?QwYMgm*Pja6Hl%9fSgUS`SC}g0!PpwCQ`JAfL-f_%g}H}p4~G`hg6)5d zxlwUsBu61R($-Rpjl!9Si@27=;E`?ny{lz;^o<&>JKhXZ{{YUGz@cKCnAB=e26fqo z1sz;Wssbl(yy}!9kc^9i%oN#NW9?LmKiAp!IbNL^XcQ zM(m82K66{F)})}oShE;h46i)%M0&^z^h-9$aJVb<#_a;uNa2+hBJkm4HJgfZ(iIqd<`^%(B+ zcMC$++6t#v*HnM~QgG`ajzoc6;G4`j!Rnb=~iBu~FgunO(wxbPTUl;us zm%73z3`D5c+X&5km>T1=ql!z1c=9pa<^+P6;1qv+U@g_ zg0RhP4dcDu8;w%Sa4Xd2%0=~WwkQk7h!)GN(?b`=kdrTEohI|2ri8gCIey13a$Eiq z{r&OdYz>=0J(O-=I7>1$B>TY0p@H(gwFh;h|6a|TlwJQ>VJ0$l z_K5YS-W-=w@%kBLp@sapyj5U-FHT9ZFRwhpIgCS-odWy zZwdJ6@iPYY$#6fdGGgPD;QmJ(YC}!Y`y|-0D}hBLH?p$=Y|km4e#&ktUV1t*K4pme zV_75M4i|NjsEk`yP;H-U#Eya_BRtpCq11O9)(W=rX*aGu_MKeI4KP^oLt7mkw`)0< zM6yVCW%-3Z%jtEi`sL;4=yf;#!m`;ymNV}KlD3IGqcJv2?w!negutDE8YZ);D;>k` z3$Iy~((8zBp10D|BPY~W5wF-oihzSC_A`SDyn~Lh??mTIpJgoMNkg{D9A3K!zwK0A zoHjOFl|k@lH7s+14JoKnCx2y!cF>12eKyoKk(H5XiIq`Ar!P;g72!mDQ6AFcXGx zDyX9^?F-SW1m7mR(@#IySDUbi`bqDQ=N;~6paYDSHVJU^`sE)L_rC{t0`}{%-(@g2 zHquOfTrKFg^YDX%N{Ox1Lq8;V&TSlXFg&5ru??#{-kOm1X%#j*s%A3WXU>LP$vKpq zp5{XlVx)0Q{;yOiHQr0Bj=yE~+ukDg&_C-^nc#tc2&3o!n^jkgo?#F27JHpVw)r@g z%OPdSZ0Z~!#(hVepzD$Jy@3e?tldqmC9OS#&11ni$Sf!Y)!c9b%7GxEtEDk5L1q3F z`iN22f-tJ}i|L3HnI&X;zk?+gXWi>6nv_iSe)2x9C?0TsJA7qt(?yA?WgoFpwJ3sc zVFXnYm2tLuRxCdGxq#;Q824dtG`&{{wJeU2BpLORY4!Z2M?I zD+}?LCx1@JrGH&yz``LM=oTxx@^y3)OBLO;RIfmsxmIE6=QE5xP6;wxYa-=ab^wp~I$S?aWW@rsv1lKLC8&yWWSTPS!SAS#hzS-tKEUmSH~r=IC88!l$ULtaEr{ z_#Yqvb{cw5;_2Wc`bMox5m3$s>>9W$c9irfRIL8TgarLj9I$A@E&xLHC!sFnJI@G+ z>7$OaypGI0&gj@S4m_BZV-lYGN;7h}x?ID9r8uqf_W?uKFZz^McUkWBX~_KYNc01h z^2Z}ALg@|VJUwKegX1&deR-H$cpdc@WmC!LpIZ;RZ69)_98a zW!jYY%Wt17t#ZdsgOt)bP!g1C?!tE7O;PgB#w?tN=)p8uLciJg_c{c6ioeT)B%LZH z&r4?F%M?`Bhj8-2$n)DcoV90@;<44)2dUAkR~4wg771S&y|)?Ntdg4*L>gXx*IArl zU)p`=J#_u3!#8`qVG@SuuqmiIaPH@xAa+W5G-M!_Ts5H4tH$%bPqKzFA7KLRmuP7p z+-g}Ho_1*0&)A^ww9VJ1b&`ngg(~n^ezmV^o zCNH!!C|S*yG8G=3)|+hpY@Dk0A%C?1SW?Wv=LLf*IVro5+D-&mUh)4MFgH8#jq09D@(I* zsJB<$1?l^_w#z&s@|Jqt}8bq`#XO6ePeRM&4az`3icx=hJR zt?^X0XTpHyM~7RdVkfi1Vjr5%rJ)x-$lQzUK<+^6_boyd&fE5UpWq=cho@3^*3CJ= z$$ih5EAl(8TBuHpquq*3ouRqyn3wu_f{N!=CWpO(@e@!-7#O>I5Ek0E-XdMj01I2VhumBJ!kcBs{IOsB zM~*>yCMo}e7fwdv;k6g>Uu%d1-5&YBGHaONZEtUj>b;kZe`2ygyVhq%QktC@uSzg1 zo&1paz5;8uaY^cC<-s@}d5HW%-PxN9EXD4Izz>jLni!CK!C4L`oF}L^7QSgkt%<9R zjh^`%0})vo44vg%ADDhfnl7yLHXt!y^CS?AI)%OyX6A1*Df=qa`Mouyy(08^Qc;M*HoO7-%_b3iwIg2aUqFkj0E} zCD&B-@DuN!FGNXc_QkxMdml<`H=jHE6(iBQz!N$5DWlm<=oJESDYCgIeWkL5dpU{4 zZb*%S=O`t?l0ec-PfTbQBdtvcN7{W2UvU8l0hLjB+TpvixL><&71&^fi5qrAW@L$( z1?hY;0ylI$<7-C-sIeDsjd0lvI$4SWUm7%9@$`r?cr;GV>DG#Y$oTnz%dlQkd4ffV( z-oWKbOM?zlHHUHAhX+S1alvR*QS5fJW9?44F|Ocue< zalVUO;#!fF%dD-rVwm{$1rDDUMwpk{_`rH@9n>ri3*8*ooHy|;=dxkV>GU*RpvNBi zMil}Yjjb#ifKMF#i}*6goUO>Ok7+^U0pKVu#dV*Jg;@SV2fn% z{?uK%zz~ zmSeCNmf*T`#WUaNBjh_k@yxKLtqG#KftQw1pH^SN)P+@FR{R5_sG9A3$ULSRQOmZT*^e%E#0rB)FzKbnEw}U2Tl#i~G`) zU&RzmSt|WCZ&en|pV~ci9K6?`{@3H|kkL$V!$Ft2`QsmANVecD2CJd3YwC7ShPBAs z5|Gf$2}DLsD$uz(FvTZ5q?9M?xczl=$Yp(B(kF*~!Et}aT|>tS$|2qq$yrW;NbMdy z>U%>6wcM=jQgURw*jJ@yx1Pej+DGpk0r}56+n9stMO=ikocg831EVde16uw*4>;B2 z5|d8S50`W%y|mNRkV`91di>S!NdgQgPg(ZCzf`$E0Um zFE~*OJOZ(5*uHl4*|dX^6Kb?0C)m*n@}U&F(6yKyi4}hJXflAdBNr?gK3~r`P*$;#OZ5y!H+yRv$PZrDT3&{&r0*rPE6jJ)s5K)D0>% zo&upQI85T!+_Fke0SSq9zl& zVE}a1zT+=$#GHMnX^*Y3+i#D8)WEGDW376e>ITAXTEC_w!HbwauZm+GNTO42{vH*y z*6^JsZp_x9aNfJV)3uOeT)9M(vFTmk<7>LXqbt8(i1A=E)ElLT`;H$ahM;3+S(%t+ zbI>21%Rf@@cnrO0%?9#Coxl^_T?pap^pj)B?JcbWc5!Q!@0x$7EW_96 ze>&6)zfv~WAi64PE|iu_=^8(igaD00^IT2?!Hz-l-#hs$4N|W{FXcmikxdMi;lUQX z838^v)%{>U+RRf*YG}3?O&=mzT1Zg*=>vACaZ1#Vib>sBK3iONhG2%0x~g;9O2=nK z=%a+W7QXTvUwrS-7Ouwza`Tj;7fnN{=&gER`YK z&m_iEzfkM|$5h^*CqnqQ?QYYpceTd^7PWlMi$cI>ylI`oV_!Sy4Try?{+c}8!Yb2S zO;SOfz}-|`I-j+9&Z0&2K!ba$ohZ$>8Th=z$Eq<-mw4tcsv+OUx!lF{hACA-t9bi%7e>^aS^?qgDlV0Tbn~{*(gWc7QbL!8&0L%z>mdf zR=vFmd>!e3c94Y{P9FBCRtZkQ>l={c*M8`+jYOoTcTTy0tb9p(b7-!0Nvn?{?c9Qd z``oJ=10r!}fV6LH+dfR<*?Z+b8=+p2y<2N5?6Fg51?hP(i-^88<(d4O4?DQF z!3r0um-|v#9`0e@ccf?yK4Gu6-VuDD(BG&MsjnZyK}vH>jx}aZC(2ib;rrArA=3@@ z&OjB|&_>SaVvEF*R(0)PlfEa2BZYruv;Y$iE>idV+swj+)=e*?C;>|<0-KN>m| zH0V>3aE$JELfd83?KPAx4DOeaKEUfL8elY7B}0C{BIfrGt|b1+#TOr*y*;;Z626!a z^!mr1QzF_NHC=?D!vkNBst`d=Dg6MB@u^s&234KW@0xmFxm!?5ms=NM7GD-?J>wEA zpc|O;BAA=jXU5&GYCqL|#kFu(pCGIgA}1q(E1)i`KuRc+EBvt1Mx&4W5gt(!O1OT} zkOHZ2@@u3k7yN-8Sol~Kd*9)Sk`Y&PSb*9q{a5$4dE`8CkTt)MmfZvKOxy4D!vd-q zN5@yylOHG|FKTO>CKe~M=P@%aC#Sv!m9GTu0V*=>g>p+39ufdNMgr!O!uK@3txM4{ zWL=uvsEgPJylfHv{)PMAbDUw{+8X_cCiY$i(%Cp6BjJm!C8RJk z=OP!^-XX8N_(YH$>{a4?P;{Dd&av!VINZ;?r>Y;bMp%wr$K>C|@W4)5Xbtc1Jks*< zanTwgY1kFv5>&*kOOp4&#blmw?^% zH&u~VdYGfxGF9!+fFBIqW*n~a%*$eCu{< zZQ~Nw5Ao|;4SVO?axsOOYD}J&hNr0|!`yxBPjGo&@d6c^l05eyyU_N$IhZfRKonA@ zAt3o~yCH7y!c>(a`pUSnJ3BgZ2PTMMu^45mbEzLTnbupT`9%HfAdQ}iZ0)TqJud9T})FV)+`rGF{F;)M;Xx zvAyyRb}9f9q8fWC-lgGLv{Im33eC;fotd?c3bbEKC`dDi(93znX!iiOHS-`>SuaK* zP1N8{!TVBv@!prqckLGDqPD%a!@9#Bu}@X`+^Y5t&A`jJf)jUz$S)=M0fqkhQ?+s-?s&A(Twlm}W1y2@(qFbb!#2mc^ zxjh_b0rAzMfA;~5jWKvK&)=a5pcm8Qw&4!9o9$Y4B@2+L_))GZ>0%*o4KV=QZ?r2_ zgO(Vp`v)C^LiC?av;Kq8;%>;cTl4q&+d=(=S^Zwq5J?>V5AeY91oP3e(0sPChi6)D z$a_B$@`X&QWU|xdfClW-|$bDNm_U4HIemu{1mV>IkVVr%YLzTiZ*XlXc1W{MJ@r6=EQ z>=ffJ%S5_Wqyi;H#G+G%JBDC;gVavKJp zqgW4A$c|HAJzi-i4N+)1M|)S-(Tu3@1uS_s$c~PK6mKW-*+OOlq{J%2StMUC=(IWA zhq7L?QUCyyC2Lw+y@YS{ew1CFSWOF4+#Wvx!Vz^-C2toDVEkqI+Ruxxfk0MrcOMp) zpeGPlmFjd1>`RfAC8}`!pkI_*AmWGWIRgWRMC`7PbYNI)@Uw-@xVRi4hhZ?6Gl!Mt zp{910-kYuJM{&lyQnQUIzs*eVo88B~Q1D+n4j9jP3er4n!?fnx549jXR=19htBRJF zkRv-sR{2+Vv`J0s_cFhiUMY+Q`$u=8n#F#AEA1O&Nzr;~=9a2gRksSUl~K9P&9RR* zcqu{mHfd@u zc$>?xV00YzUo?ivjm?VL0@n-?z2mrN@nyk~!p&)v%FP%1o5W11la66X=zo>@I)pT(NnfxBkL>1b`*Ah%Icd zru1q31Ld3t<|3}zbS}gE5aLwkoem#ONLXem6iX(2 zDziUA<)XxQmRq8|2sBgbDg;{P3^F-G!yVF94b-KjNb}6@&VDQ%JiPl-QI4wksh6gP zc~QQa_tw!4thgrIxfD#2cH&{+*EW55g7mon*{D}1x+HNQEe>QQbfXW`;Z+Fge~2fkP1c&R@B z!@e^L_tl$pEV4uJnGYY+Qvs|GuBcgFs(P%Mdp9U_d;liyyu0SsF}G~Bmla+m;zrlK zSvf+E(c*z+5wRMA1oiHS{YYy~&k(!567BVMK(yHGn=F(j&Mo-haTHqb1Ei#-nyC7I zFY&oU%BZ!AmDil*Rl#!~bDbL1#@Z?_6oXHWO>oS@VldM=txPFkdm6g-VeJyc&9Zh} zX%6hcizqSYNx0;?_W>sglGTgnTw3F~e{b0)lgwk>DNk{{MuJH`NGphqa>(BM0u=G2 z!A){Go--#4PcdxAWgErj$NYA!L8eJB^Z=0tYOpwNDCb-8+whqF&Y(JrL(CNIjPKTA ztv^qruk8GYQx-lSsW!krQNRV}UNSDuQ*t&L*&T$h(cV|q`%NEZGbC@#ypd@lmmht! z%Q!2Y;hKWmp!2M#9_p^`o8DxMCMRaJdoTX!vFu6?om^cVRP)s0?@d^Q?_piN@=m+w z(`KF!#!H~@`8jJCxW>f<)f;28e@{7aNvFa8HP!1VpcGQoZB_yt$(`x=T*=+tliZtC zc(Mw*sKhs6TRRbkupUVi;$PgiF^)8!6{>`Oq`ni}^Me%1@}R1i-Z(81s3>oRY{)UM z#OmNn-xSjikmR&jXHNi|OV4)?1vhR)_K0p+QTy`#w!1gf;23UrL%XQMZP7x!_)j~b z6+sZNV9j}0{DmdSA*s+C|D>LVgPFgXFCAj(v>cMT#ReiN1`o+&eO-UfM*-e0)>oQH zVpdG%kU@cvQf;Bo7`K<{i>1;+)V_#|5VQ;Sc;{4}<NF(~Ub82r2HeodolI-BJ66cUv5#R^h5(VEgD=NTL1rFfNl>7#9Jbkr>O4?w7kKkoadfN70>@{z+35>&+g39}05^`^( z+@HqciK#M^$!BIOEc3o_rv?ytn|v&q(AS=;uEE4-t--!`u&Uz^5JyL*HyI-j_gP{4 ztd~6^RV*TwGjFS#7M`!0$RmB+DmBqMzT1#GR4B-mFdLDPtsNOH!<`4HDeRK# zjV1^xbo7AG^k8u>OgxwkTAsv?J+&u^tR3}b3WtI7XOIl16Kg&bgTPP|g`T_mxWM*d zd?lpq02$fF{TI)H*w^{~Fw5`6O7&QX=)=x4g|v!tu>w1J0(t*6dOlgnoJEm@z}M0q z>(H!;xyqN{iSq4lx4n?~+0!Jhd77)5h8al38yUgqG$uplKqFVj?RNDWo4K7L_BHua zms~#;wD;u=v(a0u%&3++t(;$tsYFbi#@t`|c+&IE>^5ZkDwMdV=(HxXOvjJ6H20JPVYUU_d53;SJ(!u?Mg!e{{gHgjvOsTS^Guo9_Ql@+)OVR!zixoX%lMx z%(~E>HpJL5bxzDir^?(|R&31^;m{1vr4^N{oo~3VRQK<0xX6Vig#Lla$Aw7YUq0vs zbn{mMHl$MW#FZIp)IL>wTUXTD1gD8-JB#pn zCo-HO@nrf0$ao_2X2Kl%j9+8r84bp~p===a+n#d2oM|93qPpcSL;+>Vm@(NiU!S*Y zVvYF4i#M}S%Q_gnLy(c~(`nO~VLpV>AG3y~UI{^)*HCXM7HT1w1mtkF6&3@&d&Nu$GrQGOHJ50l<~p+ z9J_LLv^mMuKDQ{>43QTN_Ziz$_Hai%!KQxyp{w7>>f!GKEsP`K z=_sTajhh6XLT-T2Baqdxgmu(~AsC&fxE~$gq7^{&Q4Tv3HMyKa#B2q!ePZs|&a2mfvfFg0wi54mP(oVbBKNWDV~8 zL@d+GxUi(am>x3X}_R_5NE=YLDs;OzB>b3cBB-hWB`EX>iT^ep1_-o?hFNE?=(zlr#FZ0y~lh1B9gg` zEit?7e$yzP&aaPBr}R0? z^G<>easf4}+wBcGF*027i%mE+t$pG`q2Hz^bVJUJ3{bjl>p$5B<*wn+x`X@gGms^4 zEiVxgH|{~Bh>gLMnU!ELv|rIMOQlf%pthx{LPzXl7)%>>9grvDb1z1LpiF}<8V`}y zK?)w~E?n!EerhJi5_pKJ{E~my#k>|CStI3_(~UYtY>t$fUssrof?Uv=)q<7~%JMGP zzF8|fz@vlkL&v&EIsYvFmS!B%KJ;Q6X+<~pjs((-h31CAtiOz$0nLEdlH0p(!{Og7 zx#ge*JQE-@rSamEH=Co>MyeY{P(58mfr35A!KOH0^p#`Ti)2i73(5zV`!ko!?Cyep zA_(j&w#Hw)XwwW87Z~bM)=$t(iSx9msnF?vt_I0N!}Er6r_(GG{j!nv)LlsxbEP?_HAAR+^% zHF>39c$U?Px{Gx}$~k;R>Pyhk)`uj_yEkWwmU`>`Br7Vz)b^+I zHx6tQeqDHs)}hYiM3r+_!!2`np{e7;)6?s|QBV zw+jNb^ZGH;eF|pSe;7gp4yB#uY#+CinjXv1kOVUIHROw?`)YJ3r`}Ot2_l;}@vZeK zHE)1R2$3(39>wJZC1aF+j13amw1tVP=h;E-{@SI4s|=fGMNF6*7aML&xUBQSD*Sv+ zOKdO!Qj-DlUkgu4Upc z$#yxHb)Kmi9Jt~Vp}C1Rw62_}n#5}FA~V`7YAzT|F5)fTtb-jrc)F2PEpLL$Zo``U z&TY`MdYN-oS zNe2-Fce&rorKD;sP3EPSO=axz%|Ya-*9SBZc<%3{^EpB+@~>?8R}UA zc0Ol*vtt85pTY+jhMpkWtV-uR&gn;ny7bN?Fy~Eh5X7$x%To3N*YU_T9q@?Gi zdn?<=+ZJ(8PSSS80IF2EbD85dK3KlEv~C=qp8jYTkAsvTvD(cE=oXt|tGRVKi?dSw zX`i@&lBNW>apRX;Wd}|^60JZV!{le?p=@Vsi){DLcIM2dc7$ozqdYHy=Yi_0 z_Af@l8}E4JM$==5l`JqNJO+LirDxc+FoBaJ*>%0I#e?#E5IWI@fqhsa60y}VPRlHy0KMVMM z?loT;TV2@SLa80Kt?FE?j;n=dSphulUzgJ)4c#mK&s6%WdGyxjtA@+r zO43c)ecSeb@C+B!EPmG#JR$ddi}Dk@Ad+&uc_WeRdgN4zV+6W^d+{ozvK4D~U-d;VsTso9`!z_;w!C2UpK^>lIk8?Nj~``+I-);z}to-l1>4}axsHlRH{_7jr9J$4lw~jc`Ho?9~Vkx^}I4o63DmxxVGsx?TiZ2yw7gEhF@NX>w zMJ7NeZZM#3&j4fqc;g*$N!OgOulzsZ)YZ{i>9_Uy{{UAsH6IY@`jpW`nj*rcGqHT) z7&8DjZpTiXU}urVOBD8!O%!mzOTe-_c}>7oT#`V~LCN&U?Ohj@?B2S0eg(pusl{KR zQu|ht_VOvL#4|s1!KgHEeR+Ft6nm05zCfjb%K$+KkTL)R-v+OJjxAB{ z?)3e7*`b01=QZr91dPEDnAI7`cFsTm{K0w-D=6u$y6^pK-%(m{SCn+Jy}z%YmzkS* znma{h8{GNr8}7S-ZBo_tZX17mH#CPEzGhsfOcPqVUx+kM2x=C09vaZK3msceyOvbA zxVnnuDrA6xS`DD!gS(Ol%7CQTOlnh%xm<4Tz5KkpeuA9}wIHE%lj*C|Ub;WK(LI^7 zs(fSdhN!m+*RxA)b>&-L*_mc8;SUV*M$xg)Do_x(909?oFZ@&Ci8N%owv^AQ$U-D{ zwlXocPyi9fGhMl40C23NbnjZuQK+2dd-Pp){{TIIErN~(Qb|Fi`s;6=i?3ZxKM(vu z@TKGv=vvo+JUX9kxLB?=za~exw1t2kWO42&i~;9jj@bvG-L=wE)5WO|hPBOCR@StI zGDUut^IyRvTa>5~7`((?jf2nR4r|SLIg_ELy@^DS~uvg{#NwW`tD^ZLan(S z-(_~cM3&xtPQpJLY1Z1^#FlbLeIA)=!r?Tvg`HWrGQ5*E8bh=Lv%U^U0~z{{#IF%v z!2Ti7bjyuGSs86@RxLf{F~%5y9G9cZjX@+Gv4%W+#jD7xK~#&3rq$h>c3m5H-u{U` zy6$TVkf!Zqt@8YP{{UXLC$#v4ZK2XMNHi;tFh?x9ZRPBjbK1t(2Y5raFfe&^Z^CGo}i3<604pC&jwO!zIn}P)Lq6 zTVyMo6S!qZ1gjHT9}cw515NPl$B4X5E}IncMs+yuwR?H)7R~~57)Ewb&5$v*ToN$2 z=oV{2q$9~jEnVA98`oEB=(hQ9vN~|}l#^-cw`BaZ`?s?>jbFwvc-&n@f8z~HNQEPh z7IN6!>P>Rwf2>%M;)*gz!p1=W0DAIt{3glZ%@yUb)wSzcZ|&ZAVw+C4f_+6)oW9v( zl0dm^9h=A>-R8O}T7vczl761#c zc&1^KCDn*rmB~ZrBIi4|6&2U`U%`3?o#ETq^e+%x&7#iI1vXC=<*k#cIdzGcxs8T* zL^o|JNFlkY#lkpeJRI)heKohd()eE2YSz}$O-lMZa!Q+%RTZ`0{NI;n@;Gl4_{UYz zwPv>QB>E4Cd?7juf9*SI1HHI)Dq@|E`SG2ja8PjA&ls-T!#6sQhP*HKeIHVnQM6g4 zk|?z~h5EpX6RQWP(teuVevR(WJn{F$ckw;^zAMu_OEg-RpBvBiVRL#5IuD=AQ5!f- zqi*RY1dh9KYa7FUFtn7~O%KCeDPp{l7gD>`rh8zl+=&utE)_u>^Vl&5Ip^BLQLi{J zYLb%C^IKajEWPIS=+g35-ses#4oS7;71jR$hSuM{-FsHI{{V%fp=wq>4qqQyK9jA> zBgJaEvd?BBEtY0?4Hhz|=E>xKe8-IZF@K@!GF@vIvDxZ(!bA2*;_~wj;u2Jl4UVn> zKPkz^ae`~DP@xI)!Cgsfy6e52yII*^y0)sQRlQZo3pTvI{TofE-&KA36}2&{>6#Xw zZFAyHKKkD2p6P8;Z#80kk%t6qM?8{xkUEO3diM5`!hg1HZgnJ*DFWKaWf;u-+P!wMZ&-^`vMFUQuD0>tNgG{S*~p9? zytQRwsK=4JCyp4fKG?U`(VLjOue4lRvtdhQ$P)wjLC$`@oyAI|;qI@${vCf_p$Vju zSJ%Gx>3=(S^kwZ9D{FcD)VhGA1ceu|JFJBN01E}qar*7=(y}I+_GbG_Nx9=7mRR=T zi2h#x0H$+RsJq=OF;l9PuP-m^%lhtHhgBA=lf$V!yzyYGEQ%Rq0P;@+bDvJxsz*|f z?XpX8c$tzDBu%hf%5`s|U(*%w(IX&r0lj@mrQoD8|mhmnv#m%%%5U5pA zFafgPbcG#qNyp>IG`9Z$WRR;}LL>Q(;Tnb#V?36|Pj0+(&L~t|Q@SOzlS|L~{{V-% ze_7MD9WwQ_>&R~*k^rr75(VA?0|O%`qjBlqJQ~u~HIEO^0h>&)y0%Cn#%?Y|$9@3& z!)tZyLU^jo|n_M!1sEk)|jm%?G)MBjo{s zHH&`jYN$ZBfGB1+5)76*azP^`j+n^fj)J)ADX1w~-)+Ayxe5w0cE4`j6}oA!d!FcMQ>m1LjpzoM)bd5*UIpipsmyCBL~xMV%15jS{G5Mdv4O z@8dMhcX6pCPoqu;4#v}xU z+`}ho;Qs&-BLfTvO)3g?Ek7^ob1Y6Ko*iCF`hEKU0H0mDBbo6Ym3`rX1+JmuDOXUI zCi88fQoP<(Tcw6`~LvJNGUgol{nLmvvyyLzud0>0Lac6Stw4shXAUuPHJG=Um+m0*qT+hU4 zVIZf6ptXHn+e+!|v_78?!*y!U*{S{?@Jf2;?3rN_$8isfZWRvT^B95eoQxcd0C>-F z&s_0${{XY*si4|_Zun2dXHrn+6oy!y-NG>1bB4!LgY0wDipwqW8Di>2H7Hp(X4BiY zjceBDeSQ_IP7Ov^d)nWw$mM)b;Qs&_ctc3A)^)pB2AQfx&1-WQ5(b$_-vgei>x`Ao zI6Zq~L*joCoN3Wt+#5-Y%J9K*cFI7;>;a9$WCA+m4z>DCSl&@@W|WilN&dfq@c4Sv zu~%(u+P9j${{XFy)=6~#00{VpN|#cE>z2~Sw^Lc&87+-0j#yt z%rV{DUM`g}XjdonuPiahXN7Hzgqs7XP>&2?BmCWWuigB#YE>fT80p>H=d(|L z*K^98u&P#j-uGMUe(ztz>~#-`-YT`x?kz5~G|~_v#TBlladRvon4QJNv`Psfe)Nr= ze(=c^=UNrsyJM)I68JmDo)5p&?NwsC(`@WwhSJ(C`zw%4`WS|-lA6)C&UF}!=X{{RPnU%8&!qrZ+dT`Jz!#2*iIn~Pc8&l*8~ z(U`DuTnH^#HvHi4Icy#})h`#=F|oM4*M1;tx>c>M!g&^pdu=vWKe`}}1se_rNmPMCR$(?r$s-H{=2jm*0Xjis&`Z7X`91SbuCJ&Um}lp$?Kt0NP>uOz4al4B|B7 z9h-{IzA6#LNkQnkq_3v#_w($!w{uQcDn9eQ{I7r4^10*QDb``Ml5Y^}UI+0Hi1p~% z*>82rMi6P^kDA^DVgSJ(KGg>R0vOhXv*|uJwo&5UVofIHZPY~!&`7>o5El+e2^nH= z2mqg(hR$nODtPHBJ6~n0YR&mt+FMSy-o_On9z@{o{_U4%`S&vQ9R~jZz}k95w)&;j zl#&N~dnhN8S+c(&^O`u;J;W&c(&wh!;<%5C{vr6E9*1jV9-k+MwA;Xf*GD;)?)4S7 z2DoV%+$h5QybeIYJusz46e~tDYE7+`wBJ|gy#D|l7PMNcB&Xir@coxV6XEy5`LAKS z&~GFY-P_A`bEawfst6iOHXk!XG0w@Ob=*|rJ9s;AYo*eBC*to3T~FeXb8hgPlNG=$ zOwl-yuuGFJ)>bOPg8_q`!GL0|#fq4W3+eIN~vJt!VOWqLe=qA_*JHAbFXV2vwiI-qE$vYclvZ!h}T5rHfB*>>=&w;=f@ zuj2mz9$Wan{`Mb-_xfGt!5!9vUmzm#5U^MD^6Ff zntDn**+%X4QM=_yI|tUI2;HkY^y|0$JMMHV7liz0;nARvhxYe+gF>*FFF~-ol*kD& z#w7@|3=D(kG2k2%&2M}+@RVL1(PFUhZ;iEm3i2J|T{lp5wYY`L6(v}!LvW;p#~}Q< z4cfbEVsReIRB;m0>%O*HJFOgKmAR8{Eo&VbF@!0_^HQ^2w_h*v(T&%%Jw6>V_02<9 z)wHc&OUvKi*lKaxLvY6g{JvtVkOz);l#h3Q?3mkVkjh?4q z(8P=xn|ictsNf+7&2Vy81m`u=hf;+_D5Rfv%=xs}SlKt)_kTNI7`|k^qr7`|`7Le# z01T5xUy1x>tZLpIeQ(4`d8GLe0V7&mTRqmsB{Mr*DUiIGKk@Dndf~f|B+y$-_*duZ z+E0nqpHrP67S@Pv3|8C8-7BzGZx~ImO8QNqME|*1j6Q(#_tTb8NRS6t)oB3xdm({p3s}kvH%OagqjCAd2^6RmuuC zer;WCzMXd2l{#tKGv9T8EuMH2lkrMh)6jNHBDcYSU0>-}ij(4%Q-;ugA&-$T6@A>*DREnO97K?rwDx`LoCK{*^2 z_pHrU{{U5+RXSIQv{>|eN&d?2iEWu-Pbgv35=qJ(*xUguI&p}p3tmi!)r60e*>)so#BYlt`k?)EfZMO zdO8)?V;C5l?)WzdyVB@Df+w@7d zZ=Jsrv%dYEydSDwGy%0(oCQ~PxCNvD{p=Bi=L3xMjPchq#GeoT1Nb`NHnVqs_JE}b zxV}4CxB#l-oDfd~_>XK?5^3mwl+Z^=xX9J3)s^RAOUW=`r^uCv9=RPHT zEj|nI#kRQ{%=U)*TN|M)h=pHZk}@;*gD7xwj1)DY;ctXq9r53U#-ZU)99mlHaH=)c zt>Kjx-B_~cDx|msDJ;BUx(s~ZrD3bARu+yXFGDak?T38~Q+g15S&`h$GJmaVt&;J0d`qq|` z@WmU&CZ{d5jIs!%+;h0(2F}Bk_2-e$bgbo5nl^n6B^h-5zpv2iH2c{sE@Fn`U%39u zI}e!vX%v+ zj1sNLohC&3^MnwXy|m>>1n%2!dahF|~Lnl3Xiuis61Z{PF$OlVV7+EI7b{{Yvi!(GcJt#GLgz07%K`R&l2aB{;8NWeY1SEP6& z;Kh);icMBIH5uj*y|s(W_F1H7$z>@v(t0ZH1g=j7_!L%3j5(FBW80w%w4SMN_x}K2 zJ(20!Q(4;U#%L^b`xrEolFm~Jlgl$ADwr6#+GC6mpplm%M(cxE9xC{+qj+w|Q;y!- zOTM|)B8nLnXqC`fq>jUILJsD0xv)UXckEEFC`CfcM}GS&es=qhH!@#Z#5ET7x8vXb z2jYC~d;O=aU#yoGu$d*9QZXw?tUHsS`o2Lsb#Y&NZ}W;hoQ=ii^kBM1O@HL8^=7-p6{=p%5=82` zB1vQ+RBgb>CyWlKuRPb2X&Qfyz99IwQL)p0Cip)=iW@7Ngk4g2CYhSt#Ktog3q%i_ zfKO13jDcU5aE4ul%_>%&AvYA3&epq%dv@LQYt5f?pX2IbArE04TYWosWd8uO{{X~& zXU6t&X`6!7|Hto05gj5 zGprZ(R&!GeMqcI9ziaFLJ07MMynWmsy}H?xkOQfVKJ#jGwr7e(x+r(I;O{_nW@FHP`IhVC@Dbae1-#f7e@ zk~2*$lowO1EXATL#^iMaX)173*QSg98_4UlzY5#~R!(AHdM!ME7B-Si0#mT)$KE*VU#iqIjMsu^w2y(;EP{3dkt>0Kv zj5@xFS$SIix3{m%Azr08Sv2i!?f8C6@j9I=P4T4gT3L7-#OdLm_(#l8w3?Qru-o~L zr}u*88)*^-0DkRr$RltddPahtE%4Mncf~&z_=j5iQDG$B9n~fK3<=biYk%D?aoi~C zb6HkZAte}D->Z6AUu$mf-(H@x8mY&bExM)OTRZLP(@Qdkj=X!}-xp~1Iu3_-tLq79 z=GjiAs7xdCi)~jWB#_U70Khl|1KyXy&Eclf;;`1dQ4fdpJ9cG)?$*NU(*9E0gRD(E zGs&Es?L=TY5Dj?Pi&De5Mr)Zn+g*2iTc=mH*V96vtx@w@`}9`%TVGC|g^6{a6=*t= zX?B67@1!i!uCvHaWdx4R+WAK{$T(thw@g#l(X&O?#ev_iz z+=+KFKR=d2Fc>^C?K$N4I7$+uN);+QzR_(b^R<<>{{Vu{k7(*AXLsKAx0i3j(VE^d z@i&G36h&*Kw}otPFC$>lDnw(Fc2zr_AP~$)Qr!aJADgkq@ZXF)U-1!!yQBD8_d&Y5 zg<<<$-KjUX5#g8wXN*T4S7{$E)5zQi0QvQ3QKdpSs;#Lzd$(Gx*57}h;@o7aChvb< zzkas)Z`8fwuN>*#60*0@d}(2*UU?7YTR|q96i}>;#Zq}Dk#fTv?m;7c;#akKKD+Q= zQuvbJ+m`+&@UESrNak0$(k`#{86H4z(#ZZmUbrOX1~c0=*_BfIllGLS?lp9+*Iip~ z_j=hSZGJ+HNX}l~+OIn=o&NygyXI5-oT=m)XeHz40fs9c)`dug-O(> zDL6{ zjZ{MzNG@l9DBe89MU{ZePIqU805(BBjji|>#Cmp*sQ8D%CL8Y%*}PX5x=yQdvWvYu zyD}dokCvu4ESzj3U?UmBc@wKSIJ`uos?t%_+V7RCY}A#muJyA|uXLcPMMGC*XLZxp zUccsYehc`4;yLu2y=TGN71!KHx0~?+RB;o`3iigW9NR+j+GaNej;f; zGVwImzA(ShthJ3$M;+FOsY5=UaAS*pJej~~=8%)ZJ`O-CK~*EFh6bJM)aK@tY?_X% z`MIpxZa3FYdM&pW*3jq7tddfHFT4D?MlOSh#CmsX8QRF&-eM{mVxeIChQXSt0^bF$L@yZ#3?KACH6brt@N@XJ{74cVEJYrPLy z-)7Km2L=EI)<%l~@IIkLfIJ#@YRTJYbldH;xA`q?(B73-7~1~tlGo1qzsGlV z*lPGAO7QQ7?QSO3^o!Gb3>R`~@#*gOms7U_5hHRC2Mgw}%e^eKxzP z+*<0IoYr>wX|uJFjMnnBL&|_AbCgv=R2TWXaK(FF-MO!8E!~#)+TD76{mi|rW$#UB z@3y*WcKozoCG$Bo&^6gaI&Q0^PWrZ`FPsFbWtLom#aMK~9OtkMPC@6r(EKx~+vvjf z=S!Y_8ur+#+`tw@jp2$yjV97h%Fi1GJ4f*JIH{HI%GU3{;o0_IBTP)=INO@*e@!mE zHq%cs8MJGK&?cWxc<*8o`Hgmvd1{78&iIRSkVs%QfC*N|BxaPl9*g2FYfjNTS@9M0 z4IWvZX&y^KeJT=&v9MJEqznK7PYO2>PDnXAkfiRS^jmqWt@QkRU$M(YwCt?k<)?qo z^SS4KJn(cL2=QFHZI_62pAcGkvWRsZJCT6pSIkBqBV&@eIL}jGV{39*$MF*C<~fm~ zxYKm`?E^3={sVmfwIu2P6^K*E#2KubBQZd@|SkJ>wa5{{Rr)-0JW=Y{{|~nN@%# zBY&B8DL5N}C$Ce0e>&hi&kKajDpHzCQ;nkDmg~Px-lyrjQH8|R%i$_*$tJG1`ThR@ z@J_l*&3od%k0J4Hi}2q~@P?fRpKoaTcAXd5BAMf6CQ=HG#O}wg6m{EPqhV_6tfkG% zhFI;{8RT3x;uI0n2P3z?TpZU=5aOuI5~5zX|$dsj%Vc^x9jKB1`Sp1(fOB0!6EVOfL{{SV5e~r(m z^jI{{8QEzX&-VSC+Fi`jojdHz-gTCx_I%sLak+8BMh7|I@xdAKe~Et#>~!fP*0g;- zSF^t|Pb?Q2gl~0ibc|L=iCwD2j#@PXd!mz$InHg;sHGmMbk#oEF8tqe)ba3buXk%- ze_j6m-OnhM=di!~HnFB$S|gDpZ9HHcb}G!Ax3P}qXv}8j_shaQG6X@0AeG7U0-R?6 z9!+){Hm9fRcGCD~OtCi_mHdbMOJ0>`y^$a}D)9q`1m;8YZrng&@~VKU$~9{8TIp-} zX{zo0Yh&D^{;x&KQuFQCPsexHZ%(hro+h*KRm}Qrgy!}Xx3s(f#SvH}R1X+(qa-Ou zAT|kIpku9kx8r{sc!$Kdv+G)==b9XrL_ifsC*@TfAn$;q>5^-vf|Go&rI!ByHRq+@ z^<(Gov5f1wukz}0QtOw8?AI-D!dP(1vC2e*gYtvhr?0QlzUa|>c6?4W-xz7}m9+64 zoOcfqIWb-$s!bX6BWjV3NIsRp#u!NBaw@TJ;Ywfl3rq5oeuuS{)l_qO5`Sx&KYF_S zVs?6PX*|TbF;5M^`>X*3V~}~k=RGs)Tqlh`XRi(G`r7Ljnw8F#boSCAdnpWV%0>z| zA9Sm2$Dzh?!2Wm3xPrb%jddtRIJIXNv(sMR)vkW8jL9hGloVw3*5A`6@Grt23;Zau zmd41eqGuAwv&hcUOW2$cKM(2+X`No~*IK$adUe&cq;Ra!Pb;ZO3C?z7o-vc0di{Mk z;;U!)+2X4-r8_jcyRE)m`Xi!_8W=o0X~OnN-|pRVYZ6q=CW~*;Qs*6=j&sVq!dzb%HP-Oc!srUYi=0ncJf?6*73YilJbqL z%D*FdV=9||ZgLJrbMsc6#pISUd0N$)Lp{7Mw$_qZG8tu*D+bs&i0yN=k0)Zb41YY3*b^;&y6*<){yKu&Q1Kp<;@fRQNYaB?>6dzR@yyB#=VMz)74frR{n-Z? zzhdefntG)0nDyo zSk#fzdy|eiuNJH#rv1dF*JhK`N9VTJ^9a$aDRV~JTc_Q(`4lz1V_9pE@t^&x7q%BU%Ad+!)4=p z*?dubqU+b`VJu~2eLzPud1^prMUP~Jl>mn_xF36NIo!~ESK&>1=GVbdL*m^o{&{@c zCa`E@pHgH{6wQWpi)bvlk}#wIPTqr>QN;4|DcUf1YRM*&vs!P}-s$}GG^bLFe5zXO z)92FPk6jN)uul<1;k)_JTxd~PO3w4^+N2lL8H!^JT?)aEmA`k8d*{E6_@BdL#j{@C zYQGiyRjk{?Ad2ER@8Vk{77pi$T2hj(NXb!zuDNK$T9UpJMVt@6_Tg?(ny%i-sRj;m{`+<1>gp7HM_({%@EC$uriwn?pn zg4XlLAtjWqHnS-VI&?k}@mGj7qaLl`uZW9#XMC>l*y}K~H`+@+A_XKs$t*zpxXv&( z?A?K0Em&ddQdrv5?+sJ7jxT1`$;Mt?bxq$-P0ng9N#0-6R^Rmdih5?Bs;7(f3tO2c z@VCSp4TvYv2ij8Z+a;DkZ;|H3fwU;yBJia!Fujk7^a=b#EN{L$ctdOLjqUtbWn|Wf z`+;97@+HYt`@b}cgUav;&rNJb9))PCR#Rz4Ew}H++Fn1+)nBqpT^0@!akQ^(?`@ZF zPRBEQf8oy$>NbsU;XO0O+6udfuB?`OQD-Pd-R3wFAO{~Y-LwJzueEx1gW~ObR@0%? zCip#nE|Sm$Ti75?L9L&0X2RJ&&WAsGIF$9yX-5lF5fxH1ifY!2X*>4SsNJOPtY7`R zbY(whO>#-Me_Jn|wEL~wTbmJHSl?+62A`?gX&1`skis=NV_73pjj=~^s$-O7;W2`6 z81q#1>+cQevRhB_A4=ABn4>;SS8?d%`C&i+pCVx*us9)#9Ahd4XF~F+%SwaiceR%* z`KNU6t?uld^}D*x$wyh~=I{44v3FG0JQUXvn{8K6v9#Kk2|fGW+L_&e+KS>6GXO9+ zU@_5nHO(>6{5v!F*GM{^uO6(-V3$zw9BpZ8NWl=L!A6kdaZuYva4WixvxP?*ky`0) zU7np{+?Bg@*)7KfK1CHL%KZ21*55bOZP$YQD}NjwFVnP9cQuoVh5oU9bErtu22$&? zDIdx znHBUnYPC6e6|EgEmfnfkz4w!~`&&+VdpV~j-Pd=$pWPi_X8iR@(SuBH4fx3FTF;E^ zHQj2=+go^dONj&`(l$igVYX+?J;vrMu|Oa(Die&F?^6hmXo!>V_;f*^+hIwba zzqpE4gY0pwlBj6qavmZ{jBZ6%4g4bv6p&OJbm>!!T%GUpUb?M3pMIJ%nzZU(^0#-V zfB0v%m-AZs!P2g*?kx|8%009e@?9*BcgJ%(5d;mipaUau%8`=$wwm(4kJomd5VN+_ zEwpP}oqE>gZRL4wcUxIWEx2X~SvHJ? z8mci(Cv|tH-EOzlYP$E-`8NLY*^~in!a!M^3D|Rv90EF=abH1r2jVQ=B=CNZc?_ZT z{{RPCi!DOXu`=E1A-5!|4=&LVLB?BY$mb%KX@Pl$T~iA!d6SQAUa|iG$<%f1&uX1% zW!TI(>?lj75ukSol1CzPHxhT*W>yh(Q(96oh5x^{d~qrXp`H0 zqRP#NR|;F?8PDK)lh@ap=5-qgZQwB6%OhU9G)V+5zd811IRJG%LV|l&vywukd_-tc zT+?z(%lg$Ec>HpuhLw9+MK=99{ue%a{iJ+!-YC>8d<)_G*lu(!0%wv-pvud4diW0@ zz~xa!#Uqo4#&cdr;SC!~);v+C=^i52TSwDnnPa%rAhBzs41eDUxGs31XF{9`4O{vBcn&cPT!N-_!mLy?+zJHT&40k5Tab z>~=RP_Oo*x^iipEEJ8>!?43~rM`cC)O7hExHZbB-_vrhDX9 zDsFLV@A~QFdevbYDaBg<0Oj}mu6AA@xz*s)P5c(@*7C@TXY(*w6@IS%&o^I0aarmjDnpj2xbWc6hdylJEXse}CzmQ&W}p-_b7G z`Tf@@>sH#vh%F)1?k9OwqLK>~kns6cC4tC8fJQ*zZO>d*Ub&}S!0#@$e$LZ}KRFT* z!I+if1d)tmoN{?M6zNJn>yM)OKlpJf5}{Hm>22ls{{UM3=XaoJ`s?Y|dXA4hkY=}5 znpH2p(g$`Myq$U>FCCmJdeNw_z!ZLGdub@w{6DyocCCA+fo`@Vht{ZA*>d_iU7uN3I;_?uGK zuC%ATZ|y6^aTKV`yH+^lU{!cjCwK?tZ1y#s@Za`uxbeS>wGRtlYBKn8GjDq~lX0q8 zNP|&(b}EsgkCmLNlG_VoV|C`Ysf&1iWTVkPJGW_V(mVcVpMs+$N0~ic{WrhML&+u5 zZ6T6b*^(83n{uES$X$+*CzG<{7?x!l1H)$rCerer(`#-q)Gr|7=7d$_yB8hbi zS)4Wm@UGb3o(~-k4tBN=pf%{4W&WG16LD#;+d!y{@+`B0SQEhm_<+tj9AtfK`KO3D za~G52CrPeo>t}t|wtD_4>Yt(d)?J-a$Kex&`MR#D>8Hu{IsIn)K+@-${{T_ep_C+m zD@`H*IKf|=lgK02u{agRc%#KyMWij_PaNtEr0B{S;j>Z&)~AF1t`uxAQ^sT<4x4N3 z{5;{@Mr(?WF1%W!PS@>k^XaEk#Nyr{S!M}gC`r2YJ{8-g{TA%`{{Y0=r;mSVFC0%j zj-M>)YY&sASZUzARyIgZ+zeqCJa@7*lguE7>V45oAPUYlmIXq^ChSRpf^g$MES4T9hr{=}rk&yqMoo4d zR>^GqyJ*D6P~fyvETryOlVa_`1z3_Zwe!_E^GlXpUXRo8-}7CrO)6ZFN-1skTl)Fi zwT_FyI%HE`>HaA2M~JVl?XF>$O`akCk$s~~8+xf^b>c#dM;=)_!2~uAgfi<*uC(4A z@a#GS^P_3$s#sZ%?7RKMGsQi;hvzxY3X*>I6cV*HZ4~SDjjp{tEvmNuK%CR|a$4KZ zUY54ItygEY%KrckG`|wT;!Qp&t~Gcy4LKghSS?+zEpNVOCO;|UPb@D41CBA3C60YR z#QrhYlFDmS@TbI)t$EA%;I$a0EV6+)@6%P*RRux82Zt9;Uk;|AuAW@C_i(2DigK?dtgULOGI%JBz#JOE z&}}a~Eu!Aq_GQi5=*&uzW=z$*F9 z3Y>6i*TWrmNuNi#xz;qTAHve=3}jZhvb)sf^8gtA+>kPCAcn^Fe7T8o{w$U=Xd4l(6_04Gt|6EXLo9ROX1;Raz)zz0B3!r zCcG?1-nWfaV<#+mgyWvWigw-}@%M!%yqm&)5z=&PeKisXx`8EUjxq}uNv38|^76%* z4p^@h$6ht6rG>;v#tPbVE4J-*-u_*0*I_JFVRo+9mc1?0OMg~ZDC(Xm(=0V>o9#!% zCsfk)7ZBQA&mvo1=@*Etuu543fT#y|nv8^H2qP7rtoS>_vR>&rrR>+%uxb$W2> zXtdK;)3K+m_*=zV-i@Kz>HZ?o^^H#6;F}F@!s-0G`(;nvwZtp}q@fNEA%+Gwh9P^O zhdR~Ah2psIuZmjZOutLHg{8c<(iptg$Zsj5NaJ{z;F#DlsddXKz^yCBIE)09DEvJh z{Hp6z`mLK<>2<2R%~icc2|IahefxITd)%Y0ct^le*hqEX2U%NcT7;OM>r1?ANu;mA-kCuF%(c53N6a#E90YH#}M-{<~j zpN0M_X&({npGeevF+IKJpB#qcUB1!H&YaAzmHz-rx>aPy2OD~ylyC)O*lS-5B-QU= zg5+u%oQ2~Taq5$4(afirGKm-{i@k_u`^OkOgI#j3KV|Id!+#X zeyt@h-M?Ec-|OewLn`-1@od^&uj8FTb^E(rK0h}~mOW9Yf;EVSJC%~%hSH#}^2d|+ zhz6qY$BDGGqo2vpMS0lw#9bEjG37Z5QLc{JL41*0u0|!!~w$7Ot@C^6J-8`7r65 zF6R3~5LxA$%NU&QQoCa(sWKH~RXjnW>YBclZ=>o~DdD{zQPii1X^_fpujP$FLvc0J zu>v*R&4+EH2o+eJwe(LA;-fjcUsSYC`uEvd{{Zk-i;A>k8C@^GRJ*t4-L&g{?zxU~ z_f60=Em1GLGi`6E+3EAN7J5C<5Zql|EE0*Qog`h*!syv5xCaZI4XsvuE3UPacK%hg zQ|ng6mRQc8wh3pr2>YXP7I!A`lbxWdC>X&Vv74rwOS-m+Urx^5ALw~?;H7y>e*MzE z&(;0Od0*1BIIRwir|K5gw-&Di{$0qoaxG<ZDG`NA!#qmIbh61HP~;Q0fAI~t z>0W<(rg+D|z9eZF&82G^Or@iiETaeP-i#SYBeN;*lUmZ9>Dr>YYTNFb>-U|MDpIX{ zJl*vCJAcD@9hQ^vk5RI^OQ>NQP3xAD=vk>Y_bvuY7*0I4_1MI6eqK#_4u$(zjW=TI znp6%;5J}z}r$8Kc$QaLK&r0|{CE$8l-X>UzKI@k4TUX!Ly|ny~wc+j|ua@DK2NNea zts?sJ_I_(*`mV&f-|cj|g_GQA8b#E1LPNSXT*Q%W$itEeIVU3+z#R3jBJr2T&lq@~ z32oxl{>2Qyq@pkbOB--hw>Vxg^5A15n)EnhgRs0mC0V{|i_=H1>G+kJ@eN#kKdMtr zQ|ss2=NE0Lz!b*ro??x=5d?+LA1@s;bM4ciuSw860pqKY9gMyW)-7(Oa#Y>hJ*wn7 zsRgCj3Co}v=PU*?KtD^0g-EYyEfw#t`EU83IaZ`8B(LfJ00V#cbJIL=;aklg!ngho z)I3k6LVO`+E|E1`h7#RLD~FI-@_t~$0Rb5d=N~c7-+?Z4zZ3Xj^m#NLMp@M)lFIU1 zFEn4uBTdYiY(+G07*+YsL$hr8u)LXMYE_}i`Zv=}b+X#~+waqduH$`&M%xH9AAVn#q9^X7Ucougb_HNLKH z?4oS9pKhx&fzWqe4uR@>{#>%K79G6?+Mz=UjG1hNB%@qN)d{h{{VsJ`|H>AF)j24@h^zdD`L?{ zJ3Nx~8k`K5 zW0HPTowbZ*8jjGrX)D_HP3h73em{RiC{&LoBCNh&)&5rWI-i9aoN(L6q-u8Bm-a53 zX>)gRErp{za7`t#RGLLpZQzj0mcYhO7;2lxJ~FfMT#akuuNmq3U}-LI<(R^fO>G+N z3K4wGuFguP$Ki6vj2iW@+>W0uM&0jiFTU%)Utc4`&ML~TAtEewq z#k%!}jl3)2&lN0ckw+`bVqvi|%2E8N(|ITc`7jYlIRqX~dENrHBNrN!ejZ&{UA5O+ z>-lQVnpoNxd^*F_m8YlQ{%zk|Xm}p21>9E?-`Z)HF-F%*0uc#h+}U8KC;{MS3^@Sy zsxrKy0__}5;xoJ~Y88obob~qT2VuqmuTHKSbDU?l_4$zsl$%cJzW)HzF{PhT(^;m{ zX1I!WJP704vj>bGl=RtGAO+M?P-B@bgJ-XBX0JT%ZRuNxKWi8dMtV=A{f=HwhEG5p=jK~?7I49+d z41z#yZw34um&6y6_^0E?i!S^-X9!7D-d`-Y_i8diM31^c3CLCmSAsGKuIwc^;pn<_ zqss*JTP-^2)70^?n20LUs-HDSvwFRMB)YH3p3xVFw7q9Ve-C&wNYwlj@ZHKK=C5+4 zC)J%1z?7CGBAyt9A2t9uECBRhhqjjbCZnf#d&4>|q$9Dlj(4>Xzn5tgjV>p-kZokS zc*#J#?Z+f>w~Dpvw@wdEkG|J`H@A~#CK?Wuo0Ga%ZTEIH{6nhC4}}(3Ad^bB)b(4K zqif0Cq`0z)=K?*=z3{^hN`)9v&3JCNuWJ@p8m6;+5X2`VO%U8o0!^}ZPcXJWeY9-{ z5)Un3Af81;Z%dbz-D#rjchUU44v47AZp+I0ef>Ig{OohyB{p$swt8LnhwL?dPh7Kr z==b&zwkMa(`@<6EMk?+fa0D_8h9ot5zl3~KbEvhZnQMNU4~?UWM3TnwWAiR-3rD%4 zXH*S0mk@BSaM)mQL9L@zYNWe6S?ukt_TP8E+(V?L7|Fd;Zq46IYul>n@*vZq@lT1o zH*4X)2~DCyWo;eCn3|QaNN;B_$QgXgbi|0@`E9&zMI`P8TXkK~HLWwkJ|H^BioPSw z_MK&wZ>=wMW=ZaC)m=}T3y7r(00Fi>e~Txgarn6#etk6b^#1^ZW)PF5K1Cf{y|3%G z{k=YCYvWO6;!R%XRX-0rSF0jMt#7Dl5!+83Ytw5&Se9Z}cGJ+1a0ob_{{UWjwE3*$ z)_2PbvZb=$Txk-(S8vE8d09{Z!AOl*0;lEV0p?c1#&c4fno8R*F5C9}jcL|!g{iy# z4SoCl-!pqp(k@CYdS8q@XjUW$E#cGc?qhHVQE@D2WM12q`}GH{tR6&l1L+{0FH2dZk;b}Hzf4cY}5R_{Pxt!rFqT1RquH;zYBlC z>RZ)3CN&SW-@l0U3%TOBOOLQU%zE5mm;2HG0Lw9h_j8WpCcMMMo-6Tm5~qeE@urhK z%UmnZruchAjU$dQz<&OCW=|~gGNhl>XNIbv>N-4&tJcXcH*59jZ@}oG8mjJkzV_98 z)3@d7nXeCrye06;&d>wc1QYU;866ur87~9RH_y#@?2=n8Y?Z9_?{4~= z)KPEVTCHuT-PQcbZ}lID_dXYY3eA15t64_AW%b>U_Pj1Jym?z0B54Z`lqi}(w;}d| zN0{gy8}V+vti|Dv6nK-wTI`eG8L#w9R=kQRBiu-N-($xaY_3YNBX>E@L{7a5Zg)}B z-rYZ)p3eF&dslsQX4GY9Hyz)}EjHIpKKIl@%jLrfS++h)PQ9vQCmJhIQeP<8kD3 zw;oc$;pxz&T{}H58Eo&P(^i_hO4_Yfsiyr3)l!!%lIL4HY4iC#Q|t0HY`ihzT_aLA z+7+IgJyddyqTf7{ zeRRI7wZ8B8C#z~60r3XA;raYmW$_EdwwAJp<(|*%0_JN+-g zH;z0^JV8CCm+@TcmUj09{fk+a<4jhCm3Au1yPP(6ee87mfM-1PX(+B*6nUw|^t0vj z?)A0rYpt7llTxgzd`&0ho!_VQ&t32?y{B2|_ZM$tsH7_qSldv&Y%w5ZU^`ek^dPWO zcMp`;AL4Bb;l0iB_}2DKW*bqyTZ_#zQG-r~GQcmG@@t2oYdrrV_#7o+=8 zyL)LFU&%Ww-93d)(vonS=KNlssr}2)&pssZyq4!rz16iHb5663V77+yK)9NCpKBl9 z-55^%j31p&bGYsV8t8lt;U9(i?U_qED_NaYrjj{4I}9xY5w-GFQw%T^uE24Ot}$Mv zO4RAaI#QP^=@%O-ulst+*GkDdb+OGlE?*OluG+W$YWm&vR~xJ73wJBp&+!V{(@YA+ z&rR_8i*V|#l`u@9n{WgG2+17gyysokw5HQx@b-n{U19{9XPZ zIo!k*QGlvVdO3DF72_DyrzEev-S2NVZS>JyT+Vc-7(a&b*3RE6_4HdiYMHqgi~JWB zpd_;Jww|nxw$ak*YkR%>ZPTwSglbcK ztKC{j-&VV5*K56X)m_<~wx8jfO%6>rR=x0*>C|M5>iV0Bqd_ZUcxj7m@)ZyI%mBLx z#_a7|_80nu{wmjJnn-W_Q+an1O?`K6_Ua$Y4d%twV~ry!PU0A#UO*uSTxrJ6agMrQ z?$Y+Z&$axK$2-=Huh(ANbXWE7(OT%Mp?I6^daSZ*8mZCV1iXY?-A12f&BVT5SwgbL z5!FD;5XD!KxQgs-A5ZZqu+;7yuI{6r!tA@`~at9;_0A^^^ zsM@CviKXYKpId3CXQ`~|I(0dvD_Of=rn;wYk6m{B4=uF#YvB(PYC46lfjo5r7-0_t zdc0!Y^Vtb+k(+iG4L8+Z&!+7ZTDjCfh^5v&?{W|*jc{6XqKeG(FKZ|s0Nc?{r_=0ze>dwy2 z!NiGx7`qur2xIvOEWb8Dz~G;vbnk;!z96`VNcfxMuN!!)QfrH#R>JNW*3E>Fw1z;T zf|If)D%-h_a3iV8t`>z^sWo z3Tl?#Iq`;zb7HMLaA~(Mdvk4S&@!_#D!WCw_l$ybkVZ0V$$lvKgGTU=!rOlUd@k{3 zxqo7pHush{le9K+S`l#mU>Q*}?gt>EjiH-!5H{BoJ%#@OcNDFA?X|YH_OrkI0p6^o z7g9~Dt=7MnU%7d1c{jyxjc@TA!P+K`s)@g~^sCpFLvacssA2Q0VLw!1s&uJ5;9 zQq`YFmQtq_;ZtXRuSD(nZFlJJxsiF{)xGf!siJs7&+Hbqs3aD@+8%6ft%9IrWw5M^ zgU`xAIplR0z7Y6hs%Vz&bq=u(y%Z?&TF7JxA^=D$vOZC;stJ6l3_xHBuPYB-PNbDN zT1j2$ZS2$6dw-HXlM#W18WB}v*G;e1_qDD17GTk}Z8yVqt*A{cwS%mqPqL16hG`ve z;zp4`Ert=2SO9X^#z0=mElb2cE!3p&Ux?@PZLd-ZBhvJOu)<}LQ~@eHs)GRz)^f}b zQJhubrB1DBMSHi`<)XjO@4rKz6^E-%lC`Xp{avl{>+)tlh%dEIgnl5GQqfuqKexis z-1!nlmXOX^HmTQ>gl0+rK1tcQ@ zgqJ5I90Py|-SibA<0qxo`(0k$K7WP0kAQX4uk9*JM`h=ypXcV!V)$#~T?;~eBF97U z#;6UpnRfG(wo9gGZN@2^V-J@Sx^e>m6^Z+#dc1RZuT;_wvEc1zK-KNu;xTcjwbNT( zc`lJEM!3hCxi~@`ZN|_~BDcfM#?noveLZch{{TO`)aR>3O}AFkO>5nMU+~8rtlmwj zEuV(`DXeO~0P!B4(_LEW`n{lv((Oo)2YuuBE+UcnP{0P-Nf_Ho=;%6TonV3C&)LUH(^dueS+8rl&BW2b_LnHJuuK(VvO)mfNaGQox=HzoHK!Mh zJSpJBOOFBm%!1Tvmcj{6uJX+s!9YK_eTv7ZV}r;e105<3ZMAulSG&@zQr>SQ<7-KD32_>nl6MSp zxj746w}yTJd_M4Qk#m3X21}h+#4)^+yta=n_n4I}Gch4dV4fMuZYOXDAe<{#l%F*E z+t1Ty>29`q9dM@_G}SsU=hgoJTkLfjJjvpC<$e)z_r4w)R-hKyAu)tu3KfAuG;oY(ZU<1< z5dv^`6Pu*zKiaxA%uREywyK-%?e3Z&ETyynEUe0*UBkM}GNHi{lF9-3b@yja-ro1O zt-IdaCc2W+kG!|j@a^XB{{ReWX#O7XmYP=U#2WUaqugp?H7yrXg57N)*)PiSL=~6- zip-`kq#ewl?re_VRX#4%ZY=x{CFs;mg|GIFma%lnEzFTcgB-EQBmV$MkN6C7Ch@xj zoSMR%B|dbT*7oUi^!~ef*qX1J&QZGEb=7oReExeffbdnNmbw1`2`|N62FFN>?#fL< z33QwCvPS!XOQGWk~ev6QxF{v+gX#7IAwq6+4tvpp^tQuC5#Oc>T8vzr`bLGBD zsq+z)v!9nHohs9EZu))8Rkojl^ZS&k!lgASYNKm+TKQh~`}&@_@aswN+URzvW#Fx2 zPPkZuUj)09%WWF&JCH%KgC3z>MsjnL!PD^;tMKo`v7>m2^=)Qb*$c*9oA)otPoL&6 z$Z|mkYLG|(*Bh>!?-i@{do6l9zw4l-1yLo;?ehNsKh(}XEb*?9bp+l6@a^M8DOu!H zvX114WX{wkH3icvlH1oE2(HgoHm_|KtKx47+r=c7;}^$9ON0{OHgO`5yn=rAI5|95 zi;t^PHGRw8`oFtm*KWsF9aH2{pY`j|uP2Q)O=>CabRQ3RmF=?@u;9#>Eym=L!g}^{wP~i*3G5Ov>#P8REG;%)!kpo+3xI~rqJbaPED(H{QLUrr>{)gd(8{S_KT(I9wPCq_wd5YZZ%6m zZRNs1+#;DGXyXN!1ce2;C5QypL|zt?MAIbjmA18|#+P8p4xYXzl+4c9%LpyvDt;)H|*@rp;;!{Lo95-JToe{amUJgtq0;9ejM?E@YTJNYOD5ko;#Rrg{PXW z{Mgq3*R__a&H66)RY`5qD!vVoxcMa zRgFf}Z2thSyY5J>;p@MM+B9;uyJa4%(Up;>(eBp9YxUuGF;&AIy)lw-aC2Am{b$3H zK`62KcjAp%S(*vuyuP1MSmeers-|ZfN&%dGB3j zgW^99_*YQAi&)pR`%Omj;{x7UWs#VYa{I0v#{D+`0CZ=rahk7F>ow&VO6@DXdHl3| z%G+ON`f6P`Nvrbt+Rb;>t2g&c@e{_HKaPB9rB0f1$)?ys&KpqFZeX@!3jw%A97PpD z1mKlyU^YntythK0KLKbKT784~emyC!q_ne=>SakJm4*@Hkpn!(1g7;W03?ucf!&6# z>+?}f8(*(o7MeG@zKdO2((8OZU&3(f zH>rE9YO%pJt-8S|(PN%ldkD7XKcD3@+&r!Fz&ys>NhJK)gZop$V@!V!XcAj!jjVas zH&ES1?{f0Tut9DLvVk#UxI(#6fDSkb*G7|3j8tuYw%6zKZCkRk>1--fl#`No(`)>- z^m_X9UFc?~hO|u*`rgf~zT9mC#XN@j+G(y@Q06F7IWp3(D$c3_a>M{oWo{>nNWI39 ztx0EdWhzM=5qV8zdu=dtmIcn)7kjBv3Hf3qV6m;`2u7N;yuaY-+1c&2{TH25GgVuZ zbnAZmTk-4L=2wSO(L6;aqpXu}Z#|Zw9PK=6kv!Itvq5nSOpF;+tM4NR2nI;pF$K1* z@dru1iqpdDqw2mMy>i-g7g8n~W!j)bk>!wpi;7b}c`TC1gJdwMtj z00pf(-^uQA#+69PK|L(Gt-U&WdOMo8+E;*}u`PG;2Ub{ap*Hiu6}*>1X#i$$vnkqC z9ltbu5(qdvgHh2m4Ln#2Zy$J)IZ#CwocH&zSlhy|ugu@PAjTB1##7W}f@S zi{{4^Vij^%<|i2+d5FbpYFEB1(e&+3Zw_cl;Ol7=rOu(K>HyqLZxK70e7(j?i2{<$ zNyY#JInSdEJgP-Gt1WeRPrdEB*Sg!tiuEbNqE^>SrDu2N(%Nlz-?KP7D|-@zvedkz)n6n+BS*-Kmvf zTc>12Pbf34Nanb4?4ZPRo zgT$U3p7PQdF3d7ow~-)rjS9a*y9}({{q4k%F~_%f2g5c=;8=BAJ3T@xsf$BCqoZm? zq_oO5eCV0Bw?zdTW;oi+4<0r#J1HpWucq&9y6e?j@wJbw%An&-#l2mZ&A-+E0KjLO zTj>5O(ELxW-`E?O#gw!E0HjDGfn-D{ot+nepe}g9RnKo`@P~*kHNS>>rlYL*O4X)# z{L^(lnn8Cvn`CTX%g#_Ax--+BmFC8TaW&p1jFs-ztI6)WufO&8Ra*3trCKkSc-gzZ zFHgInM(0J=tu12IH4QxB(V`XX; zUgjyM^Gu4xiZd&69GoseQUVNh&2we7D9;ewG_uiK&i??93t6z7T^}O&ZtCwzdxv*+worr;bK4lOms$LrBGo^Yb8L_&DT^{=KVsb5qeg zL7~`Qcym+z=96MFrWj!LSpH{nC-FsXi5eMZy7*QsMGaCb+T_D1>I3KF=; zz;FPj=NZk@oHo0*yY*J-YwEje-c(`V4)>Nk&kxgIAU!P8kZkv7j%P*80QfpVPo?d!?U3EKqPYY=_HrJXT zf_zJ+K8ZMQwd%L_GHPnzZaYR~SV=}87BQ6rBP_vy#lHBR@HayS8|&RW#5%o`$Rf3S zOPS+{s}tsNDOg9#mQcH&7{C|+tlb;l-rg4)uzAKbAu6CP^Qv;^Ig9EebkYG z1H&n4KKU*@n>kETGtR_`84R0)GC2gUK4977=B!;R&tIQky|>eJ`wa_MS%R|9EUz8E zn8>nuB3T3^Zeo0*RI4)#0svKC6CQnD%WZy5Uta$JjrKV3^wcA6{{WAFFS%UkwY^Gj z3iuCE@PCOk`E`iwbqR;|Y`S|Tv?KuGZE}hg0ADepX24beWMGOOANX;u{6e#^zVM#5 zZDY5vmgd^t@@d4jk+PM0c=ME!Kbr)u9xz7X>x#Qg$t~OdmuG#tXpK^oKY7u;zF(hx zZ=-z;&11ut`d5ea=)6a%L)9nylo5CiwhU4YiaT)?f(gSYUkVfB^gPli@NAT8} zAC5j8Ymw-8_b$rOXpCjGyJk>YG>w(x-haA8EHh#;We4&1g}fqJZG1T%lYS#$7-=8us$$cfv_E6!0`Q9SInL)@0X;O2@BQ?WbRIv3GO4pV2)>ri3@a^BBq-5$r zC~5t7T3hn!YUs8<4z*oTwH-e2TT5<%M7lPweFpKj4YD~x#(IokwsL**dsOkRnV@Lt z1RgnuOO|NbD|Obq%bT`lI9=N$L7d?8zmtJVa*b(4IXJuY{BNVv`nXCFgj7 zw7Lw*98IeDkx6AL2p}n8ovbmq=dtHC!CMjS=A2vPU39zGTRT}R`Jj#pE;_5X>1&*i zjI|$yz5&!z!rHEhe{8R2vpZop7;vKNeypo7$4br|%f{{RwvDdHawT|wXrogQ2N z05>pQY8ph4tS5u>Pd}KiCr_EMK3wsPR+Xtybk#}`R_}j%U36Ak_D{cZs79ot%~E%_ z%HCFX{{Sb@o5PU&Mw`O-J|ppOjQmrpMFYR?^!;~C7V`{|vEC5UOP%9}j9_B`bgwJ% zo$rVIW31chw;G0~`9(6B z7>ce9JrdRaxBj#|+u_f|?RQDluE&M^KcrgQ>!s~)ZKZdP3x;3|MY*ui@xSE^2cRPc zyT!=rEegR*)M&yFhU6>d|k;?8qDui~>#uSl0|CcV2ZG=CYEq zY4q&<8d^7NS+##|tej)YmEO9&zIL_txBNRgzZZC;Q}Er*y^n@8ZBI(pZ%3PVEtSMC zX>x!ll2&O8M=NkX^h=za5=JYVm&1d``h;)d4P!u)Qn`os%Wb3^E88arVoD{2u_I># z1s6G8pn;0>sLE{t(_DkghGrnK@}n+5#?XAn z`e&tbIvuX92>#CTZ-KOzd)Z@ zOI;fIMps@|x1d*opxkELzPGb|^xb|s^}9R24z8W0O=YIX;NK4E1&ER1y}X9wQ(gZoE-_;=6gC^TbmVZw%Unyz617AqN3voTEs^c+64l`MLl= zuKX?iqLY(Jtu%Jt&8wuJ{kpH_a@31d+KjtzYreML`su!lUm-NTA6M|cv2&}9L&H-| zr(4AodZds@(AqB5Qh=a_6(oSiX?7z6DQ*8cb&TK_fO2G z@dmwprrX`?TIYs5GvU2H;%j^1X=H5UwzwI}S;o;jN>1^TpfeS1?YC&HTb(0Px$y>x zb>YiPjWADj4sf3akzxt>{6{5xVcY#-p|teb-nDm zlUACm%_&DsQq|eJ?)BAdx8LtCXbs`*V#*yiLh*K&X{KoQk{gNEV20jj&zmbNe5OsJ zUR8O>UD3u!I2ZmFvDP$+hJh1lkxL^qEoTsn+|3*T)a+$NL<4g+7ju2!3YFZUA883f zqQ8H?O;*oc{VsD?r!^%zf5GbXzPsN40HbG-c-u(Ud>eT^=AEm~_qwc8TP^IW%WHXR zQ0@bGatmi_oFE}`GoB9(d{LXhc5`W3u9pN1*9?(M0uMS7nRhszCX9lh#uVqOgU30F zwAz|>eQ(zH^7K}EUrwERsLfT3Q{C#UyKJvyv};W@-u+Kv(LOloH#)tmT58kjmyks3 zFZTWUiV0+A$SW*QA~x;khK*MwwpSz_JzwG`j+*L2f1q33!EtqMw(i4H8k~~JwE4{& z#KfJbLYT=6LlcAnjdDi6)zWnBZkykt-q!o|UT3Ka5udwJ+1s+U*W-To-?>pfBgLa= zvMz}xwGY`0rWm!YDp=!nExBTXcs#a1!ANg0p{Hq*~lvV?v$t+)y+Nsp7IKOA^+V=0+S?g>0?DXyyqbY68du_MRuKxh= zY^`o%#Qy*gyj$XBbUrxLbUhvhR<*Reu(GnYo>y?v@0K|e3CV4v=5OK0Q-OW2_+6Rq zd|mMdU20v-kXv|cO(a&pOfnOG#fmj9_`?uRGn|87ojAr;sQUc>03Xx7=Opgcsc+G% zrF-k6*Iw3tnJ$yAcso~wwzaNHrD;~8Snag=HDK~O7Y^m1wTxpsT$0QVb{w4MtN5$p z+;QkPFnA_sx3-1iY3GX3QEoRD^9-y=VonLcEa&DsuyT4OQVRahS8nTNwyxc}bUe3# zsZysb)}EHTZ?)U+tJBMK3*kS8E;TQ0r2IXmvXkg7qh;!xwvUAp^DMjQUkFh$J!#oN}*7n;bE2Dg|nY48yiwiXs7rOR8Wj!7Eg2DO%Xr)Q0} zU?T?%NM162X4-n1_pgWgUDt_z65rg~=>Bcjku{WPRwZL7U;-;h`;ZeNpOptBe->-y z@SM~m&ly?kd-c-)0M+!qx9EO>MzuQ8tnmfFS5jB674T7AUEUD7Xjh~so;IZ?(& z8=CX*^Gg=JjI>^fJ8StbPsr@X(vQ^|sULYOuP&PQ)#!_V12wxnLq*m89^TqPr^Tn= zHG|BkZRMWcKx1W*IbeLkg^3`4s~7};WAX3y7Kdr3SYF2*T7`xwfb9M$oxMr!?%fUFMYLZ*4myUr2JO#9hCFv zz7q5Gdl=@#7T2&_+?k0gT@Lup)D6f0V+4{tJr_XuKk+Bx65H!HdR~j+Hj)NeV$yWs zWh9WX3fu75`?%-;?bKJNm0;`U%h@?K1%LDV-QBIy-e*2Oz8fcxx01Y_v`zNj-BIc~ zC&BNCx)r>3R(};QUex^TmsYUc?QCr!T18?;-Z7EKZq>hO@J3{ft;G5p!8S$252OIM z1ZM$)IsyUC0UTuGt$hTzMlQ}(n@hUu)t@4`s(kuUHly&*#`+w$G5B87#8cbdD+}vrd||OA+(E!e zZO9ysatI(}rE^!|8jyo{epx>Hr*55J=DtU>g5!Q!C}O#yy&~7-t>3BT-Y)R(jdXNt zjZfg$h&2zeuzPPeT9M<1Ab=4ZcG04OSOQ1@^MVfsymd7lT1UNx=ISjfMsg*ynXV+6 zSdtq6WCs~1al>$MdmoaZ@G8BpXa`(*x@sLHa?qpdGmQ_zYAaI`5up> z+vrxFZl7@LsC&n9j={7xO+IO`TD&c-Twe4yPi%VO0`aDJ8tcJek-!_OR1xz zX&SDzd1YyO`gN>#iyg+BZK&NxVE}A=k^PJ@VqY6$W@RG)@-}aWQPS4)Uy=*0I^^D5 zStJb?i5XpHcO^@+>|dV=!ve4JDcaZ~xoTous$C?l-CM4oE}p+LcvAYjEvwT@em4DE z++P!Tm&X1ZQ{lTw;=I#zeLmD*%c(}U7Xi?a##sxHNMb--u*O%8RBCu`9cRMc4xeAs z+Itu^`4(91c6rb&+d{0Cj{_EhWF>|PSHgf*fFN>WBWHs0Mljo|sMC|{ZH z+WYqT{{U7Z(L6=tdr6x{_=~FenoSE(Pcl7kN7PHhY|Yg9G5n4*)c{ucSb^HKbiaiD zAHTi0eG|sIH21b`8QAGF$kF5GbP%YNcP9rRlafIds%f_*^m?YccTZK@uid4EQlfU0 zHNNX+zJKSY=b_o_w;mbrjp4eS-sv&Pf--c-<@2j4jbzV&0>3m*~Q zBsw#AhI`p<+FvnzL3-xtICWT3P5YNWbgS`$$*&bqojFP>*1h^IFRI_8E~Rwajh?-& z{eDF=s(9Ys;@ZPe)NV8#F(hH+c&1lmRKk~4mS~IQhI|${2l$BMyUz+wd#A@_qr*BO zu#!V1w7PDgr`=80{bCszS-}OePd!c-9QoL)buh`euXWv}cWw8xyRuyto<{g-D(_XU z&ddD2LvvHqmN9uYo#TCTPfKWsn$CSgPnIA6AhAM|a7Y6ihx4jS6n-+(q`TEL;i}K& z8RLTEODQH;fU%jt@se9Bt@dqxR$rmDI4@?VotoYLul^hH zIe!-F+U&Zdv1wZEm8_6LC%2mJQ42Io0B<(ZIGGuN1cm?;?TW>Ld>`Tmv5}_KwN|xR z3Tl>`k+!skQUUVWA>^qI!5fG<2Wt*GT?{1}(Nv*sRlmEU=#+Hc+C3lNq$x?o%2M9_ zAN&{P`IyppbHmFokvEETXr+#5p4vS!eMZVvWh`13xo9yI98ZrtYvNl= zlWl$D9}C^+_VYYPNYQn9u60|MAg;-$pMAtYbY@++;1%bHp;=U$Ud{8R)y3O=U7t}&1lM(YuNQb1 zQ@OI#rY!T#;l}$c$Vnnap4wz)jk@Jfoy28F6{V#3_e;64eM3gEU0Uv2g5De>^$XGVUoJ9oJfR^|k&ce19dXd~RmRt+ zRYG%*qE1)n?ah0&-%mz!x^(3x;TL}TFUxPl;;g(g;0b4iZ@hgKwxw|{_0zNqtH;{v z2n@FH88fv(11A6sbON>EwebFyvO%Wnw~*>(CMBKbytr6~2{JZI#lLSqykFuN3~;(i zr9~FyO}B0Nb+X+n>*did{R|xmMJLXZZ)>kRUf1j2SHGFVYZe|kxz)zG;?Egby2{>0 zk!5M5p}VmgzV)n5A7)B`%)@uxA;v+jP<%z#wCnqzEVTsi<($(+s9eb*nrRN~7nVqz zubCkQcKoUW?HjhHJ)AXq6`}0y$n?8@Yh}E2Ys*({w%SvdHJa08m*IQs=(_6n-pz)w zX{~sYJxXs54O3RW276oGVW76L(CuP%-Q~vT3%8G*(;O)aBWEm!Qq%9|zOdBw{XWw} zdndSnX%f6kAC}BgS>?|AhIZWEP%i77m5i_n?^2W_O*GT8PS(?1+iLyoe)iheF?8<)6r|I)0R#SO+_fBrkixK@@mgTuCJ=so7Mg!cwS9O?(J=4w6|#)qLS)%lHO}~ zRYpuQhLx8imSVexKs$|any#~C_VFxnH1{$Gk!84XhlOxmo zTmCE0{tx^UdQ=}Z=F(sA{eM3GNUM3L>%JsyxoZ?9K({Vs=6-vNAce8m3%!aJwih}Y&>Z>6}Fck>GzmSKj&0l>$~ z4neJ*FW?7=?V*%wUKZ132L>|}2*%US-GC?u9S^r(Uqk&~#$hbrp(ojXMghR}?~h_Mqf(NmiJ=wV*5BlLPaRv^IpMJl+hwlZwLBZ+ z$Lx#ZF9KWt0K!S&i-*0kjh(KZNkdA2e8K)z;A9NrBzubTF9z%4Ykfu!5NW!U(|w}Q zOBJ#^Czrf$cELNblpve{Kpcz;_>6uEoeWLjz1wN0maF9d08QET*?uZ`>@V*uryD2R ze>?R4mrtp_73g>R1o!v8DQUC^hQiW22}?0(?&b5`M5`O@Br5=3Me_)35;8L15$IZW zk)&&0GM?4!&ZNrFK$mhLCD1H|V{x#y95<>R-1Q6d`N~u%xkKW+^wB$g&qdYs+h4EY zdQqu}Q@)=rw%g>N=hXR%(^S*7Ul-WH;uz%9bd|r69_`~}BvCeerFH<0ag68JJab=M zd@8f>N%&)^{{Uj?Z6=@P?Yl{BPnitc5jMu;?ccm-CGmm>1FxM2PuWHhT*+(s>FH;; zq3zLx@bz5c`CDmzI$3(JxjhVf-9t<|q_%PBcGi~~T1PY}lLARGgaLw(g!Z``7f2pY}`|Y+fvDTiqJN_x9|@OO;cwCO%aJ75*%ooOJ8P zKH{;{?k>EMXSBvZAwqnlZQ}=w{{SyR>-t7XS}z3|bl3dPf#SMVBbd5fY`pxxuQOWT z!#8ONmR+u7901JQkEb8YwLU)&Pib&xnnNussTP|n z-zBw`yE?C!goBVl2b0jAzkvK}n%BHppy@V@WVwnqc2&WYFz3{Rg;Cs}Q&;_=3Nhxb zD=xnyDc~Jh^3sjo-+9IAzZJYIWU_s#{@9gK<(O5NmLO#A*^FbKe%0k#{7(Z~u&rCfaKSCiL}M?H=}uO}Ctg_kr{uczyN z-8!5niZwrn7Lre;_;$}twYixAMvhq=1GQUmTn5Mmw;UXG$0s&CHKBNe#WP!Kdj6$# zZWiS%?UczQODZx2d2;K?B<|Ws`AZYV4Sbd%P_0tfeHH%z;Qs($GwP(OVd*NBuH~(^ zzn}aQxA8Q(eUP-!EH!H_HE&=7OF6BY?s#KSD!hUGxk{{z%@|RPFYt^2ypDrC#)+@r z>qTLmpw!}m+81E6*hnKRmkz(`mfemPL&E&M6at6G#8Q^3S66nomG%48lIolLx1&`g z*Or|%eSEz-^trQtH;Qzat~^We1H-pAxBhZOA54N7%6lv;yUT6O93 z`Crcc4v9iF6Pmw&>(i%}oeK-2-RhIWrb!09VWPB>G;$;|-cJAnB<=-W`3sd1m0{T9 zj>Ap1)h_I!z0q|)1$dU;*5tIUX+POzk(2->iI_2ld<;4O6c7&Im=jW?PL-u6?%wIG zR=pqJ>95_%%;y&*uiv_Va_!NbCXeEe0BYBQ)*J0cEn%Q*Q){W)ERx9GN%Ih+KLF%8 z4EY`SI{H4n1*Gv`=~`})bEKJFXGn|465=ugDU5)T5>H%*B%G-OHO=*v7|RbkKGs`4 z_qWf_W=yckGgV`Ib$u=A{{RoFtUW=rv2#N*1uls^}qQVT~xm!ySLBr+`!Z$ z_-f3SzBanoG^;3lw}M29$H=>qMJ|}Q`Q2Dx^3nwu88yOdS6>GH8rjRL-25QcBA(Xb zM7X`x&86g*0RzyEk0TP<6IW)WK>C_5zEVzH`>_ap(6pH2hC-XyoUx?K)d z@Ey#$Oirmbp9GM^ser$Cu812N0vQ1$tE!CaY-d;_L#R+vIarsGYrC0ACKAf>~#JNz6XBk~J(_W2q z-K#gce)F~0u$3t;XD1iiYka)6?WKt=yis%G>$@Kicn4X~wHvE6X|+8*`$9i#w*L7N zgmbjJ6Oph0NG--|r}$&4X}%$j&&2w6g{El|PVEfyX!^8_o@zN(5{TTL*!h7m$fO^= zimYW>Vd+W}ZXBsbT-v9-y4h)}Uh8+!-pqeji`7Q&%kT5j-d6p6Q&{n3&xiDDdmR}x ze-LSLZjSa#txYCXkgx%93@3r;VNfzU^ISKHybGY}(=Uj$UlaHzPnOyZmR2xnl0C`- zN0gpyb1JI>K2jAABw%w`Q*|Y5MG3h*oMUyX(^qL}*WR;M)yZDi$}odalD3<@H1gFN zo)qz4#T!|MoUmwmb+l~IHmRszG|dt)`9O)BmKx?P4`^4nqt9{$(+DiSdu9DHF?2Nsn zsoG5>p32{SuhZ2%cJ8^U{4;fF;!6+sOgw8f=ZFo9#3g~`xO>3N8)3Ez6%aNvk{IQ3 zzzW;fej@4q9`IDUcZs8$K+yEq!dvP3ZN!u6GB6k$_OVn^jPgRA*ugxW`BRNW3QM!#*qU-R<{=>@IvSr{2gQ+8q}D zP3WpsBZ*i<&&dtRIW4_GIrFcHJ_wp+v(dauuTQ00*|hU%J{8cd%;-F{-mQ5#bGlXl zHW`cc+m1-@!qKILl$}JR{{U6h$*q45mgtD7I;zyEyFGP%p6<)ZS$yx+yc=CR#9AJk zt7={|(R8z+>I)nfFzKOM>_Vsrhjc|mOCeRuw%lawQ;Hm|Rf zZ+&*s`dg*lx!;H$D7Dw^uQZGA2eyZ#q_Mq*>z9IS^qN*zo-wqCk3{Le}77sL&3OVeR}TSjwWgd;nzmc{!zh9QW{510efIOCtH{3m_k zxvU}7G?^?yUMiLloGCpxAajG;BfWm5lx8ZtRT-;ETgdnxDZtdF6U;>tCO*X=R{% zN1H~~q=v*@TtH=-c6Wv-#Hjm-P^76{%1=LgIdtNh3HFk@2x_bbk%4mYb(WUfnJdc$WE>$$4UU%d}_;yo7*53}6-qA(p;FHmOga z+RL)Kw|##dHrak3qVUZMzRgCP+VW4)Tk^VHe1Oe&w55ZfhWcVlI*=2x5a8;UFQW&K#Cf(%<8~~-TduIn3z%|d7Vtuma=J{*V z{(gVfhi+kmSa{h%-AKx-^8IdQcyCG78%S+mUbu=&n~6hkg-a-2RE~0eeeuv@ zw6s4E8*BBlxHopOTU-gDkTwuHl8YYEk~*($fODK0{Qm$i#Ql38FK42&TIqfJKRew0 z9~*_Cm0+pDt=!wYd;FK9(9iv({2V-C;fqas!+JfP=AkXg$+ee!jS4Gs<*ObuAwS*) zwva`9)g(HX#2cM1Eh;#ojvGi-$c>>78{W1c#I3IZ6o-z77F%h9dp7&8&wdZSE z`t5B$Tc3nybzMAU>dFo(_eu5X<#%;|_;cug*;~L*2Z^rkuP<(=Ht06GP4XUkGXQhI z0|9_I93J0m=~`40n9}Ct6OWvsd}kf=jB&$uG5=9Xc!(Ft1aQdU73qQj+uzeU9jhwu z;m(yJv@@OPTYIp4F>HGtKAjIe^In{CTs|_-5V^i*&SEo4^c|@?6eaj;;ag}~mrsUA z+Csdk<`u{}<-7IA9ChNj?-YCq@b<3(xr0qH$s>SD;B$kVvGpgOgx6%aS1$HiQ@5kn z@A(S{#Q4b7wC3OS*z!G3;S3%Vy%$~`o#44;mezI`X_6#DfDEs7XB__kc%HS3KZG>s zZK9siJ$}+ZCRZjE-5@HNBaGz%Imo~q;Nz#oW3t>X9xp1N7~O}py0(|^eO>^3^4 zA~Bp=?C!1TbUqxg({)RBxYBPdw5>+%Ob*uY%QTXOBq2m?zy^fA;k~|P+&V5G)BIN* zma>oH4+C$uwcBBS+KK{>&m?9^cQ6hZg+{`VLELaRI6g)<4I5cX(bZ{m(`i}R-Dz*@ zQ>K+iDw0!Lt(&&1rr+07OUIXXx>3`0T_)dGxbS2TbCyBBd_rHh#>I{=i#1)nvMRMZxTywbv&@gHM=QZUO7mX*o=*> z8B{qqL(;aqU8ri_7uT)D-@}OY8>^Ho_g0=tUk6^2lM0DkZ7q;vBd&5XN>Pj?@by}? zuDu?%eqZqGu@z$}K4|Ik>-}5H%$LGGGO_Vqnig$S!58sCB!<#k$RdLNz$;)Y#JMa3 zY+cF~utDVUSFSum@gG^Sd2|hX!jZs&G?wXgxo&M$@W892g`G%XFsy)k3c%Gws(;Tx#wZH9O+M)-lC$#H+K>No2VWBc6-UAD+sfGS~{0!rfno`G2}kJoM>}M@o%X3TpONfAD+$h?eJ8 zH+y~~ejq=?=eM`hCDd(SRB4lKz4ON;j2I9x9L*jSb=*#P?~GF0O=aLHBDvI;OR`c7 zaatImhVEwL?kplCIU|pqo2DzD7dKB0%A%B=?5%gcj@qkypUBpQDSJ*>{6E)YLigea zi1mMPvxh>nv%0r$I&EI- zSc2kdBF@vlYb=1^l7DtMAMh$vaMP(t(rqPeZ)Wd)zowruT%pa(_gioGY5jgiKg6FH zd^qu9S?jv4rJ+TtloGAO+3F5_vyck3BQlP0x6B=SipTIr!v6pac=uY1;ynH_)TPu_ znkZn=bVF|On9u@FT_gd31Mev#IoZLiDdA5RNf(CK;n9lf zQ@M2u-Bd>y+nvlKwuvJrk&+9A2Nlm+r0Px8t5ViiTWz-5MS1St`dmpxK`onKf2aHt zfzo_+;+t(1wEqAGTI&|_UC0y|G+Q(wfcd40;spxCd#^bA-D|w?k@1F=2mBaX`4-2N=^oH~m5vM&K@9vRoJraoS!r%r9zE&(MPHJfa62E!H%p@?EP z9o5m^_}~5#>#GTTNvC*oUy|Iy?If^W=3lG&%DaX7-P9i``c>+-grrzC?&(=tUxa*Nrg-M&{{Y868`bTt#H}Tx+J9%=%{+UsT7Nk+ zjNp$hHDYs+Pc6Yi2`4E!7kt{sc_zAAOW{iIOC_SSwZ%I0)|0lHf5X|QeY~%^-rs5- zG14_ViRJK4m#JwEgUYyH)mtX-@gal{2~7U z3FKZIMbxCzw77sbi9C>8F)@+f&3`+O_zA~A0mT(uaQJvT#`3e#E46KJcHiM`Ht1z2 zw^Gtyjne75OJ7!S{xpW$#JBNyVYJ)%u40At6DF6bPiJn+kT*>`zEB>^^AUse9!D3# z--?!=FnRnvqb7;rOE*aw;?!D5oCeAf<}Wuo6Wfh(hg;i$OKApx&BCi-IAn{UUT7}5$j_|hRefumvT0!#a1I? z9(kcssFAh7A+`o?iG}3nEOB0qFK_JQI@>82|_%!j;X6_+g_Vr zuid(_G&Y_myp?0sFT62ts5GBqyt}>ClH%s&6oo~OE$mehvOZN(NaUK{@h^z9eFsgn z(KK%!ORii=3#HVlYn_ol1(Abp05L=51yFW_@}9lx5f>F1P0sqg9-Wq{X{EgHz0N#D zTdbTZ^4q?fZEIf3*SAy8Q9L=SS-pwQ;dmf>i?|vUxlC>-&I2%ffO#VUdSIIOpN8HC z(WkN+m4%+3Y@~7(B2~!RINZ4TjyUHX`V)%%3xb^n=Cr++p4a~Xfquu&@g-bF4-Vxk z+1+WP^82mw?s_2jccV{f8^Zv$Q-U_ZziS@roDk!Ykmauyf@Eb2K>vj602JAh& z20)qn%u{w7uhz3HH6v@N$8m27mMNM=kyZrxSn{M7AYd>U>z_*a9D+3#EzWk8-&XqT z_n)M3LZs=&I;$-#ucCVS?7C`qk?IyU;nMXbfh4z<-bmp<$s#xb&ly$uh~bbfJD!K< z8~*?c+4vh;{?F5pMC%)g6L@w7xz0g2%ATFGU!hK{Tb3G)xm&yPy3zVJucpraN8o%( zm(-Rs4>?BAmYUhOZmo2CCZ4-)eO>!B_*YibJSH_gQU@Pym+esbGlR7;!$=EqFi8XP z>t5-p>yYU7n<8T?kawNIfjGthE!&FyTAdk74@QHw%l-!IeUHd-b)gJRdXZL1w6^J| zNBuL2f(=twm`$m~ZR1j1AXh@b9;EHhC-eL(PAdy_hjai4vzB7yf`0%j+Mw4eNgqE| zNvApg0AF|Y+=^IL!3i4-6UkwMeS!Y~KD9>f(sIZQOSFuZZb&)c41OQ|YWhqfj4jN3 zt~t(b@L$*Uv4MYgXJ;bYy0ovzZKSXm&pkfB{d(a1QSk`bNhY7C?tWM_ZU_M2@$!!O z9sB)jk2}t&<?gi4&-ZuYY4{dw5s?L153DW^-6w=iF5#3HI*NQ_BByQ5H5w_p)~PIn#vuGho5 zoI_CA;;my*x?N)7t}dp!MPRa`?JOlHKXp(L-9XOKoY#vudt};AMXk2d$>{vQKfAKL z;-kw4>3_Xh{{X|4d>3IRi}4jB@jkm1m4OpW=Byd>2;V4*D81d+I4ky_gS z0E_g02Wpo-5{F2ZZ7N2RHkK*lh%8MZD$%1c5xibxgZD=Ta6Vpx#>7*th^o16qif%5 z_P_iTyECQ`F#`5HPdtKn@*!fjFQu5Lz}uMMuJXzL?K6o4YfEF)y5Fc^ax z%HUw&E((jHTTcz>+D@^q_zD;_xSlC(HEk-#s;){kmfv@mPwS@T*|h%vhxQURzLVh%1+^q5X)WH?7MyXk7^G6I$Q&J~ z0AQ%du18$bt#vex%fqkXt36$c`S*WfH!{Q*KPQ;5MzE2%<8$=~fnI$y<5@*Xw(q6y zWu@1SMBriAkeL@ygPiy#NI9NvD6?QT=$UavE5$@5-|H2rMYh{nL~c=IFx53 zW2G*w;SU^Y7Kc{xC&oKFjWr5fBv$dqrr!l}!FS0hc_2_Y{nG9~!ZU`dt4^G%b4fX0 zXQNmD01l4Vw{F{9=#1P_m6EpWxB347S9d(i#J(BSr=5IH@ZVh3Ci99!o**+!l3NU8 z_wq<&xREeG%OZ>(F^aq4-wI3NLww#Np5w)umC~87hM#Y9cO;hWfUKdGGQg0>DoXs= z$i_;=RGmyCr8!!6)$L}jWZO%xWo5Ej4b_Yun#uZY+s%GQ1)}QuZmr^fC*jhM2;SUX z7I+Qs+3n_&2P8uzh?{{6g$^IdtP@TINXbxmgP{ z$Xf&u04#SL7473x!{MD5TFy&OwzKbdt-PDE{OU7m@ljr{@9D4U+^MhWx;3O;XM{X) z;z%vvn6!%%gQwY_^_ZI8Sr%V%cQbat&pSRK@ui1^ph^5)DzngmEO9pWd8uV?ADD_bre*RZEtqG?bpj& zcCg#Oh+Yc2y0p}7b-xx1nM9J9tnZfgz)EqnvMb^+%1Hw_7&*@-r<=tW`jk&^<7^tsC3BYn9sl+Wl=*=U#KQ zIVoFqm-PPt4?|l;@SlS89Yr<&0EfCIot@#b4R2+BVTxx2fhL&U5u| z5T}OblU(?tsxFXza=&KOLrF7|i5 zDbF7wC;;uxOmwzh9@TW_w72lI5$o1TZZ2*vr)jQHq})kZo>>w(HnArkFxCYF`8{ z)X2#pu)Ay1!Z%h9r5L+P-4f{5nl9S)Z`6pXR+XwPdfU<2Tky7u&d&DNL&rWb@D{qZ z8U~7D)b%NDq}4Tx%f~9H84&qCe(=%&LX5Lxsw(Iy^E((H`TjuZrbR!==4_D%C+S#X7zU6+S_H zRn=Yhntq#mY!G;>d$qB+nhP5wyYdtL{IS#?{f zATr53u6|Vi0G3Xf`A^EA92ey9Yu?MSPZ?QKhLV1F(@SXDx2D_m)%g|cI&!p?mi~6{ zqTg-4d}AJg+cOa&0{}>h)ij&i6iZImA=Uvg(Q-6m?p* z?R!1--rw*wJ(4RpV^v6_EK33d1}n#Lo}H@1x@nde<}np!`G=HB=i8B=$C~=wQ&U!# zQ}c`@9A$X)`~LtVnDGaJH2az1)h#WBwD4h}kq{SGz(2xso(H#ITI+lns7Z4NlY2V6 z@SHJGoz359^gVIgk9sVjd4I*r-Et^klET7iA%Vk5x=w?P zlgaZFq1t&JK?OlSEqK?%7QgV3rTlVAuu5fULpqrh?LEoHK*`TeanD2fKNVskvzSqw zQf+VFN3YBL&)&Er2O8Wm=LtDQ&0ThB?dQGr=$k#;z++7C=YvJe5?@=#aO`DRu)-A) zfs7z6)RT~Lg(r?P$NWsy>?|yxvVwB|0Bg8121{bEv_=5jINO4F+y;AB$m8(o(WNzK zt9N=WZ-47|>$mEdEJLL_^!Z#pHF|g6>(6E7*Uhwh8Lj3o3eWbQs!MHF2Oy3|Ju%Ov zdv}2(x|=}OwCjyHL4=LWfTNaP1{ZNH!5o3_p4FyZT7^pTjO?V-SGP-ke|DEV`~@1= zN)eK~r_UE}?_d7_Nz?M^W9kBDktUTsLxd;@z#l=-^I6vMc{h*bS{E$lP5VG4hYATj zPdt4O;qjPy(uH|BOOpQpcA9FvcJn_;$5W?Pl9F7?KYz=v+V8H1d8cWn=T2Cfz)u;3 ziKAm0uu|cM;0N&Fag2+)1t@V1lD}6=q#I~8>jS}Ju zMYlg@iYWZn-XwjXj0Gg%6Wiag71l{;Z&XU#8w6%X-dLaZMn5k8oon~D(u^k??7s!K z`T8Hqb=00Fr8!wHX8QO3t<;j%#@$eR>@r8=*Xz=i*+%tI_qih+d-{Kz z*F_mg%Tt!TVxjJkx~swF$8xBH<`@}M`u@JgxUUj;l{A+7CB3}YS5mLY6FyicINWo9 z20Q!LrS*wZgXLPDHC!sIG@H=j{{XOceP%?|_3Oe{cyRz-k>_?m+yULd#xMnR5%@~m zRgosTu(x#pDh9Vf$FB+j>U#9AI}esi7cXmH-sZOZe7~!|OC9)(WH8Y7G_>W~+m|i; z8{zm%`4FniSji*ug?)kP>-pC^;@=7BcJ|LCmiEkW#Y0AUegiWhuIzT`z8^%QSMNGQ=69Vs@!42rb43QUL=sr)?In zk=trhrS<%cZ{&TQ;+`-f+CwmwR{2zs&eAtvbDk^nOjK7pidt*4w$E?B<=p)Sl}MEvK|x^D_;chO#5cv9xpRFT@|#dWN1PzslYpXNr+-ZzYnoedhqJ|y_F z{hyj4S)dao+J{p$aRt8JW6D-!ZOs5SZ#1&&Ka0rn}$r%T=aMGn#rAJbPpDdN#uJzjY zy}u6kHK|q{iPVdIA9G4y9BV!rcavYU)a}`zc8g7oW4aNjTwq5iOrc}QP~At&NCvd0 ze}sCchcy2H5z4P8mA^F39%+V|g0 zyzlZdRMl!e>)ZYt`e#F-YrYlGWRFd=xbZ}?d8;9}wU+$C6yPcH-2_XX4^R$x=CmeD zePZ_SQPHnwjnd~g_Uiyx4WzavWth2p#rYB$=l3@+v*LeQ09xf#ijg&bsNt6Ey=dRDI`#--v5 zyNl~sV#U0dDR7r6a7xA`nHkR9V2KVof^mw*N-?JBMO{6wb!C2yr}Gq>lZ@|f{&w`+ z^*Zei_QS*%Evi`Bc#}v{q6w$CUpPN)r2^b>j+>u6f~L7Y7HYaahQ{(s-y7>!ma6c> zDp)i^1R#yknFJyu$mMcC9AKVv!_Kjlt-9#DS!(|P1^F6c7qg0-CYHT_;Qs)_ zm{vYG@%FucZKrr!z*gEVf~qvvvs=v)q=nRxBL%oXUugcl~0G5lu`?=j%QpT#%ROrnp?Ax`Ls`h%> zr?%;?sok%ka8;oFrR@IzEj#)CYW>Y!H{%|WB+IAj9u(5P#VSU14KfpPmB7P+Z8(xO zkw?rLJ*O%OCp_!T;;#+sE{|#A9UoP;S%fx_YC2uaS9)r%%#9R^7FSK(QBd``)AmA5jKWRjG2w^?iQZ_#x7&htXkF05{UwC{D-vulJ^ zK)Qtby|kHZg$6c`NP#^80~zITD(unxO1joW`Yw_7jS4AUCtWr{G8ZURx${Jdqjyyd znCGD5Rm@x_+@&?IdvCSBt(n$ed`^aBEH*hi=wpm}Z!BqB?;|V!!rm5d$qJCPh)h?NPNk@{KX|4YNF3#QiYOmby zJTiU;U5_i_{+Nw5vbhGy<%wfP0Fc5*18E14q_NwB(yrh5e@gI0gje1eo;^v8yzhyjpY32*m#HPGr>tf*Skm6Lk){$`WYvTa@8Rk6!?L*A6V-R#}f z((R?*y_)WE@OVPcU)SyL=eO|x0Ee_2Q!V|=O+4C`q8>%TE@dA-$`!W)>Io$0it2TH z9R~i@yhUfINvP=d3byb~bvh*1GAn(=P=+*!e5!F8vE7V%_Ts3*gdtJ1&UbCp&{Pp^xRp z3+Jq5SQ?Hl5Ka=B)!Vzfce1|vE9rgjzP0L8UgNr2dTrBnzmi+D^mp_x2z);A1;yp> zi2QHx?@GD4y+3JmyLjwnnof5zM8HTCa6UkX3OOX2eddGU)YqdIT1SShrgsrE78dU_ zk`$ep5x&!w+F4noY?jJ^arAh6B}G@Eze0q^~8veHYyH{5mbQ zzDA)d=e4vT?}HCio=`9yz%G0EC(BMeG*R z#RM`*DQ33|l8B^?pcy=L3^yMCCi+La|%3Z!0*U+_HIRG~twsYz;`zYO(``ZU!!Z{&75Ql!W1 z(zaNTz!v$Jf#1Iv>+M#jwRmC{>YqF0Ai{)UoE(Fbj+p>)fsEIVs{Z$ty*ECA(r%YJ zTAo|+iB`|Ul3K$AaokMdA#&_+xFm(_dJsVD{@Aaa76!c5Bej-EPs|oV6-r@)0AD@2 zj11?~9M|MrX^E%(w+5c74d3S4{B85mpV7V*Vd_VPq^0(%wQV0nzfbbq_G_3D!$r1T zF{ZOy7zL&y+xzEj%5bQegJo7OJ-_UX6Z<-X_X6x6C=RFbpV`u;yJ zk-w!}we`G!wYoOVvb2Pj3!a-u=L6Zk?laAKzr+nWbt7-8l!D$%DNHg*?pU(8IosTY zU^oN#hpm0>DXNYSpPNUsY3Q%2e{x?v-OtZ+93r5q&8HhU?zCF{m#wzF{{YI%=}(8? zPvHF$-7X|$ioziyw!o;n7a>^W^MTOxuG-0!U=c*Fk*W|k09yyR$6WeX^cs1TP76SpqH(&c`F@ zM_%Ll`c+15oG;wX!`jKG(BnK);yECYT4}bD%6hrM%=cy2RnCe{ph zQ#)=l8&pXcjFFbw3C4Pi4?$hjVC%^#ZR!1gS3G<~{hXVLdM!5UJA}864UmDCSuzRE z0T>5A&a}~4oJDG=rE*FT6poya!2N6JY0`uut+DgdtyWi3->3EcGb35l?6mYUH05N; z+`euJBd0kZr>1$YEb)Jc{70y?XTOkPDb$y>#6NW&SAVDL7W#?MuhZ-S0daQ~@0Qa^kGiSR)aN+h_S{8wo*f<{ z@YBm@;tfVgqF_=BTd5~2ByZHku#*`9h|2o&Uk^vx##gAedhcy^cK*N5?W$CzDA_-Y zZ4!MiuaP`{67asSd`*Rw%vW~NdGbSZd@p12#&$KNgLjq*2X_8JJbTo+(Ph2AeN)3X zTE?GpkqK_#y}X9%%HkF!N(V&*uwX{Qq=GSkd9O1YMw}z@pQfiox=BWpBr<#CTPG&#;l2BYvtiabl; zh+5{?;q-cr^6`Jfwm4egCgaHpa@oscF#(cJSROeegv3gMijq&OR)2f90>DT)I06QL^;jKr+o+`bb+Sgn&X_Jl7#FO5c;sr8Mpbo6KKf}*X3FjBCej94q z65HHq`eB9MRl7+UuXLia?b^qDZs@rKkl+^D19laKN_6FSIc?tC?X|CRd8#Iyb?@8! znlg2Jrby>lbz9vk?%Dp)Kb5FJ=_{!NG41mS1pL75L6ONE3ZWm0hPRsw{SMPh)a@V_ z2UbX|q?EWDu_+M}tV!xN0CSeFInjK|YT9&G_pjw|pZqzcI?5@*E&YEps!tE;dacT9 z*M0)<<^8SF2=6Z?lFoQSj!QJcT(fbFy9YnSaZ_GszYcHKD=UqCVzyLeg4W8~Wr389 zz@nyCBOOq3LG+?>hdP}~eAevjyKS}Yr}c20Wf*%tYcIcF>-w=u(?h&EoN1+Kx`oNN zoe`JqQoxLW?Gg>fD9GoKs@!eKCc7E#_4^nfN!Bf`tgYQ;XN_6oXE?(&k0;7O=L)XJ z7{K7;pBSTvm&3}HyKAq0ujTh{Okq(|ag*l1U+eny*zwO1TKG3pz0-8qdp%o*GSc}=X@ZA^$O=!VLVS|_VKu>GFwTsY#16UG zKm**;sY}_Vg{3Vt(Q>5xlwJP-@>@01&qXR%le|^ee!iE}XSKgl9V#D+J}!pL>w4wy ziDHg&?R{yj*sN;1Hg0B$K*XTuU5xHh0frB$s~B35~p#+y)QK zgpT5}d{g1eZEsVw*1RL(L#oLtlRw)oEv2+(+w!RlV^&P#B}pn2hZ*70SuwzssD#O_z+jZzrmhHgL%OpG(T1P)KM zs!A|eiAlTcn(Fkun^E7(PS;lsZdTGtD*Z3>ch&2@iM=;nZfJI%CwON*4Dhdoye9+- zvOckApg|4O3=+rAGq_Q=_<&>A9E#{Q-3!8+eu|gcj<>98vD#a@EShuNSQe1382Qsi zyT%4SX`EvpE-)+8!qSC0igjC*<-OhGeLCrN*;`bvuTDDEop0e<%dYR%&s(j!+tuAv zZ9Xkm!j|`%7lLne>sjYmL9qSx+|AHA+bA<_B}U`7JRCO|^8WxF%dJ>n+}KT{YF2G= zG!uDt)?QqRATGp8?QrFJ13a#Ff-!?#7kwb~vgUX-IkXK8=4o!O;<)n>CtwKy517w0f(CJg2X{Sl>|e7KnTuD` zVvZOBymu_iZ{$YhxFJ(<3;%Q~Y;7qkJo= z{{R@mloS3Wy7_76WqbYSr}(PiK{d{wV->(i-W5q*TXVE(s#LCV)HyjFao)VH{uq48 zUj8#9N0!OtAD5QKc=WH5&nFd$RN)G8V)|S1Mmfb(#m2|~Z za>&sna)KF@x%pS17|wXderwY7Yqzn}To<>IZUUKBWr*@JqZ|3pJmVFB7|D)e zzab33?%GKWo}KyYRD5%0@OXYe@F6RG337;dC64!C-3dER26ObU&@hzaDRatqz3+Y2 zj^8`0U#i!k`Tl!eairr2J+!x8j{R(ws@-(zdmqESLJdd5+GAPCm{QpnGJ>GtK-vdG zzym$G$9nD}oFW$xBTKuIpzSA)21g)g{{Yut&`uHdG}JU)tM0MWFVFWNqlDnkMrNPQt<`qMG1l+M-{s5vD3(TC73SzhTZalNjUcy9Ay4IYeqzpDHYc$KIz~v$KV0{E8W0SN(oD;^ElaZ zO7Uf8LkW`QMDnWqp|<249zW00u)I;PN2FOaj{aC-mUbO8+@9UK*RN8dg*Pp%c@*eM ztysZpclw@nrD>YaiM3~adMT~p60DI#k}lacwl`!30CGJ$dRKX=cv;L*T#IFd#tNxO zQw`4_#6iF;M;&YBRvvh@Db>-vyq4<6)?+JE!^Kmh@W)L$_rJ{X4~qU9g40+R>#4kI z6^Qbbt1fUDl`G$#c|4D$RkZOP{{V-rQrlA2q18s;CddPIG_a>q9#I;HLO{xq$Iagr z^OfoSMx{te-|t^7y$@dpSL<{jn%~pH3n$vJ(VyA{Alx%Ev0m z2hKq(r)~!3z~bkLyl1F*K1)3wD_th>UQ-nD$)?5;;^R40^9zl!OxmnxOo>GJQ@>TPM(eigJ+s5ge~E>_|pCB><@7dmvxK*I&eXxT>5 zhE6t-fH7Si&Y9txyD0S!hZiGBXp!O(dDl^_P1j>CpE*S-B$ z_3{YDQIkt`_jdHZ^>YJ9_;KTXcUC&QdghXD;$JFD-49Wc+1VUrmTPo_%aE}wPs%gv z-nv_K*E}QkfvM{{d+EQs^DVB-cGqx#SZ!G2kyQyiDP=pi0C~-Lv5hZjf3>$q_xf#p z?0Pel+${Bv-0jl2Y0_x78leJ9fa!gve4&T~?E&yJ>5w?!3gxSaieBWSzvJ`K`5{LRsm{$m#Od^H zE5#PZX|6nKbjhX%5J4cEMxz}0vj*Rg4`YFxcQu!--00eZT?Inje#dLD`XHmAZx03$PRn;y-Bx^O5<;9%K8vg(rPaMVqcV{R$AY;%D z9Bq1(WTh>hw@Yur&&hAEW3CDE>c3C;f4K555%{mdjjx>(MYGa%53;+5k5asn;TCWS zb1aV_C`K?yDn4ugdRJB98|$#kCxW!NG|fKY#BxcaczKdI*c^Z+nolkAGCal%26DN@ zWr}{*lcNP@*2(DYt-c<+yK8N?(NKh_M)Fr**H6&G@zt~I*Pmt9^$DW6^P*I;o+&0I zu-eSdW01{|IBuPR>0W26>wX1Ia@)g}Fxg&T*{QX6)T|}4iWdq=0g_le)?!G^ii&Z; zVr)TB8nrYwD(_I1;ROI6o-TB+^Gj*R3_(~l&{t>Iac33qlec~&aXOW?I z54*~m7G2ou)RH;eqrXi*g1lGadrd#aRu|d?lUu|*zwFx>;f`DZ{<-2|fTufHp};4e zO?N7Cp-0<0TejC-+OxZk{{V&7$FIzklq8#$X^*C~D{n8|#P4q~ zjj~B3vXFN4HRjf#41Fg{5h%)v)k|B)RqP?n$yGgs`~eZtgaoVmLsmi z1SvZq9JG>K{Dt^D;ePKVV<&0Ub(gTCc_gf*%G#3b{mxhO*85)i^Ed4uJ4!xR)p=;u z{{Syey4v@HEOk9v=U=uH- zwF#|m1-efxqWa3-Lc}5*$nKveav1{vIpFifg@cs&8s&SZ%Wu(J=9jB>G^qLD$G1AOatmsYO-kWB87(AP1E%2RGMW|@}PH-_#F-qg*Y8*9~v)=wJWde zjWoxkTfqsLMfRUP&Gh?0!F5>trHto4DFomg1Ul`x3jm9j0IFO2QhJ+Z`eLw zoRdpw@k>;H8R_~()sKd*B#5kEZJPMsIbg&Dca2|TWrluTy?I^@dy17VYeo+7S6j>c zlIzu9qkEj3zU-qpD{Hd1;@#ifr){t3&!XxQ!6v77tZCQsq|D13TisiTSagYYyX}vs zI|gx+UT>&qH9cuppCTA_H85^r z!WgzG3$Se2--0pDU4J%}rbcJeyf+rFU^eWw@coUotbuZH!dc}r22%e3!boiWO??G8 z(sb+t+RSKHW}8%5G^|%ca%rroQUa)6;jc!g%|_ntrEfzA3iS6wcBJyp2Op z`)u)m$_kSs%0VHy2p0r%z|D1^1c1=ISrk*MM7pK4uq;qAfDB|X`9L_xZaEmi-uKEbVekzCH5^V2x4vd-lqwT+?>`Ai5OIbpQtpy!N%$Gv%Ym|o2GuysAwj}!Rt z*AZ!UllwfvpeL?5t8NfY- zeksM=)id5{{goSO=HL7i`isKKF{Q&0alNGHegG@je+(vlG>DP+*{CBd&W2G6pC3kyY zqP6YP>%UX<%Jr&XuyBkl+qLz!?{)XDyRjaXWi9I~-`aV|PX7Ru{LFde;N<-?U1i~k zEk&iJjEW}VqkET`odz~dwyPZ;WJ?r_sy$`vKET0i@C+j(ns^Xsq5=2Vie%Sr1Otaa+|*X3(; z(DfgO7Srk86Vh$sSb#R@%*ccsxC}_i=abLZwRW~^GtMQs3ga7Ba3CK*G1Kzv(!Zf8 zMi9bNG)PSJE=Ap&Q}z+5L<+1K-eHZ+d3I~{h5qZPMBxPn;`KwznG;Q#{wVBQu9 zmP^;eW9AHGIbLu}#h+d}`MBxVm1i0$E32(9wYuMLmghw@siir|yEeD-^G7>*s_DzC z>DpzEr=wn58Qeu{b)coNw|4om9TcmnBb*EzazPoc&8&Posn|g+g{F*`aTYTDp4i<) z>727E5x1BJP@HtZ#d-A`oFf^oUaf7@{QLdJ@Vib?Z`XhFu`RBox@Mm%cyCGY#nsz_ zZX^vok!a5wqmAQozb{n;kGsef&)T#a$ePW3eWz=w5|;Z8vply-qdzksC2@>x7{c?{ zlU(%bDiD=c-!=BVt-8_MwYnQkMp99a!~Iy#*7Z$0!IK?GX-T0n6C%l{X%V~=J^&6j zNMAhl$S2T@)^+}&4~_2aV%I!pdugWL9n%=}``G7l6!8B5Z@Aba%K@0d2dKpAPL;R`6GbA-bA!lHJX%XyWPy zjWe{YN?llT8w(&j1JqQr-VYE-rd?~7x<0XfciKiQZe+KR6Tnoqjfvg2rbq-2yXn;& zJxpyEiS~)5_gm5adU_bT%}6m^b_{C%42fOgE{2*GRTwFSt$-KFdu0TBQ z3*?m;2nwiBbA~KB^LJWCg?FagH^c7*Ailhnu4ab&QL2VfJb?*1@O2MlUCXYnV)$=K*N_m=v0n#{M-S-f(x1{mBI_r6o8$T(r_7v>e| z(!yR5p(v=uEu^fT_Sb8F+t<;nJuU2eW$ivKe3g>v>aFtiX8hN>ptU|F@Sllob=#dr zP;OcDW=W(t3aKiy`9P194VcegdWJ0mSfIDpFFY>xmdh|}+gmLf?#k&{k-4L}nidE# z&+i;B1P}=(y!8rnCZ$W!#nJ>;Zz(*Kb_hUom2f*@dvTF?!g;hUH&)fW68Bn+ zu(GYpmr`1itfk&Sl1S0Z>Pc4|jt?2b3rbMBs^JHFCl`G_O}(~ujkR`NCQ^*zr0(y3 zC(&zkzDrM3c0UjGD6Sq&GsHg_d@+9%i6@g5sj9l##9NdO7D!S>3-avqfqm2+S$lP9Cqg=d?fI=iBh7JV=wMGB)jaa z*1Nr)tkRuXPM8bf z`6xwGlC$Pf)uq{K*K2&6XvtP|*R-6!?c4q>tL(4Y?wYo$PZfA#&qmW>gTnXT0?;(1 zo#%Dcpj*a}^(u%^O*39Fp7}QO;>C(@Cl27mZw7XVA*?d7amL59z zkW)!~6KAIBivmr!22$5TJakja7U+I%!xP1NUxPH8Z97N!e`YmNX306biYsXBSp35m z63EQ+5D)QTah?dsuWp52S*lbUTi#9lo!Z;WW0#YeH#WIdv|8T%wblL##?OkS@Wzp( zTI*N3?wPD>7IyL}78mhJ94^Bol?>*}_iB`mNus_1j$=GL$dx)sCrN+ADqCJ8Acm z=pGo5>Ne3!smZNc>A$@@Cu13#YLg*&LZc`Qfl8eGt(@lr(yx3u9-V!m>-OxPZ-}>x)mT8Nct?aI>(^j>*cGs)# z`ks+#YaO|15=q(Hi9U7#h#h$t^#1@nR_&eS3jShT$fcBTc?bmdt8{QPNKb! zi@`}kcD|+kPCHrceCCKui~uAt1qWgZ_8y|SJvkRk*KS~7u|=pin!Z>Hp~eAFah`A+ z+~n7dLTx@)dzGoiQEhtv0A7b&bolQg5(dH%g~0@q$pf#~`cgzEj2P}gFTmf90RxT? z9>14*Q<|D_d!pk>(`svH{eNHPJ{ctn48^4^OGL#>C-=0m-XA$B_QelDsyWd(RizH_Y(~6a@%b2{^$yKPcntTqlCejiiA}MLW;LN+pAL-UPCd>BbL3>s*Z2mq${T(e30SRbZ_yNC;avQ-Oj{p%wA@ zl-%mLEgI|Ot);zmeI1X|eyvV)V+xAt`SrVZz5ajIj*Cj2qe()lEUhasbl`E{2i*R? z)wOx5Fazw1Ak2R-AzLfJ+}`~4f81wTFOmI*5SM*LcUdEJT9*G~rwC{+< zRH-f8oBP$LT>{jD!g@KTTT%vb1CYzxceG_%{L3)qu0yNt&ZmFRq+LsGp?)Shqjgo%=XW#X)4ywh2}wYpp?hC z1ZS2x6_w#TJ%3zAgH*8a?})VBNVs%sriNcEk_#aW`~L1n&I!*UYs#r=(VCL%`oFvH z{TbH@UzYm%ck}+f^7437!~PzI>eMCnj|46rNLm}2p)Ra&$s`0$c*rMl9Xj)z?RLuV zO_BAV5BSnJV+65&cMF`*#~Uf*d{M*uw$9^%6dZP{x1JZ(^#piznRRRV zq(&BZx@EPlQapfNLn5>eySUrH3^S4mJX7SVuT8gSZrgmXzu(a7x3iLV>HT#%`%ejY zuGd$%e+tQ_-CaoIdGS4)$v?}I42+N}sXTMI_vfZHb*&pz)};|%cz45^RpLe^p65v# zgYte->WBif58)e$BzCVq7M(ik)79GQ&)4O@pUA#=RHu1IUYh*8*_m@6{3G`e4H@OW z)b3cATT#D~+F0C=zR|`IM5F*edg;`CDQxubiIeHqvs^>s3srwJ%eJu8TTxYfV6!sG zB!m(CCPe^_q*o(3dki^CoV)qH1RHjSohHGFY`RDHZDdpT;>scFBQdfRW%gyUr{U+TtT@THf-9exP3__Xu(e>2I`?(J;# z8U8?5&YED6lu%AKf>?&Y1A;lv68u@xqSq}n?-zJaOL%Xj*k-l1yM>{Q{n;aV?h2p> z2ODqzrOfBeO0;c0k5#7oJMY;UMw7%zS!-vn_1pTf#&}mqyIo5E07Tb(MXf_Eq6>iy zwfkGPa!=ktC~!jOa8CSk4O7%+w7I-r5I(BcD`y~*Bd<#KIt*|U|R<-V5E{{XL^=8uPbX+4GY--uiLA5zv?LaajV zZY`&We+Oug5r9C(20Sr%q`H2q;%^i9k~uu$Z*=QLw>I%{g$NvvFLxhx zq&)MEF~tflmL*~wFQZ92#U-Vkxm&u`b-&L}g;G$a;R!gk-?rXg<t}XnUU&<@mKTOCA4k;=xfP+BZA5s^JwD*Ld~6Ep+nXzr6amLxl{bWZMe!!e*8al( z0KzujIn!_M5!CBigWRl2rvq%hNLN#UHz~$(>swTZ*RbwWlwj7*F`eV(ccb#M`R;Q{ z)b6WY`tqmvS-(AgOzSQMk%s%j_j;#>JU^-2!@5l;PlEDfW>8loNYU>KPCyJ)9Aq2= zSzZzNc__KEwU5PCx`?ow?Jzc__M1|~mfT(wFU-RP?^VZb-Oe~1Jv=oRIDaFwaUN9NxCk9Vu<**9w*v#jb`e!s2R*y&ywlK0B9XM6iu?i{1w zV`E2!kagjXFmb!Ccw0XR>q)6kuXwuJ-%hxKfAmQ0Y@=&~7DzI*P=@jd;FcdT-Tt!! zXzHe$$>OTe*NYKc3DOOh;sRVj32cJ&W z`rZaIo?T5X?EZVMz0b{anzE&v-frsa@w40des?;54&NP5MYO)1+{JNk8#xN4GDkam z^~lfDt#o#NTu&H|5)>R{DJPM^>&I@@z9LR^(@#r&hlz(#g;v_@`7=QQxq)ACBp;i} zV~ii-$2|TO&1+gM;J8U`)G|dOl`yNj1C6SCa&kfaE5}mgoxiV{?s7Vjzjggs=rpNg zxQ<3pRx$`?eoEwL7#;aPl`X>-k=7yRN3?9(*)G3a_2Z|~o~~}?J4TvI`b1_)vhszDseD zz!>(fR@+cjmtX*tY^f}B*F0qN(!W2m(>+owi! z9vzXct~{iOyv15XjyQvFV}Z{jkMrwVCc;=!;@PfP;C;k$s&F!MkGwsHTz3M#pDDpg zr5MgnmzLg5-pb4F*VN$5F;I<3QHs0!?dI3tZ$k$16oK|AMBK#+fXl~olaBQaqRpI- zB$p~eg_DimypOx>)Z?vu&O4P>latkVU2o>D^z-U^^r1CQKF_!Hv9IC#gKHb7n$9F* zi~{e-#&eAJ=a4F27HSP1g(6LPBHJvnLa5|68>t&kPdUa(2L`^!Cao&Cct$U}+q&2D zx$;@o8C0t-WoNznKf>C7O!t2Q!S!j z!2bY0t$#pfv%IXlkK!y9Hwnv|yE(01^|d?Yu!#?s0RuSxK6`(h`%ok>;wM5tO~5e= zv~knkx-j(lDaIc&lMz?iPE)p<6cuK_nWdQ*$~nT6`J3DfR9cM2*3`x$`CIM-9#pqc zk4*b|SE}TrB?R{KJXV{Fn_KyGIlBurlJHF`x0>Yc{oo(~e(yfm?_DZOYYatWP{*7W zW;i30(zjgGo|_mo3RLV+n$F%^gQz)WkN}{76ak*u{&kyj(W%UHqQ(Q{yX325Bpy0` zHR{4nQP-j1VkxBBTfggLh`sRDwyl2JrP2u8sfzv?<9O=_-#anGR{=cs>=NTx)^IyCEwEnlbZ$r`{xp;Mr3thInv4?N^CcAJg zq=9g9fzg92oRPaHpuom+(cdMZu{w^Q;N4XbLWGM+)M1y+Jy&UMt zN=i;D$$ih{zu>NieFWtep8fly9__q8B1vM}KEG#gc1m1Hb19x{R|6pb02H|&DFIu8 ze+tX+o{g$_fxoi!-xYsrU0F&BL49os$Q&;riG>?!9oz%&Tyw(09Mxj1@2;&|y5IWp zHKST>az)?euj%@lH~tmzeu!t)S4gwd-ZcT8uJVqg0N=ZmY|ma1&UW&83d`1Ye-vJ5 zscolfacXQ)VJT!(pmC%=wF?qjHX4PBuwv%{gPVgJ4CDC09CPa~u`hviN4dYWx6~}9mEnr+3m>*x2+E(8 zw!m2qGIAM+IPYAziPli|uiaXG{WY@wnWrr|PnMSd0H>js;cNXO`ctCmekF^=aF~gT z-p75xL6NY}v3MZy^Zdkvo`lyK@j@Fo^>&|C(_y}n%&3+xwIre}0ydqwB{a)2mLWymJ;FAJe>9pvf+e;Y(W=m7|#H_xF)SYb1-w+Z>XsKOBNl zM?5jA7M?A&_{O4eWEqShyf!Qqk?n9mWqG6xOAV zx2bBnoR;=~3$Elqh}RR#d2un=tHC}~1Yv+aYCwv6WwTNyj~MJ69_|jr<>{ zUQg%hT8686Jb{DliYq}fjDRCT42p1a$3O1$#bEF?VLxjq+EU&2{Nr}Kth(GM2&g(r zS6yxSY_D#u+si}J{0pb2ihMkp?eD}5LNla9lD>R7_M2!SKRy(!F_n*zoun@r_pag( zi7JT{`mV2_-&hi3hE{~ZJp2wKg}lZMxp9J^9zJ7S*!pqBQ)(Q^r)}dcTl15BZuL3o zrm9{^d0P4;uhX}e%KJPibuWniID-3L@c#gWG&@}(Nw$IwdBhEH6a(`il~94kM>ziJ zIjju>#@;Ia+r6`&UD4;gwQ~$`Y8MMUmh%muExdS*RXHph%RhI9BQ#T?L)r3P{Fh$p za<``{Np^jGI@Fw`oT8grZqmNKcXrcWn=7r2nDx8sKNAa|A9%vYO=+cDi7d{ICA^oa z0Zq*^<)&PKM(pK6oOBi1w}|JrwK4c_O*hLt%@Ado;kfe%ETkD>j4JKwu_->M6^(p6 zs#As%o0qfE-cr(5zgKIf{cN<;QdFZk`)Q=Smc8!ncK-k+efty5e5fESGcIl!D3_0)vg4HWH%) z19`_*&M~W$Fg2r6O+JeEw)$IEuKjgdrPRr%RZ0+A>+1giUHqQbZ5e(X@lSxvSGK+h zTdVu4Xhg57>Jteg5}p8r$&g>2n`2aC&JGQE_OYydRMfAcw_O+eR>s;^lG{&Pp*AIj zaU&RQ+i^hI&hS$|c(!p~^d{$9l4&d6$tBnB^G^Q&Jx+gP$lY3xRn=d2+oH9)TgzSZ zY;CRlOQBvxCxmTaxwv*~iT?nyX7U-)Nh=SO%@Z;PW0Jo9qPbITrT8hW7yc4GJj(>C zh?<0Jcd^O9D&gEAQJfW0I3WDMgXz(&I8;j8ZMF3D`Cj&YJjuM=r3<%v>2~zjO;(+B z>uq};-S9t6yVSKLeM0hEqLA-NS~$i6$UwnF0QF)Ip~Za(s%f_O8dTQots)dV%O*(r zf$!~Kt>Gf6VCk*xf5rLvpO$BJIr9mqyICt+rkC|NuZL}NkY4B$#-?2=@!(%E3xN|2 z=v0hjhaXH=cVRM!O}S*5K@r9Z5IXiFuTSx{{TDcXxUHY z&9XT-V}iSIagLZh3HLvhRo1~xu9NKA#iUgvf;r%?Z>Y&1&&ZuN+v60f`4lGV5(E$Ogv)$0Gs~+N`9q(8Qf{@4V3oLsylCK1Z6^P1$Ko{2H)by zHOVycJMM-Ogq#jfPQ%u|7d4eBM$7VA`5&g>69XETP8->|F8=kr zwEn#NBj>X?dkWI3lU+U3-_O+M@1x%&%wb|wv33kt1Dxa);DP;3WI1IjRhWQw@HUcj z`TBLQlgG-clTB-{%{Q;(r=j#%K3T%gZ_DNWW$h+MYsjHsgl`fRZM_C^IUl7n#J^@X zMp#QQmEe)uP1{jA9=OTfj>oTB_jq}!LMm@t>GI$6Jlx?*4sJHHj<@sL*S_{XmheTi zNut|EH^xi}kfUngsL!c6$o%W7)^!!qG|C(TYaglYa#vR%G6;5iD zYE*uIna}B}){%+)&|SAaS%~EIsOA#SBE=MEs)i&SWcRN|no3T49z90oO+$8DYjbW) zWqEP55TG2Aamo4`=Wk>;SMb|ODCc+-GObOiD3@$3yp;XvHxu;_ zzaS2IqHK?mq{eN2?N380aCZNr2CB!;&>67Bp#K^GWHs|D!3>M0Rha;wWHR)a(v+;~NCjA%0 z7CPRCa}Su&PO)tysBMxtA){_GGTGcSn*7ntO*p}&+x)lwx}SM2XhtpSwfuVDUj0mH zPl_kiu3)jX)NQ8oVQYnw7K!X73J0AO!Ag{1Fnr8z#|^Y@uVC=bvEuvP5?lRZ=TFov zjAeYSY8b8BX!h{Sa}2Kxi^n{ky^cWAQ>Q5N!dms~yT4EB$5l8rP4lGJ-TitQ5bBz} z&xu4fx_*nMY9UZXYWJd5*cUrh5gb8RNB)VwkQD z9yt|>RsfT<#(go4YbyTEi%D7SeSYmU^ZSUR0VuT zIX+4H`9D!2bY&*YZ0Uyg#R#IQ2_SPf1;oxLB^BH+qWB0ReXT zgsC9s<=NM#dh_i__?itpq1Ci`^($XEJXcFRHd00vhGIzF7@Uvcbveg8jMo-hR}n60 zM*3)+yuVJ1Yv^}k6eTsy>t%mkjqN_q;tl1kwV3fOz0QGi1`d^~PO@Am&)g+MTR6rt zN7A^>MEGmM*8=BN*6lR4no|(dkR4GKR1$&OM`a2+<7vlYMOD<}FJ`^#>m4nA_p-N^ zy$On!I*MEVKk(m)wQr_)Pg3yY+UB?7JN-XRFmATFwz-ZgTZbG1maxcJxA5Z_$E9$3 zhL`Z(3x!W?X=4T~R zGjX<`kDvS<{^OO=HT?@u)!fD5xZg=g<43r=wi3v(4)wSJP z=06E|j{4$1FUXQ8^$V09Ru9V2G1<2qVBnHFV!7+W3ZvHXUHWUjxBmb;n8`{nnY*iN zv;Mz9EbjbIY2pjLTfw(&E}s+Zxv`G!XyR;R3RSmY5xXIY#t6wc#*c_RVWrEa+jw_Q z(`-B&sW3aBy1u+=V%&1Bgf=ASBq3Goa^%HTE zah2@6((?2F05!Sh-XXP`YwMUUbyb?+{_xyG5J)ED83PJ4f!6~h9>Tg00eJR*1YO(M zYu+Efe=M^q{{Un`vv10|ic}tB=bny$9CO;e3bB?VpR(tS5*gkUkQX_}0UW94k=m15T6{q9 zRB_t;D!kPpwnUEN^Ta~tPdY+WJlk<1#s~z0*}y$W#d(lY=WZ{Rr0*xK@BFUmJ6Ym@-kq)2@Y~C;PdfUqgnUWh-DTtO#NHUSd897TX}WaN&1e*G7G$+9yl}@W zki>EiK830H-d_sEr$ci7Dw9yvl~y=3du=>Ra1U1_?29s}1RdP=SCqfqj0W86aU%%FxlfeV(x_4z>6t!X?P1%qrKJD=C!F=w34|b#w3hlOb_|y z2n1ksJa)Qjoq1JK*K69%HlB->SwA;zTGL%`lF(9weLCOo=&$O%cH^~A4cvI&Sc~DO zfbOBXhSQmD>@@I}a!)pz3tm}Zuav}`m(xObK<1b`6q98S7)bwom2eo zzRD{2g7d@LM7Is%d+k>5%C`k=Hz1NUiool3N z+9mheZq_)WTXQtZ7dT%ri6ur0V}3G78NoH`WolLNF;I<@cIe)=-^u#j_2^*^YdY0s zrLCpawDkNoOHI{}uRalJT858&(cNr~MY=}I1IDT5Zf)EkIL90ln)b^$%yGF(WhWUd z3YI4r&p+q$uiCLO<)WgW^>gwpOyg4@IVF9+FFwE1I0%HgPsBH6xSe6Vwmj><&F6VV$TtR zPd=U`hs{XY41l3kQn}+e$o~NK*Ns|kF5e^E!@)@@Z`6+3Fp(w6kwm-pot*QGbLrc+ zek*0zNoX9gR*38&jyDiG{{Z^^E6s%CeH;)I|VzWaeOiK?h{a7RBRwU<+I_KKIoVccyO8M<)O(xQebywBJG{0X%`**_m z!jB4JROkH9{{SX?_160sI-9zxZjpSwq#-y`Qzsc5{Cb>n8AB=*;5y|%-g?trM zm1#A$%hUcDYJQxbyA>}pr_*htxO57x?9q^l2~bW3agRZc^|xuE%`zKwL%1lBgpzF` zags?m1as?OW0&R1RMUdh-^+bIS5HIcarpSssV;YJUn}YQ>!+^9KBK4HK=MgwqD0%5 zCt8LNDdDR+Qt#7l+I)|1F0Bfb)T8C6U3=Jlh7L6EO z$Rdyc5Mv`f^NQU~)27qb@A~`>UR6@6anj5B{7AJs$t|6s0I|pMjE%>G*Qc?pVQQAM z;y4Zt#*v0g1~~*{^6OetZ6$7|Q?rwAp{o>e#}l+po4EOQ=KysW91PZ7)R}c`2LXv> z4co6y-TGIfg4MRqD=~brv`BB}hI!0v(ulU>X#)Trow5aT>oZ;I?ufFOZIj7aBP8c{ zEEnGx^~P(`sJUpUzazt?B`i{$Z`b|-yKix21W?4+uJb3$zm^9bGDtYDGx(9B+UjOl zrj{upkqOy4ZbHKZah2WQIrZyaZf{GU131q_{{YX_>cLfvG0>8C{=E(#OYmLRt8Z^E ziKfjoFcz6+vv{Nsup4qycxF5v7!%J^(zopVQK(sJ5ZY>&qQ)jG65rctaw|9_kg}|< zLi^n-Z{Mpv;+`S%a?025`aQn>`cLcJDJLZz}x1ZUc#fx@WB!S=+o@tuvPwqhg12T0o@OL1$u<)WK;{q@Xf%jW>D znPc-DWFFP#PU}e7KQGsBmYwc;cxkEr?ozVz{=d)2n*QQAHH&+TFBo`tUelH&WlQmP zgsP5kPEPJR8FIWF9+l~S62H|hh_lh2;Vt4~651IGybjWG+a_#m!2@s%M_g8Qp-&MQ z%A{ALZAp49#-%EAaHqDtnq`j?+-Mhx9DXvnl6jTdOGw6@CDe#>jQO#)(m4JcAE6kk zJ{P^#{7pBL;cM%ATPP$|NE&svKmgB}(4!Xw_xZEjgVM37N)x3jkmg@^>b$y}(Yz<4 zPrBFs8~W}|s%ct4)NWSh8|iKUNp3D}UP7SS3RVW;Z(a_J6Q1@ zn>Zn@!CW3XfO>!l$fE@+vV*5y&OL8s`DwYXCZuV#DsNt!_W6HW6m{PW zXnNhUc#~Y!n#%Gd3!7UjS?cb$xlWTqt)$b;-@gIma{cvsu8+}rE zE#P>_3y&=$a6K}G4?Sy+Rr&d&PB*o!Zkm5u?c{V*PH88r^S}9*u5|rk3m4S98E>Na zcG@xJqgz>N^4e_38)T3uV0s)jdU7*S%dWM)k1@T~@4R6xw7^buYY6Tjv)s7hB;6W< z6bkdbxgy`aqjzu8_tig7Ph6_CURuXyuKbTW)uQnZv8PQxfiJb0tS38U zv`h682jJkwp-gz^7#nlI;MX^z>%K7Xoz2dRr@R)?+-0s4F|?%PZXY8##|3_a2d!yI zs&H_fmsj_B-F@GwjCm@>({Wep=I{M~!(KCgbrgn``T({(5|l!XE@!+RyfRJTWGzac+#BSDaoJY?1!1 zPbq=P8?l80I6W)NHIEl~iM4%B%JWmW@O``vU~y*G3mc-47%V<}Z{r8$!i~o*$TjET zX#HZVc$<5_W!l~EqL#jDR=)1nH>Wi;`CaX6dj2c$zn0h2)4XxvyJ#c1lJCcN4H}Ry z+C`2waB$vSB)DK#11?DW-NtLZ)_hrK;y(?4XWHr)UKvG)_fYCrb~g!h6b>^pf%mcV zZNlXB7{jT8#3`z&MMXQ>E?2hw7VAsdEBuU`rsSV9a{mAimy_9Rt9R~a-f8{~)@&`N zxV+T-L$3g$JAFR>&dSyp&KGbN{$SvqWRo2Z4R4(l}tNcD&drN&{`tIcgxM?Gf*2c~lm5SiAwCwLLcqFG8!6&J& zHSuSFA@OdRX??EiTD|U{_J@o++nA%b3^GFbN>x-S`J4E+ZCn~yDz1z6mC~}d@^?+& zb!4ykdApg(xY^QL>u=9{>*uAP%@XSR7mF8KeFNd1vj>GdJz$ppcB6ZE!X-rj?S=$* zEO>0G2uUE42nMzFZ8yeIX-EDM-G5%yKeP)(br{@>iP#*jWMTJy@ewMJ0Nl(;#d?>F z=DA+F%ga}__w{tF`Quw4x+xF zB9p6%i;CT?E$7nr*X4h}%Nmrh@^jNi`EBykYbDpI_CLbCF)S~&ml4YveWeCOibi$< zM$kHZ-~O(Z>B#X)OY-x!d%q7?;>kaROcB* zUw`ZIv7oUOjBaC?@NlCzIr`xCt!r5)k~K-DK3?Lv#sE0U#d%n(N-h1zvxB^3mvyO5 z&^$LU1enBxgUH-ZX6cdmdsfAcnQYOtlJ%66g*XfJ&OzvUabA6Cx>CA5j64-sS(GM% zFz>Oj$is|h^`=NwppX`4l~tG_`9VE+JwfO3uB*95{{YwZsl=3HG`e5$Jmcc26W{1? z+uOk;o<{BRHZ~3djIr!bBOSWeA#(&4&SY5;QQ1$G7{QPc%9G9j2cAzg{Qbl#FE+%@ z*)_}S@TLC%1J(H-+a4ZC(&5Y@$vg zesvX-+D7m8=p~hWwphP=wNg$#ZigUqz{fc2U!G9*Qp7hsV|S(cZ~p)Tp4O16u(+i&we13AP-o+>kyMIF+;wQtLPJgxW`TK2!GOp9jG z+(l_@StE`3aHQ~rj&YC(9S1yDC4C|pcbS|Lz@RuJo}G_h%e8zaeO6ekM7g7DXuTEx z02}^i(q#Bbcsx3dJ3ZUCR`qYwQb=Q#3#kRv(!(Qz9I>)&`L|$#J9q6`UN5z{YfDQA zr;0;$a|%j)!paq7RaRa{I46%x>tXvnYt zBU?ocj5C)kPB2I${{TwQyK=LkM9B;lmA+Lcw;+3p@4=?ttn;%8B^#wF~WE8f)`TWnEFFa%8eKW+qW$ZKCT}y^3XA0(73X}5}anA$$#PT|U zU7vtHCEWO``HzfsMzpfIksuSa8yVMuxUwL?0Y_Ip!-HRzLoumNPBTmOzvcP-u6~s~ z6&kd;qWUiWe=p4S3%ygp{sOqQhVCfFlX|QYM1MJP{{THzN`n~5;ekB|Ca^EHZwR&g znxg3z)5=)K1@toub1LJ!g@y?P9Aq9j1A$w{RIwAZ;GZ_B`rpd`0GY_CRHyI4c5C|d z{{Vt+TKINpEZ}<^)p&1k=@`0#1q;p&%#$v1esxp3gWT6ieJ-!5*y*}6Xm*;`43XSh z&8y9B`;~#*j1dCDKL$*+t?BcAirqR zK)_%t77@QAl1p{#)K?pCCxU!8XLG1c;z!jaVqC|4c>}zFZTXY;!#scvRE~qEHJkQw zrr`$Ts<+G0?b81Mseitx+?u*y*ZdnB{utC3U$(fl@D-x1xnDAA1ZHUyfS`?t@r6Ex z2;(BTtz$y)Cxq{=C)af(yu7)8mevhE-tiH!k_dH)mnT1Ua5Izdio+)4l&>zg>2A7f zurFyFMk(L=^C_+W0Ei~GxH_MLVbe6ithVyo*iCON>$HTx5tLz^WRP$M4`W%@aO&C} zy6QF>j=Ch73#6KK_Qg~Y%Q6Ux#xOZ8BDWdGL0)zxQ=0ZvrOkKex0cO){+9=6-P`8> z0N@P&)y*Naf-^F2u3YMB^I^l+g`eUCT^vt7T~*oU#ZV{gT&J68XbhT zeh|B~zKN0nt<7^X+uSxWhmlxgkOaa$;StvIXsLuYtk+br35-onsuFHTH7Y; zLvFGxsM~m&D5sD2gRji6f=6-9JWL{{sm@;x(z3R_8*;x#c9)&kTq(P@<7Stamt}oA zZoOW{y|=@A?PBP~sp_+tZPGc~R=2r==q_7qLP=wdNk1_DA`byhGJ1p03YTZo9ub8uRil zX}0aIk4ydiFJ!jt`Y$)M(R@2|;+vlj__kl{o0u7G;be*n85lEU$R(9X2thyU;0!|! zKHam;F72)FMQH63NiU(aRTxA2`36|N+yp>)&S_M|Mwcr} z&EJ(J8>Zg(P5NlAyZ72KT#nb1wVm#?wyWprwA~R&;x8Hak5-P)OTE0liDy|RT`y0K z7FoVx1oJrZfhn}@EW{1G16*gsABp<)g`M@7(-Tg)v9)9oHSBSQl)lE1VuTYZ+DT`X zih#SYGlR7(KO#x*D|0sap8IrOZ_8V3VHW2*G_4(#yzblc{8rnZ7kT0f>xPQg#CmM^ z5*b!ot9H1P&6YsQp-fTjB;x~|5EmK72<<)t_&ZMV2a4BH2UEQfpE*|SvIHu)F)Vw_ za5yYaryyh>zTt>dsg9=`CvCRU*LrocwfDD?=I2%ChQU>zHMD&!_0#(FKBVx@?K4-u zwP%thYna?bVPL{D3W1%(gMz<%+XB1z;f0KHi8eEw24w_+j+_szey@s>QMz4O_}?p) zd#BNP{{UZy-e-8j!Sv~~5S#-s;ca^8HXSTQ# zwg@YclB3iGKaZ_=)aI_^1^sTnQ`wz4I#F}oKkM>GYXm-I9(A*>amG?cY3UHL7*2OJe0q2sE5WmFCJ+e8)Wz8f~ zLo0c&A^CvJK!O1F&py@NLQT<5$DfFWu?{WuJfGsd+!N~BVoDlQ_6^92oU4)m1oq?u z&U$pNXHk)FrnqR&oQ0G$#k|d`sy7|nXRrg)KZo=G01-7T%M;43^#1_Tbo-vS^FO&b z5{#+j7%4rJKRGAApKhlud}5AAW!z94D12m$@zC|7Oko`4IRZ3o#{-;wN1!$N-3KL! z<)_u@_oMWxsk(ahJ3kJX;U@AXj0jm|`+&pTL%n%9o?~{uCcPq6#9HXOcU+#8$ACqTvD%Q;5QVz;I(Rc3BY1#Sy7dh_`B(uHD z*Rb57ja3d;048#$2ZlTzo|VboL}zopDIHbIuGJ(f9FdXh#z;Q(`R;nxwVj(&*GJKR zOZ7ghD3pDIj9PI^PTMc*@GC-*$fi;-x1mc0`u8a!E9166_0t%aO_T$EP*3 zs;rPAS_u@Rf>@F|k8gU<6H!X6S7TfqDMpN+bC=XEmf}&TMGF;I0J9u|JD+j&tz?Km zs`4zXh%iV@1CQ6eZ5Z;Ty0e;dQj>iU+3uo}?Vdi7uq&K^2YihBRa=Q8Cl@jm&SWi< zjO25kgQa>HdTth7Yb_A%G15B$kn1JX_q^QZ0$T}uf24OXQ61fsC${;KX@wwX|{S9{79;0G(tI1?V(Pg%d80DVZP+6O92v8N}Y+w!#2e%woRY|B* zQsvuSHT=3;^%XeE6KZnZb^f&b%UVao?+$ohOOsENQnb9YVvxqV)wR(`7^wZ*7~_#P z_XnJ0ocA}{ahYAZuCWbAfFB}!lM8VZG?Ct$rf*%ms*lP)=+TC4fYaSzb^%#=kFmQGwH`;_O4o(9w9CXer zO?*+}%>-R(+6TjZBU!e0^QUWwVzVtbLc$L;j(Izfoad8R)s^qgyKAaCDI}?;-PWfg zsCbjZTIK6pYF`fTG)vga39VqV7W=_a9Hzp=k&;N~a0eOfi)!8z@TQw}r~d$I+i20x zDJwnag|6==8;(MkxML7d6?s)r(>&I-of?#FNu<^LtL@ck=ilYK!l@~^$=yFc>Ay{m zj?>~zw~Ra^{g-pE>AKvw*$flvklXp8eq1f2ZmtFZ!k(Y4dB2IIn#JRJVx9;hW!v^8 zmUy7RA0bCzz>H@gkTcNpUQ}aKRXN{Vd_6Vl^?th>RGewmw<}L{ul-wIzj@PWo<4gW zG)b&{IlG-lm<`3&rYseXI59&aJ90XZc_i_JRWz&58KjqbuZ8>pGHL4Ge6VU0w6I5< zjo6J)kHdG@QfoaDd)W1F5q*-{;hYGq zbbUTunETtj#@-1Bu?%>~>x#~}3x9ninro%Wj3^e@T3m)nKJmlt3WvDKA5sn}b2&?v z8+N_E`~LvLn8l~M``*9T`~yE+@YaBD<B_4T?~s75!kYpPFY=cfG=KBpTR(Dx?S z%l-=?x1Yg&99XS2i@y?hfg_#cnkesFM+++9e|8QZou>-G0CULVvt;qko#CrEu5|wZ z54M3}s7oY~U9-!134R%4C|nh9oM(;+7^>xUBg;+^f`4ab-uvmV$!*-h#-w7SR$R{h zcI)K&b=LZ$rOCNazqSeK`hA^&cuw2?^E*dI5h>j>bIVL zwc(Exk*8aMD>P3Ql`|89Nf$Pi!=Z>sq$3K4WjEL3Xx&Va`A@Kv^4razb9&U4z7o{+9X@{m7D4I05nA|XOIvH5jV<)vF20`rfxg9u3cPGkvxggmU0v86?DqXi=5lwj7kQfsn1|6O*2uPaEJb66^4ILSF;kcn$B(*4eHF zyML+x{E@1}RJp)*K4T08Cm0zW7@BGjbE_n^y6t6c-i@ois>@Eh=|U;fT(?@k!$;p% z``zh&#vRYYjZa)KKBo3sUFyWBnstSfTwL44fVSxp9p*AioT=yL99O1($kx`d-s_k1 z%^8l2Go&!F5t{dJe+B zNX9!;Za#mJ`KB5i)g#QUqT9>ApY-|@>hVK&XCNwvVPp&gHwUS}A5;Bn%zQg_Hkac& z+c6r)XQ_cCD(&~BKnDOE{oEdF$ix2bR+h)LID2|>P+F~i?f(D+(sag_AR&@iN@7Nw@8iV$&8PXoPs*%C-D`{i*e^|bv408e$6R#BD{g5kIj(@M z#2!w1XZafAFA6QR1=XV^NtK=g6XrNwyx{Si5uQ1(!1$6pnCkMH?)&W5;bi{+F30yD z1j-L6!%~C0jAMOmyl_V3rf75U{F zDc8JjYwg!#^qpf1N%T8?2F?q(A@VKm8bOzxi1|YH!5RH)tH1Ew>^dr3JzeR|(~Q))&=1eA@iAKO4@owTI1NhN))Uw*Ky~*JQNs(7?LYF0Pte zzdA|n<%wgI$lysPFi*L`7#(`oIM*R=N-_mO`G$SXiKvvj==!z) z01tn>`#iS~8g$%ZtgNn*(`{F$LIl+wDP%~ITG20BHQh&fqhQ9y)dys^LY+i&2BwuKu2z>F09u>M*5&sVBRO^!R_Txc8lJ20I{< z`HIp9C>wd&26L0&f%(;yc%nshW(Q#UQ^gi{OeRCDH ztkWp+OlNUoNmU?c2M4G5#d?&JPsyG>D$<3L)f`WSTUpd^?(gm!2Ufs9q%O$RlbjH6 zanIxU*Q7|!Y!)v(N92JUv~C!Y>&`jP*QHEs>T|B*mglw+w z949g=p2obsCaB?qmC|Y1 zYwP4rO$9t$BNwgS*8cz}{e8!Z_!!Ue(AMx5g*82QR$2T%;4L~WE@=Z=>Q)oWcO-IP63Zc;Ex5coPA`@> z^J`Oz))V2&NcwH%rT&*4gDiz7^Jcdsuq24tSQ3ySG3UQqAn!H@;VPvOGyCv^!f4RPzXpr#gRp8>Cn|duymr3x& zrkf$O)O;c2T)Gr#wJTUdAO``rqN>Y~KY~NwgIvAzz8%mnZX&w3y176B2Tr+(e2#I9 zm1$Qews3v%SVl^5vX$HKw%c1}_gK^6np5bl{WCH3%?nz-Z6ipZPSV;)*hMa&vco(~ zqb-B9w?c4!P%?dL)u)8KJ*Zo))}yKF8so%1b<^h;3$z|GvZ%r17$a{u^fa+F)hK&O zNqybdmruBGl&Q!1fACD5M_=$pjVs-FcfrtG-rG(SGfNeP+-DdJ8Z5c#j&_dR*Cns` zSH@bEw0bV{t^nK#1`2J2PjBsM`#3Fr``NEMjtkkpX*<8` z&iXQK7r=faTQTEHD^048=0iR0-ME=Z2MzOJy5L}epKRALdE!42&*Bg58%=NQva4h| zUNMc3^2&gYK_KJ|{S?2=!sB=y^~?sO?Cy4l{}FVyXPEh)T$ZA-;k=Bpj4 z09)Kcb2EoHJP<+K&N^UyYnHvW*Y&-5gnEtGvT1W4@AvtO&;}q3=g{DGJabvnrm1_| zF57MEbk1seRc))K{eN8#NW9Q5G_?}TXf4{>Ma$et9D*3!VI4V8s}_veL!8P zlg3w&KH$*LIEAgGQd{npjIrs)G1IMQ3_r7Oq~UiI)|dSrzdiK1_BG`S@#J>1dq2}u z`+r&-=Ba7oJvYRY>w5H&YL-`RvTLgwcw)M9kCc=w7aXt5M>yTU;<;T@MDQKil=x@C z_c!+upq6O0>Cu20&sc*f2a%R5)C1RzV~TT{bW%%8xA88TSu6bA*~;lSUCMfCxBM6P zTep2q2gO?d0EOU|;>$zu7MX6by0N{mwv?+b+@0QYHry~Ha8bu_aBI^%Gx0k5J)f9PSB`Hg7 zUzV48{uj1|PYe7y)_x^w8l>7)oRM6sMyX?`O9Xbds;U9=rJa;V>-P-3&e>OCN{x*&i`_XqDL#SWi%Z`UYFfMIX4SRPG`AxPFe6RCuv{OTYAEi&WcnDo z5y4=WG!lBtZCjopIMnMH5bxu z62e*D2es2Q*)j4#Z?v%`0CANH$0V;OH4lPyNOesT{{T<9vAb;+*5Y|C=eWNX(2T0( zWRxgp%MKzyU9ri)Dtqv>;fbWG_OsT{UprfU?QhQGoLn~1=(JmIth(v1Up|iO;+VWc z7MLKgk_#Ow`5Nw6E%dqKSRyK?m0iVv!TFg+PjQ?MxAsx~#j&&0tt_Xxnk95;WM&B# z;<*PUR|MdU0!Z#TueRX1##p5!?u?`vQF3G%#67P8ukD@`8vyVK|TerL0MQ@=V= zXqQo0-UM67;1aB9wNge3K`e90J%?dliKSi_y*C!1iJ=(Y6K?+immCs0jAJ$WJesK% zrP=;Eeuw7VzQ&y?(|Z2^mfHUSk!NE@)4V@@4c(*{aHvIa6roLx z(~Ob81L>OUBe#m_#EEb>D8WJr40F)-Jxy?9Ta3A^bl?)4c@rYJfuao*jNzpuppygU zJM|MPjn(kAhg6J7ij?{MleQ7 z;f@bdYmd5x;DKZpFLGQJM3-uq+aGv>NEif-zL+N!_+JswRI>`zIkn#1{J#BC^L>x) zP7B7YMpZ(Rg_KlP`uqvEWWHPOyIkY0{&@tiBJmph_U9taGf zhhCWP^smpbjl4s*N9*}|pQlty*=yU-^e+bsn+3O)ZEi~;GYG;YELvQR{0v}v4%sIa z=o-zeH(CsWb8{us!Hiydjnm*B0LbW192{o9dCAB|teoL2^S!HRbIJg%&&Vce=UchP^q=s_~Y9L6xr8IBcCBeppwj-1uqJ*BzUH0v}G zm6uS3h|b`zyaR#{PW*aP;pc3|E;~6d&uzYcBJ;g+%FbOOC;tGFpGE8P&iB?3NaM;8 zGk_O@c=?7qb?errw~V6(C7ZGI$Mmo2*x6B5NBP@QE?A4RtAQf7(naXrUVH>OC*}6^ z;<@Yli0;wBAhVFU3Q5T7N1(483wczOyzTNm>{X*hFCtrbgnnEyKE*pu0VJP6)9d-v zl0zI<0Ik37rBXpHf(bn2di6EwDL!j1r;OmaZuPO0*G&|FQnBjbi0d-IIPhKk}K;(ZQSv(+9F0e=OlXd736VUX~PPXUaha|W==s( zPZ{vtC3R>200n+$op^fpThi=qG|vHQ&keoN9&{HG4UM-vs^F>41_lRinXUaR!8$jH zblb(A-}^&Zj#UQU*5%P$Y%Px_AQ`dA%I7#3=Q#Y=**|EU+iL!H@8-T|-nTfn(p_Gk zuj}(QJP&2z9|%i#ec~?_{{Ut@$X4Rs3wZp-9@Qq}cKwOvg=5J3fcaG6(0P1D& zrk?s-Ru;Ym)!~LXmPxMG*t`kP49y{DA#i$w+zeH@^nV3wmO!qxVP|tH3`-5UR%IvU z-sF%o*oFg<(~9SxvZ)6NUCZQZ}>mg$cs_%o~vtSH62F9Qra@NDPwi2!X=ETB!qDqV4REr#~kN0 zy6=l6@ztW*XtP|{U1@K;MlD6f%xXC*CRZ$1*P%a3<&|mA;e9Oh)32W2k)yOzw%^yU z>2r#gOV)J@xX!Qf2`%lVQrmT_2a-~odM}g-UU1q@_~Pjh5bfuPs;g%t>>P8GipEWH z`<*^}c`;6!O3!T!o2^Gz6Wv+bi#uTM%n}$AEZ7674YXsR$LU=Uf^|J!+G(wIE6FUa zE=UsWba!&R5X9pgkKs5O<07F_gxifr-rKKD9-op3MJU^q^f*f!uNmv|OM9kD)9RvD zCMzdcZ}uEvktJ5+kZ>FIIIiKm&V0RMCv7rZ(@-BPVfn4Z5CA+^{jedP@FrcN&MQFxCfSd##c;D2HI3D8_I4l+- zQFWn4@3&n#y(H}a0O8G6A{1xKIi&pb{B8L@+q2XBLE@Va0r)rUeiHCki1Y=xXyKny zONk(!>x_iiH1Y%oJ(D%$xBd-tp~J3OX|PUj7#F;KTHT7f=V)k=M7jBaz!(@l^~;4* zr72FoDwL&W;;xcQMC_8ko72BTYISKS##G(b_qCnX{MXA(EO);ObZh0)q_Drfv|C96 ziR~cMuOo(c+z9hp05>SzkTa8<<#-3A@fE$7iea7~4tO?gL2cz0_id)V_&AMNf)S)7 z4aA1s&nJaFbFVLFif@~iI$rKQeScGvo>IKyciUU;yCrX5yG>3DNP8^@TM=CNVr@Y0 z^A^(1(csts8$^;7X#qGqD+U?C>T}%qcj5Piyj`lMrKQ_ynq9?)CAgmJO<1k%n|3CD&6aMsW9=?48?sy}Iw}yoP*3@ea2Z zq5YiS5_LEirc&2@wWY5pC)O|Do>W4{{VN+&t>?&#rsbiU22v( ze~LAK45iJUm?buLGhbWS+Z>R-dqul*6~-9t%M-VNDwd-JzYz53H0vE+4P#J5Ylpj& za@$)VPy#079BKj1=PQ=rC^)F6DPiY$B;y<2+WfBfZT3z1^e!=SwC8r#oxkAgz54C3 z#_M{K@HNxu+MkF20JN=|BCOwUbho&a0zAX8eBpC|Ivnyk*Q0*O*Am0xElNAPl?u_@ zx*`_m405P20U12^85Q@OBgyrcR9|b$$?y1dJT4=Y{{XY9%U7b)O*LQVcjdA57sWjf zQt>~8H3(srRDFV2;~=vsQI#Q23V9?EoMSZ~!;M;7{T2x>ZJ+G{7AHnv#UxR+vd1{d z8Rs2q^c+1U3bJ?ITkhBKx%qx3a;b)k-NoPUOXRI%)3o^|n%XB&8GA`ZF)rj+ zNXb<=Cm2)LvG)E|g=Ecbtj1)UYRKTIDsZjWljwSXg>oo4Qj%Sn)TbENQhI8R&`Q%s zEHehk=OE#5f03?JR)|M>(8i#Y+l6kwQO$GUFBc@X-0aM)B%fW681bdd^Z38)F3e+= z(j{2c$pagS!97@W{&=i!65eT%Ngvo9uC3WaOC*eqDIl;TaQnWU2WtE`h-XP+F;1#& zr)95CPbBWUUi}a4P8Fd)s9>W>S}vShdfx3TYPvR^``hp1H>{JajUGn)kf3rtqxsc{ z1d+}5W`HuVV9}`?o1XdY^z^TT%i8wwsmrC(ex1JSpP}Ma>A2p`-hDd1L%s0PvC*yL z*YC>1EHZ)RsmLIJ0*s!W{{R~FT{~TxT{bCTvCGdii5#;QQ5h;uaya&{-tuQoo(WTr z#L|?$dVZT9fN^#a;_+Wvs_hi{W3}D2dTe=)sd=i#$oCM)ZW32gz?nlSz`*a@_0L{w zo0LMgk1$>8#rPwKA6zr zZNoZ6464Y(VcfXE>_Ft7eAcFc8l7`WWto3Oe`ZTSqLvDqD@gQ)g4to=*a;+dk=bl@bEM zRAV><{{Z@{`ku*CNdEvmUy@-y@m%GtmtxO=5OT5iBC_n4E( z=ltTloDaJPKIgBG_oS(#a>CA8ABc|5M*jd$Ppvmqwsdra$V*6Y1E?UabW^OIYbSG# zr5EgPYZ#aB2Ayvtj{7)eV<9WfI0V-R;ro`pxx3Zc#{3!g#SErEa){$-$6=68O?v+T z920#{B9v5WN>6C$dOd}VDW@&FF%q+Hc}U&wj04nGX0Z&ATNihVM=VtmyZDLB-emzUq=uKkX0!hRc{TD{aE&|NOA zqJS9|Im$~ZcEE};gVgrP931rmy*I-8C5$?BGw6C|o1}?HwUibaB-2E#C-~Jq4OZ*LSGN%BJ_WqG(e8;>xzjI`Xe=|q%7w|n`^P7t-JU$}$9lfAc;Z{n3))-i zZCQS-`)O2Ml_kFYHv8B0sHs9XO)o3&{eNC&&Yj_Z5Jz)u zeWiRy(=F`e8zZ&VJnJ{e02E#75nCkVYZ0DBI(v^6T-sdUczj#Fr(-7Dl#@-_G>U^e zgwf-E27icy)OD^*L?g}0rkZ+v>q}eu`^{5Hb4oT#s{X&PQ_U17s)?AE{5)^f>wLJ#I304+KRTNe`9YBr(_;C7HZ#Tk(WO|mmzJW`wsk^ z8mleOhVCv5)>hV&EXWnglY=11A);&rKEnj@)`-)L6m2eVyVYpY`_a!;$w{|=>-zry zGorHak=BH#M9>x%MPe@6P^FFr7YY~-{B<6^YaTltTf>iUaeoYgWF;0!RUQn1jGTLo_jXTH_drZqDnHa`CZLQah z*yp!weK)`!AGJol)_i}dT3c*=jcqxQM92sw(Vu=YI*jB3D}w_nP=_?5&8FS@Xxe|K z+Mj2NjO?LJYk%wd{SI7d_Ii%1<+il9_KX})cLd0;`&8{XoNV+t#&eJ=zNh;{_`kw> zlXyGBI)KC%y{ge;lSimWqcV*)M;}z*%6w~6>Oq#{+x28i3 zOC`nZR*~FW&oIGa#m>MRA-1SHN55L;#?plw)S7-;B(Kuy`u=?kROM#~_3L%lO}6W< zom=xbzYzGBS$vohvR=3d@=Cy zUFv##I{k*Ah-cO$v1Nh+plu40L{~pC0l3LtHjEmYb>mG%&GN~#lWNJdv{CN*Uix~A z*!xLxH1&VhiuyjT&(C|B7akzeJW*q%>vtD=3dL`68{Nfgr9nLL`GK~1&kRAna=&yj z|wOlnu9D5*Qy zYs~Dee(wJOE2Qn-`dv6fpP%7LFV9^z+s}QpOyjj53+cKhn2^}`(i5s(&IHr!5Y38)MC?Y=d`@Ff?J1^<-LyJvaEoDtUR#Czwm*P)bU+B(yvLl zrxxAsx@)GpYunG%)x+6*asIt;{{R7Lp~`rlT-D6e9bqCqa9k|gyut%@QrTggw-x9g zvmc7!hvJJ`T4|bfly|lah@i;EX$*;g%*?=Z{nL&!jMv)m!uEKoYM$5i^7(mK@$=eB zwgRg1eqFWMexD=mi>ZOqWLv9q0Tn# zM+1;C%8~W&U!`5ssp|g#;C`p%^r7u=^N(9!%SMl7({AL25nAlX{3{TkWaBvR`c}2{ zQ{GsXZHqi_@}rD^PgBoP?bj9NW9g{PO52@TZC5I8E$#XCIQirIEHU1_y`*hs>hlzs zmKX(k?c|f5znypf7Qcs6vW|N;Ng0%2t8jDf4?JePtZuY!-iY@wiTh}_wP>}d648kv zQkyw-UNF5YoYbXza}Cl!0as91fypP4SmC|sS+h#(lCL$q&eq;(C$l$b!I7gI2~tQ= z&pr4x&1!cBN!xf*%8F5e10yHDWB&lwu3Q{fESl(d<`c7x_Giz&Es1qM7TiN5@`-K1 zjG3DZ{{S&KOlO{OI&?LKu3bXQ9lg76^3Vaek^uH3{d<2}{&eDbLY^lRQZH9074ouw z@IFWPzYD2L0fVP)6*#>-TeXQG-n1R%#FL2!42P>=jv_2@pe%{w%5Iw@eJ06@=A$EX$g zKM_uH#NMK_Z(Dl5*H6U#OC*gr(dDP`t6KZ?YkNMoD&8xs#Zpc)kDEOJ_7%I}$y|7Y zNz*5dB}s3iWnc&@bIvi;pUaxtg{0|bw911Q>Y{e?I4iE zTq*?z=6rPb`QX3%isD(O9WyF0=VCS zh9jres9i^I32WF0ZMopFJwWF?^sF%Ra+|iy+Y<#EYWuBEH~5XI8`oVHN#D)5bVhiX zgSU^HBl`Z7?+Iz->MuRPjKu;NqmmZ>BCEpyF`tzC^V+_P;HH#&XngfG&CNM=dYyw` zTiT-9nR=2!p}+);k@d-{QpzTf`6})q;N=NYf5(rn(zL?Uard87gBw*&E-CDAe-!l> zk4Jkk2w5&9+L#0{L(X{Z>0cfAfwg;Y6t6N{$KF_03qkXu-$1_8r9v#nRjvKhn5KL7C96WHoG>? zPu>J%4uYSfS;^v6i%DhHnkdtJcD51oyPStIu#G_44*p044r}7-Imh1V_;0S){Ew=q z)w?Tgf9qdF&qDCWiL{*})qF4FEgIGpwLvmY*NG@|)DqV00Vh2^Z0D%tS6AT=66rA7 zUA@9yU)r+(_NPxtBHT$BVCFKcK@12y?(5LkJDQ^wou0a1ZG89g3Y67Jb2X=XeoIfj z=0)F(v}sydZM01(Z5{llwKo>AOwp@AR zj&Xst{Rcb(xa;d&tLt~(Bbr-F4;0>9TM(+ym6)uFfsy4oF}~BDM{%Ajntsm_K6w0- z(|^D4E-{rQdnm*e z?;6yr)aZQn_q|vAFwYELC5E=zeXXU{ z)TR8d^ob)#omhR=+(cdP2Y7SnDnF`H`{@?&+#3dpO4CywM3 z#(HPEpYPLhXMB_Y>v;xB% z`i|U=TK+22d_@z%VI{P_VJj&TFeEwWsxA zd^xJ=7dL?}b=_9@w58*Q{oF>Lq#Sw?)lNQ!yFEL>J{Grzc{I%eNhZF?d5y$ZGIPlw zJ19JM#dvez3r>=z55QIM3Uv#`t$y-V|aVO)_1qjYBv%6o^cD0WY^j*65eV6ram%?up$D?XvPqV$3L`az)XM;zI-r>kmy-8LrzmPCk zD9FzhnSUOgd8yoA>c1B?6ugrX#~RzsaOoZx4ervYRs)TrcTUcGszt*EDSxb@;tC^ncf5e?jm{_`6%Z*92*84cw9&O*=!hUbuZEiV_&Y$EOo8E=Fd}vVa9_$o9I3(O z!B*su0nI)ih<-7&@XgnUv{cbF%R5jO^D4A-%9cizJ8~9p)I*swnGzb+bXeKZa5r+?OnCK%vV-c0Nz-v#KbhFWEEkcZ%u{yKtP?v)>5<<) zqu#kqXg}HKOoe4)c93vAabA7_a?Qc?J97o@sjjC(;jK&UcF@{7#*FB8GOj}&g?^*B ztleVXWSFGR3n9Sya5nWH&Z`e9wOLoiayoaY{%ho4IGvY5*eIPYYipP&2# z*~H0Gjo)99>OKt97f;gNgNy6=BJ(ZdjC`m`=)exApUV~6_=(mXCMfUjZmks^O~iuE zHuFva&Ru{2V+S?+<{Jp;V4|Zd=(W>d>tp%bKF3EBnS2iCdAC0IC6c^M=g52pgZ7tb#7vbNWKm-W`)@K4+F zWd5lYE$oxl`uzU@5tp}3J;{=37DkhhcsygF{J+Vq--j{o@y>@DDGlZ`kjsJhNzYuK zwco=xtD91tP2A)E0Hq_3ivIv}!}zrwl`5b5M2~!sOFpl26G#u08Y=7{owz5rPPNkL zXx8v$!mFyWK*sW+~d-*b;(;# zvNO%(sEtbyBs^!nF61f%`k~uEQ+LL^MLrz9*6R;ne{&oPpIA89Wzk0wM23}`>4F#*>lvQk_pMd0QDFL74jTc zK~7NC*KgCI@9_0!8g4edt=IMc06&@1d_C~*h^-p<+d*%t-+9bF*Cp7BG=wN6SI*kG zBp#!11mhLf>6(S~8i3L@nc{;@wu!Ccw9;-SGC;=|XH=gO@sZ1(*c@WMUlWFsjjGv4 zy47pfPfKija;pbZo-0@Qew})4smbcz3-Ii^mDF|@`Z7%kkO*%gdpSgVgB`=nD&xNx zJ^ATfFNf1b(rxtUHBCy^b1IaU^4DyTMo7vlm)M|Z+=G#yZx(daRG}4h-{!p?{_}ZM zsW?SF*UcL@DlFxic>E7zdS#5Ep2kS6OSm5+n6f@_IRzXOx1r!x?TnXxA+}3dE-od8 z>M>_4O(aP+L{Xa6)bu9h)5c&jv!NTcmg zGGsEiKuf43y*_{NO`KezcqDVW_lR}h5Lm!94-Uz3Eu^ak$joy@ z?|?x`d3DE7TjtJ3Bv%8i_*N}tw%Tf1q?c~Yo z{b}6NjQxYsUx)Q$qtN^W-X4i{9dAOp*3f*$duzfjE!YekD;7rN^ds>#m3t?K^!;{A z%ZW_Z%^MWAF#Voo<2X3R?t20be;QL%t3o`n_w>JBtNQ#zs>-C@rK8)rf0c;zJAtgr zh1eTW)UdyPRMk)7&Ye(~$7%>B0WrF``~T5U$;Tm=9=-nn3d5VjSH2XF?HBq|^d zjpFrk_*?I#(rn4{+VtI@^1XD`Yro9Km*Mw?wHub#H9c}m%VJe#dE$|TWao{>Om{p2 zIKcGB4>!a8QMH+GJUg!c0BTr6BZQ91VI-{)Bq}PZ$jVQq?la#N+P<&P%S!I{)1trS z_xh%BLUM#}Q7wHR-?IGtx|BRqpxCob$rD#&87*6k&?*4b}cCF`sKQ(iL zobR&f_gnh6b1L`4u;_EVx;~So8MNJy-rZ_92JLQLht9rBlB9yioMYua^_QgE={_UX zFD@g~^?i1AU_>@(mXM*~IXhNB7v{!zABA*axutAFo!zy*iEQkWwcWJ6(K3^Z)!N5>5kqV@Tr$qjU3B$aeXYJ(HHLoSi)oF1muhkJ+tIi8rF;A9b)dv z^IThau7gW+Cf$ha58Wk0JcHY=Nn@N>RW~_CbuD(bNhRpJ->$C3(Wmh_O782g-DI>{ zKh)dt2Zl8>qcj>`s}{)dBRtWpL_zmeS8*+jo(9pw4#$yg^lcYIg3nO#Ot)8-2qcoy z?%l1?WFQccm2L8L=jBo9(=@3{jd*IGHTT}n?$=JAi0?H`D5ci@?f3ov0ENzf#Atj& zW#+}D>en}K4i+VOCJ7qkoFGhq0LdixIp;O!z8UdOso{SXY5I{MuA6wXHN5P2DEy}& z<0Fh?zcut3T2y5iM%PN}%kkg(*utb$Xv&=3?yUCf=cma1Tky`fHSY}A-+iLeJ8PRr zr$HX=tjqzx1Otp?f-7gmI#X);OtHxfA}_PJWixJ8P^<_mft+>cy?(KevQeqieUHYn z`8Qe9j_XbPY3ZvukA?b__xc)J%OH6zw^}~s*h?qN#(C&7?V9vm5+;@si~wBcEW3bF zp1gBhn7RJro34jW4wHr|RNCsx+NFk{Ex44T#88s1uz{{WtA&&lOdm1PJ@&FS}_L5_?aHzu@No}u6;7c$&I zsLMUFLmBdXhugW7obWOT$voFzZ>8y;BnfEgCGDNCLkW0GkV@q4EJjEtp1#MGo^O-pZi{ykqyoS%)n9&8{ITgaH&+>37`jogeL z4?N_MezoTfnC=*>i86Qxxare9Yw=zz!#pNAN!wkv>HRGa+PEhl9M3FMv%0!^-(Oz7 zqb}GaXz7rn0GuAbTI_xhTSI%}NL>MOYilF1BbLbk0qOU@THk{CYG)La?;Cub{{TXG z`fiU4<7U6-+|&81ey6osNVDoUG9rlcAw%^556AGXjyU3nPL}LU(jBa-GEWQMzoRkD z#YPLr{u98f)Rdo@&gs{(Y8O)7%6BU^18vCX{DEBpUQ12dVA!sKilC zMwR;)LadahR^7{*Rl67(_UK`p5&>=k{VRm=itG~HCAolrs*R9} zFcg4BI{Mdr*D{Y&g1jwxEv#YB8F>mkQZ_+22bCwcJ$b4=BEA|{kZ(%35X8ZwS0Jz) zfCtpzSG@%ruBiDMoYQSB8`JSTuf4)@8a| zmTB4p1aaA05z&@=l3kd0Q4q;IV+E?;hc!(z?N`1Y)_g%>3Yf#g71f2SCe;~?q3fIz z)0OLn9TiCXR^ts^cH64?f5Voka_p~l{cYE|751S$<-8hOU8T%+yWUl_jyq?RV1c?a z*pTDT)sC;FaX#Yv}j?0EYhngX(oTa!J4Ie&6I| z+GwLw)CHV^`7UR5^JWrmk)&QnOpw3~0@>h_FhQ>CSJPn9w55Z_UK@Gm+FC2SYmpSp zNWwSnn65{mQQtYJkHr-y+3DNm<=^rr5mrxWS@*FGwU>(Z9|zoD3&9*^R@^+!%PRm* z7DX$;_uMo7$gV#7Mc3>s9hyk5?bbgwW-L6_B%YhOJf7JEFR15EWr$Xew!ZrP+dudn zjFh8JZ?*b=TK@oErtgJ3IpWP`(&NNF5xKS(7A1tBUnEy7yL#=&$RLx)86R5bHG7>( zJy1)kUEIerF=muuwy@*B2kD$~&UiIbqf(zLn$iCN!*$dZXgbYXRsDZoiEzEulyY22 zEKFyRIP+j;GWR74HZ#fKcG}>LOt2~6AtU8XoDF=2j>T!{p<(1S^ zino5B@CONVO}O9hK9)WWmgugl0$n_&CCj9uLfFnp89yoXBhwX;eWfM+@q!Nv#PNkG zzTPnuuE(i6&m-7>_3Pp??9I+i)RMCD*GpS}nf5j4q?aOh?XADhMX|MOqu6LVdnLM? z7-9o^IvG5vG0}v4e*C4mAQ^i`sQH-2vB$D3m*Q4#V z+xyJ@tkj>jTK4|5*U_0e=Zt(&Y2pOaG=Bz7cVx-|+U*Q%*vZ@*1p4wvZkeq8dtbY| z)QsB9%8nI8ap`QWkZ^XF%LL9g;d%GXTa5;kX=^91Z@=ZWnGQ82@jaL0*VpIT);WI> zS$t9P3d3cnCYj-{3$%+Q7DizUPDufo$jiAP_s)FUSSa#&>BzV7?W_4L}tGMrjg**!n2et(h1+{dTu+I{T0_m6F? z#O{$byt6r)U`NdE6cX46gvi`L%M1$7ytuINv{pwz(;(bU=HvE~~=o+I~_-=a`?PAdNZSh3~ z#<6iUmva(+V5k^u1QGx!F}oYOkwV+Si$1Rv`gqSpyOLO(n`rdUv^q#Y$k=z88v_R{ z2*qhmKEcXKHvGMGw#_Sf+ilEaR%tZ#z4dO(`rp&D)xI~x5o|oY#}uPMUqgLb~+u!F4E0k1eDMpkwA>Q0@Sneg}*k*Qo=F%pT+2l)iM`)1#?6HvKB*|dAOqPtk-S19Tkb{ypU z*DYAd;rVZ_yZWAoy0M(iJ#G0TYgt)Mw6RIKVV!p&3ZRA@;NbEOJ69urWhJB*^Q4%P z+^a|>RxG>QcaEg-%G293Foz z1y_nJsNv!UpOM8AR{v7_{@S?x9;XEsE?6v7; z*Xiaf#9l`7x9vazh66v2D$bsfBbe?Zc2K}B2wXQ_dFj;u0EK+!285@I=5cN<{-@jG zCfx^Sl#fR6gx7j?&8xPBZ7XhK@8&r!fqqa%4;dr3&Ebm?Ev*=;(Ma8%VusJnOkPv#yoht@L>WrwKeDZLh&B;J~OuAK~@ zh!+UjOxJevTF+{VUos~4k19wXK0zm^9P`?|8tIZ*CZBiik%E8}u0DgD0mtQEnQ`1= z>%luM-rDW@?foA2Ye?di1a848ikG5%Wj!P69lta(;i;_0Z>Z zG-weag(EL62rYwvPg>u5d7+W)#QXX#<@rD)Wc_NfPAYbOzi~K7xka_<_m?%hgQjR? zxgg_iLk6sS6|XTLYr=?=G}k6X!GCN2gI$Qcy`*xG&T^Eb zt!;GIy6=AE(wd_i#rl6++wU{{KdxQ)c1Q3ph~d7L##sQfx`f4If=-I_AX22{fzKUD zJq~~9ys@g0dv7b_1EL?7jD8?zzc_4K^p~1knl7tzBY9|KwJxNUCqFJdagM*s z6-~{>!czHqc}x8CHJZ_K^!}~?00d1kO;bt+OW1c?+(zoM%&!>?0putn=G;2>=NL7W zCy1`$wv`QxTcc$%N>r}mNyd7Coaa1sz~?ojYNo7}uj;q*)iKecr6%vE^uOT#N7%Yv zwGO9c6{euqwpNig*&vG9fFyqluv{_EI3x~w8oz$JUZy;)JID|&U6pR5j!6$riZ^<3 zUzmMWB$XX{_w(te%c1q|ZvOsFq9me zlGE^SOa6tZv`r$`86eW^t(N`vw5;~vlfdo|Jv#e(3WD;&6)5OndK2*AQeIIYX^CGf@rR^lSr2ha7EpGj<{zh5wCkqFR?;fYckw^k$5Z8u&uHEsS$erdmv zhb5ki`ttm*_iuIJemT_bd_8TcUwEbC)U_E@Bs+`7v8ezC8!$*b3=mE`^{+6uxYVCk zhFfhd?<2QCAW3Cm8U`DJusn=)!1wKuUtN~Lx;K@gwo6Xmef3|K$17^iZSULV{UV&+ z6n%Q`SFn`tmu}$W5tl8JGC=`BCnrC{?ge%h-VxLE`^cuX@lCk5gLG1A5y9oa2~}oD zWo(j1IU!ISaC4mXSH&kDOKP8Au%nhpeb~hIC7m+V+ zFNBlaN0JzX7!fW(!DSgFb>^<3seO7378PB3yg$m1JG zbRq63D{Fr*msh5%*Iva{f^bor{P+Cr`ZJl<^_#0=z@!pA(wA$Nc4q~fBazrE)0PY)?cijXpVd!BlrPf#U{;%iXPRz>F zgl|o2`T1?<{Uhto+1pb#8l|)rQcpIWeWyT7#g;JFDU@Qk8<-KWXD7XVY2m$U;9VuI zr1=UI2aGWoBRD)~j1HY^_6jLta_gnC{L+7~WAa?me$O{e{i}LiX#4*FS|f@0pKWpB ze-i21?W2^9rvgWajk0cKQV89iI^Yb~b);Mw-Z2ym!OjB&#yw66u1as(VY#36{aEkB zMli2V+r2*@_&?J-MS|Z@w*zvtumC`I9C6gw8?F7XPiKZ%glhi)BB~=dm~oN`>4AVj z#~jy#hi{vfOJ;kuRn_D6mi}hP89dlnG4jrSUi<^k0M~D6Bv;x!tgwFh3W*S| zH>l&Ne5IIDTE-XJwW>NUnhchL6kqPxV(n zOvT2O=t`vaSNy-o^iKur_WB*o$?*-e>d}{uOQ~dcWo6n3Q4(aHqXhQk@m*f6tz6zi z9klv;!5c~@wr58(Nwj>VLccozPIuItZxK`tF z05m>aU@N}i+>EY4C#P!s--_!~#MD$~{pEcv-FhFUa9$PAq3tlyT#c(WqS4y+yLYy_ z@7Zi&8%2U7yKuxyy;m!hARb6K`q#O98PYBE&j&uDQZY5;k1#J8$&7FZ9eC#z>G)}d zYa1$#`a|<;zmq%<8}Yu&hgBs10EtyE`~^4pq;~!o)9u+70GnP#4BJOeI*(en34ub@{5};|J4I`7;XRPX#GhT^7|9mg$l}mg~HXkD0rFpXFK_ zOs#ct@=E|wpEC*p&(zdnq~_-jQ&+ooJsB+&*vl;H{$reF z&JP~d$m)?xb8{z^G1?B)D*pgB1~NL)lg&zUli3(&adD>@t=SyqBZS8*hC#_}V8^H90E@g_vq+hc1y?5-;Ea*a9Wh?>YBbN88uJ@S;?wTOh%GL(+fio1Bt&*ACmf%hzHSaW za&w-5*X4Q5er$D1F1GE{O?_4T&(Lz3PM!vo9=d9mOYeW{)a!K}Z&|+Z-L9cyr^j(; zGBA$mlmir_sA8vR1fGq%J;o0c{3z74uMb_%sA@Jcy~VH-nCU4P;Fo||#vDEv=*9zwggEKB8ZcWvpb>-azT z9$J_xQBT>+Z9ZOIjU8~^YdR&w@2=QB2zf=V)RHosfT6s>yBY4IZyuG;c$)5C5!q>G z%`WWcW%4JA=I_t9y9>r}c~B2>NgXnH&mC7)B$r)(OZC-XW2TgOI($E`_5Czhhr@c0 zimrw3r{I_^H9Zz35;mL~-dW=xbnFLfW08@JhV94`O%}2syPHq&^^}%M-dy&!(kv64 zjO{8(VUftr?2t$!Ijm|*QH`ae*?E4J{vjb7R zwfHXV*4}%B4*pfdX%gKjJu)%R^6#43XrimcbB=gBl$-KDOf4jB14xM=&I^#9%EvCG0AY0m7 zqo(--%tD+VI-F-b`tzQ-r4-aJveWSU*O9wk&OF-NbLu@aT!!X3w8hr#qP=A#MQIt3 zmgoaWgBizV2k-*A4GTt;+xd`bu$IdiE*?e<&FVPoo}c4imsOQ0!Bd6#pO@pWPgCw( zDm%`i(RbGW0Psg@Iw74z-XObk1b6}{T#O$1-<`+l&1qWO*-fS?f@!9ER4UfitC?N{ z_d_-^a8K~|BhtMbEk!uGG*z$F_urc*o)s*M5eLHRWj<(bEYY4VWpxZ>!ozi`- za9E$GI3H4LBKGG^vASz%Zc|T#X(=Rd`HbhU-aLv`cz(`ZLshQo8w%j+x0MbFa1`h<| z9V_Z6(2A$YDQUNRck8G1V+l1F+HZcJBBr7>J$mui{Z<_%ovz({lwe857+`^tFa|ln z2a2<*>FIf6X{g?K-%Pc()7V9{+!vjQ&&?c4pdtF6GBcB!SeF=19F*LezfP@v%gvk9 zyZ2Jj`73`~Yux9&HR8=famEs{pUM>!`1sbYCNetZF45{veWm1^v|+qJ&`0P904ypX(}o!ej6)%BFS zf-9X#rnrd^!5nWGR*YvL9iRir#&eO6QZvWuc2>8VaMmramfCpTqmnj!J`PA=2?TT_ zILA*~?WB|^7i}-M-}5u%anjm+zu}L4_(iB(Ui>e!)+5wbE3Xe~K@Hf>uA7;ee=bdUFp~C;H`O!UNvOhB+=tw(8!YRQ$2SdQFlJ3=QZqi#}_s^0+9D~#qrHZ_9Ej^^JULAhnKCzXIj}u$l z7xSP15tS+w08evP{0%v|@c6fhZe)96%BD;bc{$p1k@(h?8cxu>F9q;_!W$w_H}GGHk{8+x~SRq?w?!O$JJSaNfcNJ&Iu^P8OK5~ z$sF_b^`_~wh-GJtF_fH*q##au=NbH~^DHG!Y<1qM{m+==5@Tz1^DKq+(oL*+(?VcF;yG z&;(0)=5~k?@`7aHv5}rZ>DsuM_^P)pbr>yE*4KU4 zUzz%E4AGjUd0y65x=Fk1veT-!+&o-OsI{h*=6R|Bh9w=#9C7upru6ML9S6ZN>9IKj z%UA?yzymlV@#i)AXNItpsMN15Zs8xg{{ZBV#Qb{1MwL7+3OamqYwlm0X7`6}rAgjc zql`wefZslGo_NQ#a(*Jzq18Ngwh(V0V}v}X2Wi}XQVIGR{U(pUj+B$xAI?*>FiI_M z&c4C`+I;QiN#(R)a!xv)IICJxM`>tdiPGE-rs-c&Mc&`fhn` z>=J6eBYj%zHN-K=MVZngfuuR`9tbcWt!R*|p(C0BsQ)89C*MJ=S1h1$VkP&hpG9IxwLSv*xb zI-Y)cFKJTIIe&;+mFAVAOKYVgNppGxC=6yzgn^eMzB>M1wUe$`CWqna=hE%Pf?I;_ zw#vhCZn+1!B>w>Q>)5XS-}3&vkDY^1rkd*Q{$HCuIFDJ?b<53j#5&9#EjCih`;0A)IUpB$S_jitO06l7eN zAr1o^@w9LTa@>mTTTIdXPjLnR0ER7Pzmg^L)*VJfeU29(HVE867#Um+hO?Y$Nty|mH(m;Fwa7};A} z?XJB$vufADORwI+srYL3V45izXVbj(wY_`}b|c5-$^gm2^&i4PseD19Yc`hv_-GiS zkYZioE#*hS1Wg)zxg3qaDaRb1yv}l_?fpKzbT*WnCZjuB`t#fICAP5E{5>|GbbLi( zBfN{so>4KoR0MKImUj)O(-{PuRtJhaL9OYVG@ID1rw0WuY%UCtyjjR3xh>p`9(lny zzzN}%R;st7eXYOzH&BdYDSI~?Kl1*xEX|@?UO{c*G}F@YPz}V0$MF9E4{VHz(os>QqT};g?dHEyCr#98 z-qzFcC=U=@Yb>_H-uZ6CYCMHa;zv+&26!XB2;g@kr$^!DT_juTvRlP*46&BCo9y0n zSR67kb?cve`{KH2(UjtxmDS$%eHYK>Wm52mBX+;b`u?tE>aa(3HOI2 zRXmcxSRQ%7=O0eBp4L}-eUF;@Yg&dzSXi)SaCk1Hjt?Dw4u-LcSAQq@^p~lklwFjh z{{XM+Q=hsQckn}dJ^UtfF+l_)WTOB8N`a6)$@=mI8mvk*e6vb#5d&<_(94o=6#T&O z4;+rX@+#pN+Rx2)^Ys3;I;8bUUwyo`{=dlj+e*;xBvO%GD%-n*h*h&Abm}?$Gx}F! zXJ=(;W3u!2Fa{ZBn3jIoJ%Igd@%%EUR$P%v{ocQx$K2xQI7M>a%b|m+c!I-DdB=v- znH{$It8Qdi$8rh4&%Zy8YFYK0jW14y^3z|qzL`$hP#{pm^;Q80!5JJ7ewFXi_Hfm; z&GUA*r|SJt=TuUhQcHdIM=!7GdXA$UH#&9HwzktUnB0VWh@?E2ncR>M_gI6tbmSW0 zb%Wwx2;4&^uWof&B@ZMPw-=7e5BHpqtJ}77?_IQhD9RC5(n+ z>An8|Uo*@+U!h;>*7q{qcymvlUH<@Vo6EXp2&C>GFHXD};(8nrt?HOLrZJ(vD+o|XKCZ96=b^f=pI_P%oeP`h< zLF{!qLm-0I7=pzcvmKH{K}Gbv;JcMQEdf(OwBIVo)Nsk0&7+ zhXjy1V3I+vPYBgWxz*Ayqwm+}s$Vmj%bme#*L^qh({%nuUWunz>({djo9#Z&%#Gxh z?&e0=tDJDE31WEdk6tla-WH!!T^CY^OVc#i>|87p7L3Is?Z?brhIuMI`fyEl<6{{` zsa+*+_-{K{xqK}<+fUE*F>fv6xVmj_eHtr$o>*uj{o=-)VC=~1PjWp*L2SC$TDiWk zkDH5V)k-|<5O7EvS0649Tzx&OIuVU%-uJb>dU<|*dK+CNn|_~ht$*QNQ&)*D()n)m zdu3F4ZLY$3EJ?x^VYCv!fY{ne#&ceE;wf}M%cmgNAWfoG8(6p}hZ#A~On^VFbkT9= zk1tQ^&i???`J7be&nF12zdx0i{5kBuvu?RzcW0~kK6@38@=|A55(W{Mee$phrh26^r|t}{o0^bZwZXk%9`6wbF% zu-mdlBMpt9VDXYU>&I%PXksRk-*bgIRKTZwR^QkB1K4~YcWy0>vRpn?5<@O9zh3=n zuZ&|`SS51_XxcK;ZX1-YJM)g!^0gPU$4W0tpIt}yxF||5Ya9-Td3WLMY6gj8n@>WF zlH~5#LCyw9KF2+}SEF3rrlA*|1gOimdbDGy1GpdLR@lXPLaOXm2_~vj^Zf|5KyNg( zo>-zR4q1kIIOnHMKb2#6D(c$W^7~Io%!EuI1cA959H|`eLF3-0nr{mzu8gVLIJGC$ z7W`ilEw#!kGkK8~Mkmwo`g`$THF%Z_h^9&8n8^^3?MWq8Dh_Zt9Csgqug*M0qbcC2 z)=t*H>C>tE=YhD0)5K!1(pugveA6&5r;yByRwAsN0)aq1I0FKzZZS6JeWCITU^hQX z{C0$tu?kMf`gwLgq#8<OprSOGo1Xa3C44dht|7jZ8R+( zNRsHuc2Z^%M(J$Ox#axbSf30y{vn<{1%9=cRD>{`(Rb5ZMW@%T{_A>depQ~*tydEY zP>R-Cb4gpKmgIjn_R+0QZ&yok6n8PnbbitdgUtzmxg$K2kEd^X=5C5L(vYpRGj1WU zai7N>tMd%w-^W>9Cugsoy**drevy;&Dhrt==Dz?X|`xH9AwVy zNnkdPy@yaetLZIvRY~lu@_e{~ca-uv3<1x-f5N|V@b;8rfwXq!e>+7l%>G{S-n*7> z2sgDQ^1Pp8M#APhO)6IsoXfxi8OIqp6~t%}o1Jr1)np(^EZY_NIRJGT`u4B6!z)Ux z?Ya17C*Y+E>~|(ciq04!n3FNwcooaHs>jt<5Nyl1Xlc#b)4)p$0KeV`Wz4lAd){C z<$gSC@@T#iySB3O{L794dF5VJ`@2-J&hNd`C#5WXM+`MdLtP)`=5s=o@ib{qd#~!= zN5-}~VbC>eiS@CnSYJ3QuEM&|!4oBT^r#~)n zleax^aw}CDPHI&jZi#p5wcp6%pS7t{QG&JayS|^-{4v*?uL{}e5$l=_t;E+3;#p#S zK`zx!Gr5<`1#z5>_&v7~#WMHA8ZVBlV$|+5s~s~?R9(ujNXv03=O=gE9CT3J{J?>l z%C9WfB{=DAFRT8%{zcHIHvOdDsqL|!;!g-_)_QOD=9{Hl+szsYnPHI08C(Jtl$OUq zwB?2~j=VF%-Y}B>-e?la=Fd`AA>xR(^24L~as%|r;PKkL>FTX6`|YQuzMnI)7OMv} zy8ga@n1{ofr;VVvj`H@>%T}|W%t=7<%)yD}wvM5ce86Ya4Ai>jmwBT2eke6brnb16 zK=8{Ua*i>z(aB~2cgQ4l6r%{=mfHUSU2kHiSvja#ZaY?j(i<-lXWBY})(u0;t>Nhxcq*U9>S zUx{AjwA|U%JSr`8fAov^yw{CPO0J{;+>SxP$vlJKoPktyYpbcO+fUQ1E$y%EgUKO) z5hTmdo_BVUZ?a^^tB)t0DW|PpuElFNaME3sxFfkjOS#76^^vv#Ae79)< zkORRZkVq#d9CYd^kz>@frP420QJ! zTshoW9mO-$a(`a6`2HDAs^*r9$!^cTsZ~N+Yk$EaDYWQTNUf69u814nBw!Iws~^w5 z(y{f!YLP}vS5huKxb2{PMjZA#cqjAyYtyA3SlTM@@;Pc%Ztb*=HuF>Xix#Bte5 zs6nOK*()KBIsNRI7#RNP$m@|(Y90X7wdGw{+)k6L6f$hT_uhEhk1(=D8nejiWML z?i}N5U?~_qPs_?D!0)sZ|}TYsHN48oEZ|rFc|rq1&oyWOJuG<;A5Kfu+(P= z#XI{?)#Sy|>c;0JG%2xw^DgZHc>dN(spz$-z(vz{j!Zcs;kJYra*h z{=ebOqaSG9{{XEIUHD;hK852C4|uA5Tf>*I%O}|9hQI+VF|IylRaDLka6vf$jN^*> zhf>#J@RyFXzZctT3vpxOIMYs+H4GgjL-NUz#1{M6&rY4W`<#yyo)yhEc*#3G`X}_%Gb&D~!2%CS>VQ(8x z;#;e$`H~owqlOq1ZABwFBoT)s`}VGu>rc6}yG!i`U$sDak|Platavyp(><}pZ&Tfh zPvL!kBWh0dX8Nw5@WjjFFt+WcT_YJII|`8Dx$H?CeQJ)Gsr{40&?UTix0c+qkfU&A zAbh0tI43_rQS1~c$t|9t?Rl!gQd+GJr&j{>D?#Qo4y2LB2^^Af)3;75=TC@s2T#6h z38o>;#z^Bs{0-3c&row;pYio2Jfhdxuk!rte$C*%CDYI9Q@6z*%l-pr5vWFd)KKjE zRX|csJDxqdQzNsE;O?EHP`Mc{nsNhr{|-0SomM5_pN ziy;lvdtGIY4broBAnj%tT}o5uAo6R z!)@F@d@y+plbyRtxlF=P=U)$UyNb^FGgd-bC#~!2B zxsQlC-H_6j*2ROU07zjV2L$5-o;%i9dUB0Kt)jVDiN`M)vqDio?#`Fb3E zoZ@?j61oNocVLg3>s*(_{{RwQ>DEwLSUR=lr#x1Wqqzb=%oOlPaB+dpO8N=4Nx4g+ zK2D5YB2lLvuV2*K(X?;ue-7E`*0#dQ?Umt^&`4a8*vTC5LFcu6+51jw{vNrKeIr@B zd49-Hss>Gx5=Sz8%FEAn=g@IpUTr8+%bZ_bH(qUSb>N{>6PqUu*Uj`_*Gukv)u;y5 zRqbHY4b8Y+_To4DPmnifA@a-t9YAb!>4Qn2>M*XP*7p7ymT0a}Tc~TNUBiRU0;$Qy zdIO9Tz^~2eKi;l&qVsFa+rHfzebt@6 zOLk`@Atxl4cjUfn^*WCW_lm8ZVce48X6zmrq6-z0J43eJasynXI7f(JpKve!ef zSf{%1$k4S|(E*ogNWriUTtZBkP)H<@G1Oqvl{Tr~JEyk)0G*kQN#1%VZ7$c~bNXf6 zJ`mJKqdXeL-iN4Ln8a3hF1G5;@{tj4Lgyoq*!8Yz>f*}xR=2dZ)#Y}yB*vPDD}#}R zko@t<+i6jrhZ)UzwUTXU)V*5#@9Xz!cj2U@-1k=7uW#$2&}!Z$(c*_sztS~ux40zQ z+>&Ltml$~Wo_6PubI8Uz5mOC%_g<0V*QK|X2|i*G2?XGlB;XA5?~LSRWCC}L zFY`4?xVcGL^f}CH8XVEs=^Bd^1I#LpjF`>{z~k=Yfyc|wIIC6{mY28f2B$pURL=23 zAy;_R^#p-~pK>|JVk$XZW}3fCz3tPczj;kg+|jr7sjaDae@eL1VOx(9K{RYYmLSX? zBD{{Hk&)DN&2tYftDv+tt31+21gz>{B!Wl^#EkGts08!S3?3^;Qj(Xlc4@BZ`T0Jd zkf=939)^V4o$J^o#k?~@z^l7D?JP;)76UtnsORy`Q;S&DuOLf_Eq>Rqx}@NeMmY$1 z865labJDrz87s8yw^qM1UPx}=;44Dc7m=NM#rCfel>?AKz{h-%-#OzXaa2~@PnJ;_ zGBL?0ND4qCWE1LndqFW9Uh<8Z95dCoUIq9L+qN^UAMo{MCc{2%M?KK@i?DcP&GXKGq~ z?e)BEsNG-NMyNK%_bLm2z*JyouX9xGG|Q{oW2fF+I_#SNs2q=&6r% zsJOz`+fKLN&qCDt{C`^HZZ$b? z7j=c)jL|0Bbei2lqYyB5lahVN;~66ANGQ-ic#r z29e_^^$!zWDg^@F#CK32-PTCQAMUti80lPR#eEY;_@^G1Yw(jvu!B&xw_v(O)#uso zBn-ncF6J>z{dwLS{e#9n;{#nfaFtF}ms>W{w$G|s@48*q-!m#t4J+!`Ri>BgZoZzj zJf7#l4W&aSk*q^=VXRy-3GGd@CBWbUHt-a%0OL6HCb4wOs~ZD*Zeja75BTUxh(J?oj9PlEGSx6w3naWuDg2@=IH$!Q6|Ob)z}kWYW5dX(iVkCq!H=Y1BQ zLQ?i=$?4axOZEQ%Be2u;%P)uXU+9-wKA)*YYjW^P$!lqLCXrhV7+gk4P6!)H{{S;x zCYdM0kBIi|{{RTgdUu38M=55O!s&B2rX}Jr(1QkxZO0-yo3~C8iLZs+~P?04!H~8wuBqq z>-XJhs(N1k0CwHc$1G>Dv|7FH{#)`tXuWeVa(LW3PO1j>KZ9Sxs$neJ+O02{& z;BrSeIsR4H_`gn%U+|^JmkYhcs+S8Alk;QcILqA|?6XLR-YISN* zsiv>`{{SPK@P4Ch9))jz6tl(WE-)3O8-V00u6u)B{*kFeb7c2Y&dne~k-~~phCbcR zaOP2STQGLeEk@ln{0VQZ;Jc1ig+fmQ$W~O_k_SLRt~*td z=G82xoTEHaH<(d|3X{)X{{UKyBwLG&xBmc#G_5{arkC}hur8#ZPBKSqX7YhPQpi*s zoMaw~dt;|OSBLyjdrACEijOK4wopdpW>)kB6Q2Dm;kfO^U^!&|()`cayc~?bw&gg- zXgmG~2XTDH<)VFH5hi;Ia>fe*A~1svnhV!srjFZPw{{{XM+sr^pk zp-H=cRy!{ZL#W^0$7>d{nr*TpDf1OuAaw^k=R9(8@7lFIQEzD-u(uX5w59en#!`=*6MDd#FPVejW7K0g>C)2Cka?|;L6ExXlsKT5+@ zsV|Rj$L{iaXnSA4c;?dlBY&%iFlLfQjgHa0Dr5tkah^EOewFAx3ej#+W4^gr4EGMx zzHn6uZ0!Jc9V_}Xh9&H>N^V>7{{Wf%Vd9LvuM}cs9ewM4$tV4OM+5PXT)Wh@mhjJ# zml56F#cvo%fGS%dj?!|(0r+*U?!>`kX0S^m#E6P9vwIQ;T=W(76ya(SgjTvAn%0t2 zQg6HdzT8#ykmEWXbHiCKe;D98krTD9W6THfYnw6}?_ z1-3W10~k2t6}}dns^gpfRjc_UlQF8P;H=iNXD=3^EVIh9+kd0NhFKkfUAX6*e>~SG z;7ul98Tg-8@vn#$3#$tj5b4ng51X?;EUKg&DLEM}oQ|C<)WpffsKdHn*Urb0m%=Ze zwDh!o{{Yi#oj;8{O$L{z-fHs$<=fk^jxmAI0$7rG9R^Q&_`~8%dIyU2GptYI8&&gA zNpo{F2H|bh@&}e9BphwV2^{AbHRtDXr#w2KuR_{C3pjbYBi@ z_KO|IgpQ%&3utBqZY^U-Ay&p*I)Ha|>ANF1-0$qZ3~6|5QpV?)Z5 zu&)FUT#g1o;=Tr6(+e+gTi46d`aexivXweGxivjn-FEx+{RJXxyPhGjsKkU@eYQ7kXR=dTA@~&<&FOT0Q0@{I^8eE-VLy^wwm8cj@D~c+YIqt&giVb zWNqKVjt6dic+Hu-Q>E(w#}&=xhN6*|w$z{@L}PH;q#WT`?)i=ZBc6Dt?d2z?{{Vj8 zy7?H(56kaK-~76+gmHMU#MY)w9_vW9)U9n*p5_b7UoZV(06MxTAh#beC$GO5ORIQ1 zSjhxl7>?c$$#TX^m6B-l!y-ET%m*JXI{-N5xG^(rtGizQSJAGzeurfmOL~7kzt^90 zAH_Crs07rkq>6acctadfDwQJ{`EWtNJbp)Yc0LL4&aZo=T2G|kSv{Vk@|Kq3F)UJn zkcW~!Y=8mlpL$-=!U}s|eb?fyjao{Qy3v2Zf7kpmd&Cx(9v9W7`*xKTyS^d0jkbv8 z!k$p_IR}n$k@Pj4ccp4qdKIp#r_UAQ#Wo@;Kw`P)frFfL@6AJ`>B{Y0tFKSFrWER_ z(@xrH`uG06d%oITGWX0HiaZyI7RQm8Wf*@KJqXWVL&pTsqUrJ6B(uS(J*C~LW?9l9 zwbW{De}$UPxW24+$_{|+w{4ZlRCvbw>~3;?43o`phLTBbY)U-LH6g4 z-RPZhZJb;AgUEc40605{=OFbtJ+M!;V~M3G!BU5CmDllf}I`(ToNffdzD+0M#p?Q~k$nYkr+KUe)&=5BQqhU@G$mj3`}xDc7H zWsJt57pEi^IsJVFVd_v>PZFh`ttF+XcKb@CMNEy(2c3b8`}1A2snx_a7%Rmq+t1T? zqFP&H&RP04F5Kg)d{=OulhO*2bv_T`QMx!v|nkwk>&7(X~AZ$b^h<7>mIFY)~$6<$i`Cka^`~d zU#h?5eutjx>96=0y{Cg>}J|6 z&x&ZtCn+v7F5W4fSKov@HsiIzUSeuiS%Y=v$AWo5r+}m$0O}ha-^wH-5apS zy=zLHMI{KU^j^Mh*7^4`#9}E^Y7=YcWpCAaJ9!$`TKA3gjX&&OD2GbB(j$~5kvoQnlg2|K?VR<|(mY|H{6*4-!|x92`j5ld*`3xTy=$0mdF6b`u<)OxpPwqIs4NZCBPZZwxX6EMPeYFOoWMwKoM<;L? zCxFA#y?S&~wahOK-O5FX_X)xUWf(p3Irrwc>!??u&jqTw{=P?T3bUh)lx4K7FZ>CA z!8~tVxtmMAno@7oWSJ(C?_#(KoP5gJY#uoWjPNVgJO$z+Z4z1U!MA9cfn%{i&kfh7 zzH5SMRiipDeb%==jkw08I_c@NX0ENTSdjN3?m)|efe^?Wcc$Fu>sb2i_Bw`$_R(7x znW2&Li-rdudnbWQ4^B~0zLqn@a>`BaFM{uEt~5oN#mwl?35nian*%*@&o%S^0E+GR z_>%hS8I-S@(=Hov0OXKz06pvS&k`f;J&YqOYJUF!;CgVcjHxxzFURuK<~Ns}Oo|zt z;NStb^sOsxILjI_ca1^Yka3ZoG4%Xv@;WN@EqCVrfAHt@ok_ZM+qa_rzVofq?QLvk zjw?$`gCHRNqFEFi;P1i_fG~T5TbI9Rhe~jDfg&;346;Wq;g3+efCCtCN!bCp*X?)K9DdTp+*=ik9bpDdELy>;L6Js071 z?b*>LhTi3t3%iJ*jc0AyUOd7Vo}7$*Gm7`kBrcg_93k+Q=*J;*k&6B6hvmvRQG+igblV97$ zE@3P#BPblihlF9+gt05AD7ac~-#61&>*?0Uxhx$x^F`h3b?dghG)66lhrC;NX3J;deJfLj-*LE!Z`fL) z$NI);qjgrtAnpgA3FK94O%vg_g|Ft+JWu0`$GK(l=C$yY46sUgZ=UMp<2$;l#7BQh z_{yHfisqcJeXVuts{Aai(&yLElbU|bc{KL#ef52MdHI(fdIs{@k|UgF{ZfuN=K{1K@!yFptgUt3I@7`SFgv-D*4M*2a_t-*50b}ku3IO! zHOmZSqMN3}12S$U%8n45MzR7TiqD>1@y0R-99FgUhni4wvrZK_kS;rWr zoT@D^r(OPEeV@$AG-<{@%B$;S`g->K3YM3D4tzwp#B{{T|1}!edfN+%{LD% zI`{tofHKp@v0vHArR$F@uJ0g@M_)E23UG`GImaX(Pp3|6ZpIB$O|*R^8)!aa;v$(x zIO)bn9*3NEsBSI3PQT@@%|E~74wtfgvVBW1U0RK7>KB&c7K{SW1DNFpj&tZTM?U`5 zQ(Dk0O17(^YK$V9KbkT&Gjc`;KylkX`KqX#qh{}?uFua>5}X=IF5jue>fRlDds$ZY z+E`{r#5XJpM9J7;PDXeb9Q7S}sO+sZ8$Bb=w7j>H-Q0<7nS)B8Vicq|))%yu4x?6O=dzphNLdbE66CIDJ9D8R6ITfK0hVCeCZRBM@ zggk78aKL~*P=7F}U;9^B^KC7PyzxsLJ6ucs+=0OS z$G2L`@h#QIhOA<_hewA_d69${H>7P?@HmWP`egBdE3*xT`oxoq_49AH$nt7VR2MCt zx-PFxdVg9UHhA;IUMHT`U7|~yX^TbYm>fpIxY~+N4o*gRB%E>9yspQ?dd1$O4W^%` z>Irc(FjZKbx8BAuI&yLAoD6Vl^qd9?r3yaeb?awzzI%F}Oz~8pn{!EP{cZhvo{ekb zZ;YM}(PQwZi?mBG5NIgwk!fBfg>E50Fu9ILA)+{72bSRX9qPTtqwo)1@SNTlk@b&< z^W9vf!=;4L>lRYXiM1mv#7e2l5T-}LX8KoLDg9bX5R&D++*7@`)irdw-YweiWOMU6 zvG(|1%F%r~+xoTkIzI>eIrvwkOBSc#{{R$e-Zj3GGvr68>lYdrX$Vj@LXn1S9B?iM zbM>yS>fhrhizAawylpeV(MF`fYiATD%IK~_q|Y3Nb^v7M{J?!F%5bdQ<0~blwr>0T z&qmYenp$_%;b){uc7J?cVR?mrhS!_)+6KjbK~qxBecqpP3|*9ahrL)xJWb_<=o1PT(-2jy3}rUn|bba8)781x6`AR z4A<)45r{Q7DL7!7n{ZUbfI<446MFd z&z-U<1;!ha7-fF<9jmtRl>Y$mvFz>jDJ7N&V*#z>4UMvJNp)=RKHl~ERulK$^M4Y* zUDcEQ7s&V=RY_s#soUPB+&gIXPwsF20axQ3dj5rNVdFt04BA_e(c5ngBs>PlCjooy zADITM=-(3Ud~p_?XQ4ESEc+Sam>(?_PEO?dy|>OZD`BcAt6ZeP7zs zr;LZg6w~jftNf0?;x3Y(*zjr(aEUZTNIn24LD#-qs}L|i2N@mz01D;)7A2&&)97m$ zHwhqe?Bx-I9OnT?1K*KckWu!p(f$XeMs*$$KF?q4=6Zx05YyV`ONY6a&OAyBv~EG@ z2`2;j(wlkbGDWAmZ2-HUFcZkzfyQ!w3d&Plj!XLWHk_Zd)bo2E65M!xT~|QTtRuI9 zCJ@Z+A@d64lY!WCjs`gc2DpC{tPgc1j134a`^jWw!9&l=anGk-_4v;i;wOm2RfSfU zD`|Y*{{V6QQ{jFFo)ZTQMJvB(l%J|gPfPy*UAgwQ2`GsW92^G0UB9h&NA0+Zjuf1{ul-o+^qnqJ#iF{io;b6~jh%q#eqg+w zc;MCBtxneB)_pqIHuBqpHNz^EQ`2rgkQMqJX~PSG(bxX%<<3J`b|5OM5{PSOTK}u9(DLq=b`2H$M;w2a@6a20Hf5AClh<+>6d^@7~mljtJBrbO}5=a;T zNcl!U2c~|N;{N~$?yvku@e1nZHb||aQ+F&ADBYX|j|T$>>+e{+M3y3z1%2CkX|pt; zOZPRg9!W3j=6lAe;s%}KX=G>^f-+cOl5vatm0Gs1Vq^hX@+Z;viG-*d3-w|6`o_s12_PP22HY3cq)v5UiU${1QtbiPY# z{{WxhVfZ5HpwcxD9(apY`!u)G%(F*41SE0e+UkQ`eom^O7-Km7n%@udD&Cyt-^bF>ddt#?c~f z&u|Di{44Y9TXLFJ9g^yoXKtGI{;Yj&9x5=Crmp*6zfIrud+tvg+(4Hy*?Cf0 z!y$E+NOrLUjDk2E`jh$AkB4u(HENd-LmlRyapmoK(q2z;Iu*(1s*kDZT+x&z?#b!t z-_u{r(yci-w+r8|U-%t-yt@~)n`YE)F08F}d8CO@v4&<@q>!8f6cqqt8Oi6+5Cut~ zX_{I_Z7nsAI!BQd*vlgulycZWfmai5&qQT@y}+rV1zMwP%g^wC*FqX_=7Ns5>7(`j zzeA?+PlvRruPtr7Z+RDor;-mbCXrfegit_O%u$sj^*EDh$G^4vD5sK+gYr#wh4(Ci1ccN_pdU~5Xwh6y;UH)~n#uD#lS)yjgeRvf82YWBVV z0L#_u=vmkGJqN^zb0(Q4m!|4*mxg<0iYA8O3}#p*JDVVb@<_+mcS`1TTXcIHy$1gP zZ2m@WVGR%kf$CI)j^yx9s^+}9kmqWwQc>SUYdx)XzpvnFN*>NUi9Id5{{TL{{XGoC z(<9Oz;>{&gis?d|Wj+<#5P_oX88U-!5zDNXy2ZBBR zoEnPD+eJR!SMS$-PN_DUl3&;L{W5DkBgI--OPxY%Ni8Rhnl^S~3CI}8Tqz#?&V6de zpcH8(5^P?>DBTOiwBU?oPu)F0BdPDf2DFwQ&BeWUw*5Ojbujjv%}OYzcYCQ_TdtF+ zS`#UZMY%^&j=9HwZ>D(3#J5zoZ?fF^ESs2Ykym)Z>z`ri!0V2pxTR0`Z7$dCx8QFD z8#KC^7dA6B>{jsJOC7(MBt}TfZ5cQ?>5x6~-?$a21a5AYJNZ~fzjET;N#nNU&lw}A z$>0vXRH?b8r|IX?>*v(kO*E5xe_z+!&$#X{EQwg{Y+yG^NZhf5jxn6$`B8s7>udHm zSob~%8!^s$dZ8|yJTxcPcK`m_qlu_#PG3q<@ z^sXCIz12KHsZFKnOp)0}%AQ@L5fT&7Gxz!dUd(ZPv6V`XNdEv@{{WHM3<{|y*ZTc` ztqqGkKS$7_ipmRnTbsEQuJ(&?L%}#v$>-Pc=~>$Dqj9I)qe#~B+(_RotVjzUK-^VM zPCD{`!nrWBt&FOq@2&nz?)+I8tUM@3mHz-=*ZeVAtaXcM++E2vx`Jhts%7M23Bxx4 zVD?=8HRhiZd|`g^=JFdzT2v55?;}5!J(Z7Lq?6AX8Lz0z>C&BarrYxF_w&=Iq4PND zxkm7h&+$A@Uez@H6IQd2N-=ZfmCy|TPhl8)DI-z{F>shucNQgVuo-;%rh^Y*=TU>io*YMiQ2?_qu7P;6Wm3wu?2@-Lv1vbs0b{u`Yca6-+7Pru^XatjkMHbYIJ? z_;*$oI(P{jmU62mK{yB_kbJ=P2a$|&4R%v&nO*y~>g?0o*S(tj8Ob?CMXHx+>2AJH zui$rDH~b>j*YWB)&xg}bmI!>+Fkcwn_aLY&$&`y~j)0Nhj&X%;b8Tzl%biQX7Vskk zR`PCc;}JU#lpy4ZiFn5&gVVixn0WKljW{KJ?(flejr(5uKAI~YPqV2vCsDT@w$|M` zZm;sS_h->Q61Tt59?QiVU9@*rz9NlczqIlS2wh0r%nN03$7uv~10>e2gRI*4Tg0~T z+1Sfzp=vXgi5hLt$3A{!05cWH0f0XIN#~x#n*M#_yj&_{DmZJa{O|t&1LS{cczKsRHcdyJS=oM8Ux(&81a_Ou z5^m&{1RM;XW6#o--L2zbioh})<+28Sv7WW^bfpC(<))|TGfk$Vj@Ljsk7R!Y#%ll*=CTu?$3GkG#8ZIsX6}`)qY-LjO>hF@jfY0&;|@uMo8TwWg;{{TM{ zi}hdd8NmL}PhmfYQsL~;Z)bP8a@=KI@}!?}iucV$Y#@bXHkQ%J93(hNGl7nyJ?r!& z=HW&uzlC4!U#a*$A}WcCoQBApkoOz#yJaPKKy> zBf?%HveDO6WOcpQpLC4Q14jxe+m#vWdSvyjVFf%~roPJjUW@fEjN?ZI6;pXX!D{~i zM0JT4zo_b#Q)>58MzBfAxGV7S7jB@b;4nTx$2tfW{)s$UgAn zpgx!$_3G4eq^}pMUyjR9Q_4<_TGZf`mHu{DZ~g(-MIMddF93+3M7EYVMa=5vFaRXs zKvRK(k=DL*ip#{G7rc1^@a_C}x^|f$xV(n)SB4}YhS~y-ag@&Ef)A!^l2DacsPkK0 zeLWwMr53+?ik8VW=XcxY{{W_RemsX!@gAjT;hTM4=Gi5<^2LpsGsF{TAUMI>fs>Aa zp4Dx%yRA}bEvHQydpjtS(IAH4#~@TBN9Dd7k+l8X07ectrHqSmX+FzUZNK5pdTqj# zQjN5}n(q4j+j^Wvxua`(9;)kgYj~CqA)oD1i6m&Ez$XmK+kS4i8TxaccH+-N*7X*; zHnunOGzue9^1uPW%i&Wl4;cy$bI^AAJZ>HrahkrmX!hx<^L=|H^*)OYUCIh{-%VP! zop!qE>A73Q8bybP%u!Eib#HXhnGzfADA>Zh3}IR@?guz*gVT)SuwWX6^_$sCqr`C_ zW|jnK$OPc!fF$(D`MUG#UKMyLOO^|_MboaGJipBEr#nNMZ|-+rjqd#Wo#%!;F{WtI z%c|>4bas-}ia^&cWswg}vFtB{kGy*0fCfcjuZgbhr*`m~&0%3AVm6hoO!s7hGFnm) zsXTnB0651`4Q)G7k0dmfy>{!@*Jazeofvy*xy?4Nt>^mN@MJ5d>JkNeyXmBwd=PE- zJe$bi$eX@SGINeHJxQ(Ax4YFe#u|mpQ>1?>XNmy(M;SRAhki4Ty^VOYjH9aZ{{VyJ z&rYj@w37b5UzwW@i!P&L_BQv>$rcC<#aY$!@~G%~W3MM2_^rQ(_8uFwn(EVCzqpQR zZ9dUvm3a#ROPBakP z+{qbrCMHaV55_|R4_uz!wR5e^tuEfXJ8a3NOO>RyG_>oTLs8L$w(!L9qJH*HSjO4g zla8L_IPIF`uVK`aRRa8FEU*y8UA^2uB9-^t(9(v%aEihF-w z*T~W~V&%kF&-P_i3d3$yf}Tz~bDyU|dtuUecGpjFsaagiP7C=!osE-&jE;EV=bxd$ ztRlUfZms!#D?+U8Zim>`lSeZ}9kfo7#u%950J9#%m-o9q;6Ek(nM6t>?7cht$NT<#HQ>201p2E*RP%b01X*S89Fq*q*kw|f9tuV zbR9M*xt=-TXNCyqDIkb#uVAjdh*I`iqrdh4ZG z;pF29Uh8$I{588Aww5X_&+cOCtD@<;UER*JeRX|vI=__^d^7jJ2cSN^y}Nvu;|qI_ z68OShV_2CWwXl%=hQLZuK~M=hlzk51e>(U0exjV^UdcOJJzs0<+o#O)vkDxmk?r#S zzu}KNZC=Ymzqh#8^vIg-F(=vJFXg6K@Xg620D2F6W16^^`p1m~w+F;pLI|8m1-!Q~ zSu42ffW#KZVV}evzot;73r3~%*4j7uCf~__!1(-1ahEhz`z71&UU%)$8X8A~V!AhO zo-m%(Ads@#>1p=+sN82c*y@A=cwkBAkSd;`;Gc-5`UBzL2l(T~5QvpC{{RU6*i=s7 zs0CZ;&||+f=vBg}B%=#z{pndH>2$B;^m{W1*XM3E8eYE_-MaaH4BGI4U%NzF~`e!E|`mifI+U31{<{vSrZ zmq^z%$)!6ahd}VP?x7hg%7tr@4hOR29@(!T@xGJrrp_<;M>YQd75M)E!`E`iw+?lG z2ts8mw5WfYreld+B7;(Y;gYcCLBYw@!0VlvHoBNx#ka z-P-F^dq03=iaXW0)MiGt)ETZVR%`9@PdCbC0BrfbU;QB3?s#Z9H+1=r?4>SPWw-bL)}oUwh38m`kgCuGYJ2qw1{mK1x!YG4bYYMdaEw!vg%-JLX}EMYZ%!rb#ZC8 z=B#^uo^)9(W{%qKG>$}apJll6$ZYiaPdwMpnnj0&uf8H`miqO@$eI!aW=YIN2su2Q zWb^I*95{+FmLYS0H~!l#{{XMd^m4kDeU#+|c_s7Ju7|#8mKPVgY*9yjB-UxPEDsnX zZVv^3`G?c3Tk%KPJSn7ax70q%GZ2W7s)FS30wDhY^$PIw{6uiLY5ey6KSSy`R|P!V zGNVQ@zN+c|H}vXwPN{u$d#OnGw(J`ug=GPW?oK)!=RV@IFCtk^)Q}O7OY*rr@$1ch zH)GefsX0qWeV6O^{wMb~T}n7=RO!>%CH;S0h}PP8W6B|aFqpwBocoHmV`{=jd0}e0|hx>ViLK(PBkshyoTRR6qwEIR5}Vnr5$mXC=Ms z-CepYQAk{179$7d>PN3p_*d(yr?r!udj9~K{H0!-P}iaI_lER0_=oW}D_PmT!xh(= zDQU9miZC`3KEB?S?*1s%u5>BbXoTQ=X_r}>#? z3Qv-f-6X#AUqP2nwD9`sw>NMq$rql*mzCpyJAwWc=3Wk)Q1PdYbsrQ>9HP%pj#Sg+ zbp70gRPr*p!6fA5cI#a=XD4|*ulXnX*z#ymjW*>c@T+{={{SnVWAUfQ8lIpR!I~V> zU23-%E-qn=F2li6!~^mm&NGhO*Q9s@!?vFbd=n@3wY8X%Xrq|hq+2c+1nJzd-H-=N zV-=1QnypDr_e#sA`@hY8Cw5^aO9Ko%bd;NYRl9#(wLFg3$9^H3#y37Fxxalj&Lx#} z;%D0y;-O0{e1cCs zvYM??-EQB0uTHOZ`5lgur4Cp<5=)}lYwKrquJ`O`_=`$?Gg)hmI@?rPZCS5AhuZBWms$9)Egsw}Zc{!^{b+0qtpHj>2)XO4`=f;q)_8JD!D zHl+zQ(|azLyn1!$&de%RY~?k!y>IgL(|dO4bs9H}8eKX`uJ7d2?~z*AeTrEgX)-ca z;t<1sJQ6@|21A?*yR3M_$9@lr*)-h;M_W=Q`v$Q#n-LD%h%A!EP{zPya0B-uxg}ns zrsUQ8{{Tr}{vU3J@uLXTwcVE8A8$43zps9N>%=;Su?t>nGejO$ITm*paxNK&V%cZh zJDeW;)r+ksOtH3+H_qXr%Si-)`I%hcuFj=R&b=BY3=Dk_1I6iCJr{n!} z^*8igH&NH@=DE}1wTaSE1m&GlK-`=aWE_ApHj+n75u9wzE~dIku-2hXLMacI1;Zd$ zh=%1b4&l@8_a4Hwt47hZpHE%B=5o17RQ7i3{drsSGHfrj$R(cM>PJoN&PmHEk&byi z$51-sKA_l^!^2v%<_p+-m4SxVSK2TE!5*D>;{zuHoQ_FO&&fY0)3aaJ=VW103z|KD zulRE0ZF{EKi;W*pj#!o>6zHc11%?A4>->jqYE3s%U09o|h*erJSIpQLuS^nnJmao8 z_QyF^oZ}lUE%N;eicRoKSB=?X>jT~ZP>TI zlq@c|3`r}T_5^Xk#t%-Om6W+)tn~anHD0}q6us9AT>DnttOdTyca4tHHb%V(^*`iO zZ>2Vngm~qU^1&4k9^C%`p0)Tgr6%0xv;MlDZ5#8bOGoB&_nIy4ts==Sx(N#h+T?J* z&*@uc*CS-nFJw}93Zss_zLncjyI$;dvC&#ll2MD*74_GHNU=7y2+AhNlMBp@d;Ke# z`y5ucX=x6h46IR}V#$S#asA}OWbx4R{I3O4ttmOhuSaH|%V+8SM)9PjhfNecL9O^%B#u~$OETVE4a&V0Lb+vLazP^>TJn`ohqvqY-812>jmulJG?GcH zYF7q0`N6`@Fi)W!J?rmsnw61}sd)paM)ghWP{I=uRMlRO4l5z}@uIRK9RDk-ituNDZdz9IZj@os~7 zUE_jX5w0#$c)Es=23^2pVSs^0S!oqf(V=MIcTY7bF{{SoNzP%3;c&e&@?DDf+ z^o_dqzvR4*yTd;SukQ5wtxH@wi|C?7c|1ivuHxe57X(2BB&+$XK3q9anIw~d8)knO z_=i~upy(a~)-Cj%Jo#3(>dkPl5^yAS8IpOAB$7!yV1Zaq3mS7&XvQhK?5%#OcI~C? z^h>$Yv0U-zl}rAe{{YJR*b@O`c_K@xqMWWe{f^kk>OFkI zhaFURMYJnWUewD zLR`lDfyN2OJM&$1HogYA(=DO+bK}hl?mfOu%zBoOs#)6=AnsOd%A3w}mn8AQ01$oZ zSifU+N*=9Qy&uc-f05>5DOAK-RbAEkY15*2cU!A@lx!_yiqULuCcV_3K$V>%(^+M* zbN>J>0g=GMpFz~%@N3rm1@R{5#C{)d3A8NJ-Nw>dS%^$+aT^1j$`0NR4>->tXBF>d z_={5ZbB^~{ZEDuueY#(E`kqc>hI9AtZby9{%U0XzeR_H=PbyD`8pntHS*vI|VbWl? zNd@Hl?nIK5Vgm(b3FQUnf_T8|oYz6|8piX)elW7sG~3j%wM#glwUW&p=D3-ZXJ|Pj zjAuKC_)QG9qm$*GlkB!hw)gA#J+w!3agnQ4RB5|Kw|y48ukN+}?=#c<1@N!Onp`P) ztazO*QsNSe3>IOWoab|~BnBgl{v`FTi^1OqBC+u;$BQ+)g}JFsj^P9r{2 zKzE|&p!Yt<^RFq@{Bf-7@*AtUBy>_y3n>8s>DT~x?O%#F*3U23d9;W?1OjQnxMl*T~40-aA1Z>rDbpEN{361gR$-G4k>0p1+M}ERfGKc_n}V z3=%QLesNk+jQySN-JXxFmHPeX?l^vV#nrZpO;<&Ge_cn&RW_!^O~JPBBaeQaYhOov zPV5$03V_5HDcEvK@@umJ1nWna?$`SJj(l6S2Af-NZ$C3uE8D2;%EWI>a=3Z-1{uNZ zbH+c;DvM7Ha=e~VICcTpgMh=i$0yT1wd~@i)H!7q{eEr!I-WHe3z|+1EAMZ*-*F7K zmoO?$5P5Q)z_tm;T#?d?)s0XrxZX&3%xQq!;N*6%4--wK)Vk}_e>v)3RQUr3~t4D#s8+!9!LBhEAgT$vV zhxBL6@y<&O?<%Q63-_C)-LLA$u3X!_^|iXktHU@WaPuE}xb2>R{&mCax?Ztmrrq4h zs|-l21UB}H(%^gHxcZUbn*Hkr(}I*Wx%^?7LDH!zbt7v&x_$?YdzSnJac{HgmV`tj1l~+)OvACVQ41I7&HQP{(;nOB7eUCmC)%hLR(CGl&=I?7xxg!K7Eq}O9@$c3E&$r%c9zzg4;=QXLX z_?uezfAIcIA4a#531>m}V=^K^3`JT%E06lg%Uxq#l@XoX1+m9OGKB%V0DJBbSk@kYpFeeJ97yz7f9M?th8^^Z( zJ-)E;UxsgDj%Foej&ZaysLvZgIQdWAB=_SL-9=Kv(&VM5Hs3!}3__kO7NuF;Q(D`} zU;6v|l`gdXJ5JLl@RVK)VW``(%Q6;elIms~nJ~qex!exr!8rrkv;0M+c%Qqa^{{X}i__F6wwDESIX{IcU-(`7BmgsSlwOD0xPImxudBEp6_nQ5Vqa^a* zvs^@ytAS|VeXYkQpg4G&jPedTfI5#08(BIn%2&PZ>Dy0|@;hkLjH)@oHDtB(>h$Z@ z{{Vjaa&eGZYS)LgJ%3McG-@|1V=4Xo3PiT^ zh2t0!fPSM5!NCV6zIqj1I=su_-=p7q?EOz#QFEr_J$f(F+ppI{vC_2f3;2dvU&6OH zFzV09({7oI=aNml@3l?<{{U9`Jdu|K8qu`Tj4=I&Rfh8I=GwVW-%Xm=T+#r95X&rOBl6DX!9~F@ zlZ=u04tVCDMbWHvSFwK)$TaB#s$C>PV5b>Cz;qelka+3qUUnuBNi_ceP5%G`s)bp* zrK;B6y}p0uX5Yaclc=Dz)FF;Y-6x7@n8;n113P+w*n`OS;+=0Qz2UjKzm~>w#n8x% z5xbOiAY&!JBb;PrxuGe=Cf?tUz0uyHoD*^Uf31$X`^35p){#DgE}I3b-I(PM1f__Y zB_I`H(2!0?KD`ZLXm`FKlI92`)5Xx624CI~(ghg~2*}Y|_tcVDpO*$gZSd{KM2^@;J!nip12kZA(McqXOZjw;^3* zc2Y_Xoku->fE=E+l~=9atMA*%uhiBrk+?Pee3`vzWfYO6-kypYLUuBpsz)4g*OA|+ zAo0yiw@Pjrc%nl(E+hp{Ac2r^*Es5ZJ-OtQw0SRW*7pAZfN9FyTOV}x+N!P9y|P7d z8ty5$F5}bhah!Vl``}BX&kfs4X{a{ELf8^11cAWD0QDdKvryqE!I2yr9Epd6FykIITIa`UZkp^TiHymYtxF;@1< z;`(8!3vVe`g+_cGzfbV24Q5NLDB93PX&PJ>5*0`D3gbO<*R^!vt2q0wtN#Ey9kh9B zMN^B_eustX+6Ir~8TAOI@l^UOhC^u!O>FNT2M6bjk^w(1c9B>Or+CN0mn)!nPsEYI z3`fmt=r08RZa7_|u5+Fk1IO0CP{CTB7oLQjb}a4-iMB&+#8nvqy5Cbml3QLY`Tp2zq*cXPk@=5Ps4h6|8(q{gDrg zmsGKYZJOp?8ptVQ!v!WIw>Uf!-0@#mmEx*YX(`KFx2&z@tH0@?^Z3dX6s^dXntJ)2 zzlHuNYrZs&+Rs?WIpA}e_hnkGldWl6y`;Yz+wV@vo*SnaHwfJ(`h2ft zrT4P@bkyIt(tICrVwbl%H1^MD7ncNf4jCXoe&ks|M?Hc9d-F)p=w2Vw-bw5YytgU? zOFpF?w8L<~S2o~E$ByHg$zpk~Nkbk5nr@vEi=+ zX^CQ&NGge7ThqEDxuzPGopLz=tzP2f0n zU=zlk7I;-v*=N?TuOG|>NX(F1s^b|QIpgu}Z9EAL--qGQ^q&-X4Yc*RNl;trB_)5C z8+T6}c+WY`cXQ8L_9)a=<)!6!XJzx>ZvKBR3e_hhok=|(mj0L9?=M)78tJoKT;1t% z*!XdxVQ+PBXPlAFYX?NT)byK=?d=m!lG_u-Z8TOfu$y2}zXt>+ z=T#>h5)KKkYY$Si)Kq=uo%%gHEpM;ss?gwYqSV`d>tB2GPqX>z`w8}P^}qQartlvGLy0M@U3dGmmYrX9>1{MOY`k-?+#e|+^e-lfnYPpSvmSZy<_aJTT1%6SOXSmFCB`UQvfAIGCpU`SNM*T@;{)ahK*>D?KJ7vx19Hc4$PK^)*RD-`m20TBAW z(~NXQV$eq!A=*|WgZ@oVZ)_C{y0&F<0LKS{c*joFmL8mHHz=)(#7

u9qz=P=Z{j zE)ZbI-rWBHlj&A;_X6iA(yZVDCF1~e{C`^a@LaU&MJw<9Ka3(d5pXxsYx&Kxs@UW)R& z{2%F{*DGyr=1UqXI+Gb37fj$Y4!O^B`qgRWlW1m=MwqcE1b7(h!4>0TtF;vlw&`z| z_1|;SqfJfodG&vPulW>+mS+xBCNqpL>(72E?k1NnAua#}Fu*)>+7kYZ`dwJ1Q5w-@hwHpw{> z{Hj!s?-S2j^Q%{>O0uU5*)8<*T~}ZDW2&5K%8RX1-t+J2{df7B8qb3~YvSc=O;^M^ zCXat4i*+hpYZj1)kq_?kb6}vnr86wiWM+}KFf-t7q zZ;MTe!!1lP-_cCUZ(w%zh|48j`B||YPN94rd`T+43i`nMq~GsG;F6Fxyh+V!|w}t;wiO{0pFckTV101!h0zH z0JLFbQdDh>gt!<3CNfS4`D@6lM%RRvnmu*4{Z_W~X3C^$rBai#`@4RYZw%R8YLo7N4oR*rmfmHpqDIQnL|y_{3g^DkTN->>MbY^PF5^Ik3KeK+rYzv1*dgYfH7w~850g;P#5Gc+rG zAJ~GpIRkXkA^g{-PCHh}(&4qX@-^7}FRI2FSeX1nXKis2UNEzH+qQy!>xNzj0;*iG zZZ}r)Z~Wi&uv2xad(yr8{{TsS#cBK*s$E^A9trUWhqYU2w=-CcQrWKIUUE)u7&bcY zR_C4;s!#CuT)0VY^zAurZe2;vpQ%_}KI7ey9k+r39gn4Q)^#MWYo*)z{{V+HaF;dh z>wSMDa(dpIcj2f6-XziWZ6e?>NN1Z*D;p9q^A;Td&lo4vo-3czwOJ7PR~C?5q;IhU zGi-EjMh8)h1B~Qg9(q?5MJFpizy2Hk81$*P$#m|#pXb<>yb~^?aSo-YX)?Hp_dGHU z#FLS^3E_`Jfx+VggI2_Po|`-}-dNtiRFw!ap%^wdAp<0Th#Bcz{?>AWi+6f??WdCz zt0_f7{mQdy(p&2@+3GOLVz^wS@%)aR4)3o{-LiS>er<7J62mQ`TtF2AWP)QSlE4w$ zIl%h!lTj+JX+iDx`RxAyLeyN8QeW4pHi3N-T)m{ww!nf#jllubkTQgOoO9cboQ>O; zDGYjsnCQ!oETI5oZR?+G@$}+~m!{H|&fVAfqej^dl^V{h*EZ;cg={Q<0(s*HjxY{? zA8NWHM1>wAvlLQQh#--W0`|fDIq&OS$}L_m@3UW#n{wt>KD&0?j46weNPSkv9 zeRB5`KG%ifEgAB2g#fo!Vt*`tAE01d>0#Sz;(C4le>DbvNEu{M56svc=bTraXA?B3~{T&j5VVF&y;dSE^a~hCNo@uXLSC$~eoD zB-Y5XmV9%P%(3U!8>`ZI`C{)+n%#7FYo_}B{a(t)p6JC|r%krC-{=1T19lglC(!iU zSBFt+%}V3|WQpz)5E%B#s_Y{jRGfR(Y_scLAhEWS!=4iG?X)>&YyD1DyNWg#+!kqa zUA@MB=*aC{@x;ZhN;0*#Z&$17w!d}s(7JH4_L5$U<=_4vuBHaNKBl%`VAZ}LYFF1T zHpX;2c2z=psC1GvUf(yD$6l54=fy31z~HZ#RMSbmmTKQUJpTa9;n!c+JX>vTHmjw> zrEOP&-fyuiXk%tZ8)7-f4ZDTLGu#^VTOSH(J|c>1T~k}sH7~GRgLfUx=#C+rs+EQ% zJOau=-O;h0-$^uW z68FK^w->$(yVOjk*sRbc^o4EW<#Qh#oDuT2NbjBvcODzD*0fzVOT@Odoh;!pwb0ZU zZ!Eb8RhJ6t4?ijA^z|_G$;W=R_@-ft`tB-q z>puNY><$>gLnzAWVJOF2bX}MA`J1r~D&_%cr5KbeGMU+emH?l+4tYJhbJD7f5J;h7 zL`{r$2(Vp;J?kt*I(4IZdMjC5f9a#!!s6;-n~iJpUhlTOJrQ1Q9`Ys)5o9>Q-67+i zNIfxGclJ1ufw)(ZQ=wpRI^=WDfAh_J{x=0aXU+1zq4an>Y$q$hU%rGXZ7h%gs;&sn z1Z01OUem3W2}uLsoTErG2=w&-0QFW_JUdI7uAM($z}FdBa&`FI~QSF41)n^s9T>1$oDK8KxOmJm+uwQoJ_ zw%LhtQrg-Gt_goM`HgNk+E4ef?NPnWn@H0%2nhrt88Er*atGspHh^QlOpP|PsPjFa!$oe56OMQ^b2GK6J$ zy@yMp-3_Q=k9y!00EIuV)}U<`@uw0?Iv~d7CnKj|PrYj_HFoaZzpV~fWAOH~*X|&d zFKy(Ag>{(-aU%SrAE@MvQ}vG*UMz1d`%c8DkBNR(dN9cH18I{d*qQU z_YG>MSj!xth@hU`k(yg~gfdGLX9UDcs<9xGfDQ;b;EK($z3{?n6GyA+T8D-8H@V+! zcm1A35i$}$%q*lX<-B~$PvUk;9*XyTC`kj`c z;*Scz_WFOs-wUp@dnRPF@oW}W)4_2r(ep@wW>&^FiJCIt4o6c?);=K1pxDJ@t$0&Z zzq3aHJl$(`rNT00LL@MGESoXHpvM`>>&1zLs7KycOZ8j-09u~3D#mUWm9O%CYgf8v z5Bw(o01uqJcb^H+1|oHDw?O`f0Zq0*BxC?N>(ex{>;C`+ZgkzL;L)eHH_Gi|E(>np zld|FtybrnGfzrH5)x)-_$_hT0Uz+^BM^dNFqLcaG{Qm&VO)EwCE3Rsh$)os+=ECU| zN+N>dZ9K-x1`n4!E`a15x7q<19Os(qwXX@wt3a}9>3gr(NTngwY@$i;ZR6Yj04>@E zcxN0hB!}vEcC9K>r|jP@pMU4KZr+2FsZFNc{Qm&2*48;&DEw*RyBQ(THHmc%HC&?0 zXDdYNbN6IJ(BS>oOdg(wxsMa-Fuk%*t$1HeyH^EG?V7Ef+BV^UOiB@m$s=+c`yRaW zttwSLoo!R=)qK&se|am@Z9nUN>-tQJX+{0CS6Viub38C85(UI;;L) zk#>7)tNQ~h#Ij2gvPjXA&V{)heX)(+oYWdqHN6FD%SNFOjtd?Vb4t`G1kiQZ5y4)9<&JbZZrNWPNL8tif?3qQ=++1;+zFjYD%J z*Vk$lyr>brQoM8co=4_+ufXv1y^S>LD{I%t{UOp+s=K?{ek|3owzo&!A~U*t+uU{M z=~^;sM%vIYi;QQ0IPF{&{py_0UdJS&>r_eiF?AcMlGKoVuvn6EGm<*j1E}0hsFPxd z{$2yh0^l6y130fnl|{`P?G^qIf|!bI9kSj->kW)oETA_;c{~>q^ypV>gK| zd_k()?ziy$oS?-FOnyN#q5>I)K0r^Q$i;oO7ByWr>?x^9=##$oex7abwYr}jS}8s4 zeP5FQ06miX*2lE?U&B&s1_>@c7F)q-8T(h6JTf#<790eHlWP&4a6L}k;=8RgO`i0= zk0f_?)@VzIf=Mk341CVdu>!71HS}8bVTPxMRQaPc z+S{+(w$eq_X z&*8mHCe4uxyOpFkNi`kqwe4%$TfWPtme+oKRpI5@ z{l6vV`n&wIHH{+oQnG7kG&NaJhmgl|im@;}0A!86Vh1@q1I{{E&z~1Q5^DZBx@YiL zg)FXaR#^oPB$BBt3s@fagK3}dI_M_SiE$2xd7?B1{E(%*-FCVQM0fOwq6DMzjE ze?RL^n|Ymnmt@xQ!5XV7MHo=ra-*klo+|vhfVuwwmWUhzr>;orUxL@hOWL^Ke^dJ# z1%QlbMXh;I9a`emRz*>}ATY=P^T{0Gf1Z`8VdG0ki?5p#sa!Tl>7J(t>0R`(Gv(&$ zdDZaHl$=vKeJ@edJV!E5E!e~e6m7v#j^F;jO466Zx)!YiLu^Z2DPW4KrA|i~^zHuu z>aVK7QN!codY=>j053!5F&NBFTTv=Y-Horl-{w@0!FP7%QH8 zuOmoRomCo+R#tz1ksP{x+;OGdya1pFctCzu?NGy{Y8NV9?ImUeZPY6$`{L?i$}Khx5@yiP9-Ht9!ind)HaV$)S6yD8jBr(Z%@)Opwg0}InUbnbn< zs~cF-Ao2`PYq>z)=N-sBbN+uS`RrQcny*WxpXPlw6-~wAt34it9T#8Mblo0J1t(7~ z(nY$B=UvDFW4TxX&tuLynzsZRrRJTf>L1u*2`@^v>t-@Y!7wtQoFHw)U@zfc(0nDE z&ojYO*Jbn3Ss%%MAaLwBe>AAlX-VnX-QV#403#AV6~PtUSJAem9h@pH<99vb5=BO4%lii zO{nVHRMs}|NX;$W7IDO}NIMTLin1^#Bomb#vslGLk-J%It*x`}I<8PxzrE*uZnWvI zW@l;!$#p;ND;->mqUB21M6yLAN4N=I6>uatQ^r9AatIZb;%^t|mUBmOde)32GWoJa z0|Z%ig4j|31dh1eIr`U=TN4Q1ne#83-q+Q7?ceS$7->#PMO*#_?R)j}?b_EcZ1o#` zG>aH@T^?BPrD@(Jx|hq$fFHROYylqRb@#7E@I*c?y380FHh>nWqEQ%&8CyrrjK7Y-rBX)zl~eN`dqrR>G9oL zmm=mw(ybs6;F0^>ruH2<01gkXD<(~L4R&8X`sc!`<-!LVO_jjxaO%sIW5*-cw{8qa z@fwm=@3Z@#;!PP!O;wNK<kG3m#?T9Sa>bSz`Cwlw$krv}IU}OiLIAxq@4~3k%`CG(<59=ogZ31brh3k^ST3u= z1fr6vk_ZC-)sCk_nz|L)mtXpu#h7rwmpR7kNPm$Mb~#>ZZ88&Z#bb297Qr$J23NR( z!qiq5fGKpQ&=&v2?~rH`&mXP$IhW)`_RODoGt7v!F`07KwjI6Gf3 z{zW=%TavkTeQ=3C8q_F9<%5fE1K5u+BW?k155YNNZSR#TjW~ZBKk4|qTo6tPFcWl` z$G>BTl=z_dGW5UjxYI_UK|Y%@mfnundMhn(clXM%lss+do|RcgNpJOA^hUsQ&xJ(W zHMffpqVB zO@eFB>u;+M0|yyUGufF2IX zzFoZ(A4=jjU0a&kfA!kF`ID6W0%>MVq=tvz7m&A}^PSXXYmxa^7~;sBG4X=rVBc`a z6{JdGe?nBH`o^Bv<1KsnW?OH8vzAa2?W-F915CT&-a$V6tX%_V@R6s2ce=Ux${Dik zcLwh(xePa-X)!3*koJ_G<5!tq-Oae~8!YcxZ40YA z{xJm&=Vyn(X7*c932~_W$?7@2pu7|UqK$i{pLz8|u(^N!xbd2~rNOTcCQSu~XAELq zH@xNorcVJ;SC)&13ov^(pVtqa!XK74Pfxse)NP7nn_OU1l{ zaSyC?7VhC@v7SnrGYMj@9JF#GtyNv|(G3c^4EhnDA@Hl1q~5Q2*FWqcR3ImKk;%81 z#8Dc-g$x($+9++)hkdU#BQ#Upoh3G)U)jlv2>Au%^?CBnMm0l_$H_fS zOE4KH%h&0>rZKs6#(V3Tid5T^F)J}r85?h8^5@V-j<5`ql8p5i(3zreSyTLf?H&}E zs+0p3u&d!h7`Y$R-i3R~`K?5SlM3(sGlm&(Q6& zp2OxZ{}qxZB1klhiAOB}(zKnbHRxnjiO3|r^viojp;`lQdPeDF7(}q2KgxaVOyQ>M zqbwvlSQ(|=gnwpd!46p>-3+w%(Cc1X1=(fqh=b3odapPR7>KyQZh)hl%zS{_{Fv?a z^>4{7KL#e3|+UvhE&3siWa-Zbm+ zGn8uye`bz#bG8;G0Y)o!lN9a*q2_h6Xw%t=MA!!Jj)V5bcfJvM2&nC81yO_vqU zXg8syYkoNDppJN+aY^i3+(R{D%72O%WoJ0yvdl-{lLT1 zT8y>+W=XqckG7P41$G1mzYBK0H6EHdm7V7092%1mo9MOp9))18TX?#gGpBiPXz=gCD`i(PASgY-;Vj>=D}_nEDLin4p7 z;XPI~Y?H3&mRVo1SaDr1dWz(O^%IOGXLZ=btiL3+Lg8m$#SB)yVTpS(l+Q^|&mgHa zX0$m=&hxxgxYQ{*LzAvNXjxv_dHmAivb(^BnPBoW-Qh_WM&jSS%7$+Ub-gdc3-SRI zrxtEQx`-3n!J3YxH=jHjMgz|vf=^=e8MqDnlYK%d4M5=Rw}aoA?3y%={!M1e0=)jH zNuX`+3GtATe#v7|tx7XDSuokidDoKK05W5;V>+)c!ITf?BDHsM$)10qS3EstR=Y)g zmSpR#YJ>gd^ihd+eWPy&&|w)xj@5Xe=eFzKswy$Bhvk*S(yBBWITO?Q?l$1CMQ)f` z1{A*w2D>+!sF3!u@CtE()Wl6Zd?&SGmbU$y^?40nJYSl z@?a+Znlw(})fYG4P(R*4`f7Nb3m-gh<1uNrP~UCpj`XgXz88dfUIW%Xw&|spAtTyk z+6oDukvP1-jL-dnHjlfenI%8nmAU`3J{pm$?+hd^S&8wgd`pj~pMqs$TtkbyKlV=P zx7W8efs`g=+Dv9*?+Y_U2<;XSQMs&^Z?;~l?`pTV7KUHiN=y1P)aY&3*6g;g?l@{W zMA|z07ZHc{JoWwcrdf4taAJ=m9Ypznp?bt-HaOBc=iw!n5)scIVWI+Qjuh3iE#?UE zjWv#yD|2AePP-Xk+iw+}m)`pSY{r?8yWNi`p`}mR%~B}W7*(Gu28mu|?Z||ZNc8pk z&;KFASrmU*BYa>FT0{TvedtTD!nqc*g`{MnpyZVa_^P+o3dJB6f(Deis{oKQ%vBE3 z^4UzSz_V@z;%R}yL;lzkfG8PE?4y115O(2}aAsnGG>>%c+lXZS6W9w`&78edZ~kH6 zw=RiyLOLg}g3|C5blw`J5O_G%ukZq}{5mJN$Ndt(d@n%TXaY5c_oh&%%J6(-VW3$F ztdrspk+fU@5wO()B>b+E;^&9lFl-btdPxlo9JUHk5QV&))e4Qw(o)3P#I}^0_L3Q1 z4MplqcWi2Ur7Z5pN+I!&Wk~|bf(Rm9CDflPI686v1F>ixHdOgh7{6G__tIyfih`o2 z>cSgeMdujd^A@e&MC>=e*KTrwwf_D&5WgR@SeE*0zTG$U_6;PjXW-<-Z+4j-Oj+>C zvON_qg+A#}ie%@=O6|QbiejsDLDFSa$N4^?gC9ROP#H8n<-&Zqnhj7J6sOMJL9}nX ztjs8{;-{5iecyKKmYgRRvuiYapoov}T`!eHlZLfF$*hEBY_UjAY#qT15Sf3>Q05Cf zje@V}x!sDCJwc7~q?Un@X%7)}1#v-I5M=jSB`GNxmXKfs+rJGr!}W*JTqbu(%rcIG z!zJqpH)&2F{uHY9d8^jtx`g~`!b)_u3^aBJa0@jld49;)! zGdKuHN!_I73~o&S#n;yIsPXfGSsdLmK{Wyfp}Lkf=avHvA7o2wYAz87w=IKJ?T6c# zASB}>P|oc6&s5(~U(awhbxMuc)WNQZp!-~S(NxkV)ThDj>tA8avj>}dIXj_mOHv1R z(^=FDyn9AHTOTkIwqK7N6dmbxf+$e1x^QG}1VN|46&T*dl&EGkTInsWc=jZM)OqyW2V9 zljFO9bQsiVMz>^-lYUoDjd@9{OiOV6boUCG)D4p_WA4h?LHXeLQm?aOpvBtEJb93u zb0GXbf-2Pb_U9kjM8K

Z$#mD{IjGvWePgNa$nGs$T|&Fd=zf6i6g! z1vzPbOk+9w-9C8w5tW&M_k{+=&iu$k^FSYr_+6$Zk za`=jcbBJe9xUW;uUBj%j$rO6acW25ncGS1Vr0{Aoy7cc7PkBSqkNZl>BJ#;n3X4^+ z#^#0qVx7T#Mn`~fM_=h@4b*2I^_-KN=Jt+LkD1rD>)JGF(CS;fbKJ!^8E-qt?4|l+ z^Y;1M7CQpjLZzTkUU-6mSrVI+b&G~SFpeUopX^^J7qT_9!0d-!cONXXN#X0*R-mRj z&yz5$Zfi>uq-lf9*qNI%S|;(Lh6#n69TLF49cvhqTW30Z?2VF!E!@ht?rzJMy!@aGe&Gw;nz}wya3@UB zGDiHc*$ApPLZ~j=V@;X!GozfJevET;X5w&rrRvXzx ze=#E{Cp|XL3o^w0lg}(7qGHx&@CsNCxyfv<*`Io z%?S9-L*x1K`gVhd2!40L(SJ;6QAdP%A&S?gdYQ-1P~-Hjz5nh*20k7;<+6Xa9DH%B z;Fw!|J+!Q`DzCh>Da*^0y)im35=21pDMeEDH9OHJ!-!78-yFZ<%|$Z7lF9Ca z)VakfI=zP1szHD1Gps#~2#x~9y9_BS6Lb8Lzb5D1Aw%v;#k%^XTy&7)6a0S-Kg7;| zw%{oXCv@uc!=xL(YmxgB2X(@bK_d5+30a^XsbaG)50$dC_=vM!h~}kL)xry^-KD1h z*{qxNPGagn&H><>zS7_o+D)MYAHUuRK6%vy-flWv_VU0+TX9S|pP4P)wm)hW@Rf0o zb3C@pzs)bgNgWwv#koeL7!Q@04LDb@tvn&#Ax#xt?6B#dd#?Seu~l%*WBQ;s3K9@( zc=T~%*ie<}-vv=j!NcWaZioACgs2zT8?j;nS4CWZEJ ztJLjt!%qRp??VOEk6R=P%&V9H8~v$qjjWmk6h&51X$1ZBmRbNzX2A=DYI--~j=GH_ z&_=^3t=Cv9;2%el4%rwFO)y@VXOzj^*vg2%Gs7!7-U&LUxwChV6Z8>tr8{t>diBlA z@4Tu;Zo)U29%1c*mT$yU%LB{|>+^wU@0-%3e(UIZKL3fvCBETe*beBGrrj_E%K+7O znFZUHQ!t7SGj}SIwHODH6El$oJKUt=!D3TNE!maoI;m{vgIc#f%}7c879IDkRlCSl zk5aY01v@IOg@Upc+(-FD$aC4{Yrp9W=h0I)#2x$&&fs6J_Or3k=(#@)=-o>T5Y<5J z-MMF^@P1TI-Lqt|@aOnHcZW+1-t2ltL!N0mozO(bm7f)HPbiSZgWz=GdAjLmo>8@_ zbexfuMc5%$01ryhiw||x1x;BVWt?myE6W=2ww{vwQE!?_1zo=ypL-I}?;nGz!VBedV-M{+a)yR$w zk*W)}0dc)T-pJGIF!6jjp?BpqLJxN>(rb!jBHMrf{P6MJ|kIor%<0Syj%| z_k>QwJb)e#wr)RhMwC^#mrZ-{+XWcdcZIt$zobQu&77 zl^N|f68fH3`=2^Y(X+Xk-`=t8Ptd`Xvk9;Wo8er_xo?2aN&IRAJkPB`qzkGu$0C>J)HH54hG86~oq!Z?rZj2UI>6a{d|E0}OTO{Z%KIiiZPtXV05qGdDYXbI=XFxl;99ApZ*-Wt)br|EIcf zu8H)&*H56Z@%70UMM5h`2Q~XrS+><`r##wzl{*O*#F5s7DL;3Q6Ky!(wzBl-TZpK2PUt05Gv&7PF zFh68`9O$o|Ig14_D-QogM2poeo2fB*H%Q%6v&(oNjkfh#kLsh{GV%+PJNE6Km(OU+ zUA+{H29i1dY?v1OOahO_&VE2dGdIZkRi1KS6~K>-=6jR{GZauL1K{&N%eBba3%U5| zK=-kl_OfdWVA=khYoKCW8*zZ`hsGISW|dw>cGI$Li2LnAoM&E~5*0u|}6+R?kPrC?qgAkE~BR8FM1T4%;T zB#2P=IUke-kfzd0zScY9LrWW*FYoF;*&;vx z?EEcisSm?KKObw$Dd}b(dN|{DjX@rqpkgJi)D=uFNET!Er;g66JV>(K3p{coQwp*BfHt9tKBxDbDN$rY$L){H^oRb{l}Rbv5Ue zR~3cxiJMI~(>_P7@Hjf>THTm_HZ5_zY(DVLKOAD)n<@COFI%?t40~l_;(sdR^wR8k zFwjyX*Mvi{*({KMjyYAWQ&|c#szoZV>BZPn(}rLkDJXWU{gXe?B(xV@*qoXd=DVD$ zl9pD=9JG%{SelCM1zwpN$7xlkTktJTskQ3Ok2ydt3iKpn#kEOxhpL@Ypu8;)R&>6w z`LjfQv1~2bod8@51v}U@dkEnw?hXig!#j|1TCE=qo@=kGkDpIA>q+9z|^4JJYex>4UUnk`4+O(*K)D@d;<6}y{ z8zjlAqHmwfFrm=HTdU#i;wa-LmRa!Mf&#zR_AzvjX5?E(#^xRxVu>ET7y|3{#M1+r zVBLXAv-GCP^#KD101`G|tHA10@+19?)a5 zQMR%Ga(S3!C$yCM(%|cp;s~mWfy2cA2-G*O=f9hRAQOT9H={Yy!Co!-Z9(|{r0|4& zQ?^~gVBAC`PyM5Yoj2>G$7f|r46AV=7?Ez#K2XQoIqmfwTQx>`V#@K> zXHo_0ooL~xBlxP>DlBUTu;DG)RY(Iq7P|&z9qUf*U&nYw@DhlBA0#>H3@^0+qy z!bu5f+C=QMjs{0y&}p2R!IAuaZMpwxbX^qhA`;EsTe;uQE9Z*)nJ8U=3=|4(+Xc z$hDr!Dn&&NMv@)6Dezi3>6!kV>_wFBJfRYxHDL{ZZCwwgmiwJ&9hC%T=wQ;(V0fUC zn}w)7M7Af4XL*4m$dp` z;?xU#MOXwZPZCs6baZ1p+rkN0drtKNrRMcpF1h@-5p1UVE4gFW54%j^7=eY1J+f+t zRYQecq}%QtbC^7dVTP%2OUBe(je^zeA_f18t~*wf_vbmltkegF`94*psd)L|Wrml8 zm+>n?V*gsOdE`+t-25^~BdwnrIJ@^JF@os8hQ6X>cRY=3S36Tgi_Su>U9sh4hg-lz z{XYVc^h+)7H4&3OPu2}P;|>D?@1fMhyhej3s*@bulw<{H* z;0-b$*7Fz@&J4oZ+@+EH3ee}oi zI*}^mc)mgYdxb0%4<>~X{#t0L57{y2J^JXntqUa&=-ig!u+ z2AjFz`I}Ku0F~SD>?!AGLnPyHp6=iF#3w1n;X*Eea!bi)Rg6GtpzLo^(7(-=!HUM6 z3#-}QB&l87Wgwp}t(wI%B1&VdS|1ngF2iOOEs#L7%8srZ;|N#B0fcmo4RaQ5g1q#q z{Onv9(@;wL?qX)xdjqU|qJ`?Ev}fxd*&FaoQ;!A$FBS9f!d=T}9OZiIf=0mwXFNQf zUTJr!R^6VX7al`=b(x>;)iKMSRzn^q3_#Jp;f>y&9w5^%0=<&?-${^?2?rL=2sw!^;byuFp;B16%M=KyQdy6@bV%c1rtC z3@emSeehn=Ps*?9ooE6r@ASmYHWZIbvH4+e`{-iG@&* zb;fXT#^4Lc9rzCYV>w*#-lJQ~KZDNIM^IN&dY|f4 zhXX-<_}rvSa4Io9?LjXg%6JtRrT#c_295#%sf}EgPBU_>2K|N#U<>Fpyehdh|8QyG zieGC?qoH8D=HH5bh_?;@h=57akU!J@{Seq2*p%k&E4&aW2~=+oZNTNqe4Me3ZvX^iKhnVZW1nxi0ioWm$}Q0arF?u4Nk@26>g`H=iSFaq!7c?bXL8tb73m zsmU)|Y9Sw<`FV6zny8;QS)2%gp0O%>T+T5pW=nupfM>N#qiNlr8*NL|cQ@RTu){e# zne|y*!84XhO|DSrB3HP)L7@fR!F9ewvM=+Lru)NY<@(f2Pb}d$t|W1NY6)(Wpz*3LJg^*+*3Z^f&4&! zIDBb#4s#+$Vew!(r+VYytX@-I5Psg8nXjIcu`|Mb^ZxLj%#|nVwKoUIqE(NSKYg;0+3 z|8elEuy+i#mfM{XVcSbGP_^+c2o7uAO_@AXIa01ft(~}**lxWxPaVJCD}C+I!e9t~ z_ndLygbV*Y=L~Ni$Mk*%Cv<8t!9AO;kf&qnv1VosZ4=ZE)DNpltc93tx4pb^$J&kg zEK4MbfnU7HsfiwoMjcKzAAgtszE6J$U$Q#t8(!rZgz%=Lwt(d0i;LQFx>}DbAJYzoZ8HvRuHRYttsVzMP&2*0lQ{C!o+*QF+PB0kz>CYB}H;@PJ66O+Y& zuR4rv73|zgmGS!ZJRHJ~&^SGQ z+-wjD%05JbF-E4*C^UX*IErjv@>#8%M93dxox*uGKkdEudgT=j7sj(1#Ku_-9Dp|w zBveD4>(ZyYotrH#dC=0svb6svIv-&hcRwipaqqjM(zqk3aGM$ckv$JXF0{Y4Y{7MV z1>&s^8EB`O?EI5PN`n0{%xpuI5r|Dq1t?=?(R^MfRD$U#7h)i%W!BUL~!%AfRZXR9_q}X~>OHnxK?*We87xU3~ zFJ|;co>jmP<~PM%RXhQ5#sT>v^apy8!s7?kua(7~yK7b5QT69(AO6f&l*qz_?T%iU zI(aRzAG>!`k-OBaCckiDd;x-zu;D>zeD4|%_Ji~XgeFnni6|a0jD`ZdHK*mI*YPN! zOO>k7LOt@bt*-e~WgCwl_vx}oatR1D9KXcMMdfi|)Ufl{&g~<9%ZH5Pk;z0?E=ur~BwCXTb!nV0NV8U*`#V_|>7FB1X8X}W-q~HoVe0y}! ztr&SOamRNVSo7j>KoIsRU*;zgU=kbIM&6|8+hH$1`~m3^ zXH6n}9Fxci;!ayq(p{VR!tvvR^T z9lzZ*>mpH8d4)q52~;~zH=EVY@-A3h%9xZ|D1Mr*=4>S7giZ5jzPAbN$Ygtap!~^E zQ5`v5(u{--S$x<}yf8e@1>D3WVn}8Ib{n@JV03VvjTHfNP z{l?IxSg6F8#1HI-J{iwt>tf{V63;I%IWw^)bPtwYlEz{P>_CBvV}*ka0Q?sB3@si8 zkWY4RZ6tOpSm8;{c(W|J{?G4vR(8R1xgTif%_MNs@;lI4HdGbpZz?Aq18kCS|lVu>^PyvH5E>jpRtcX?P(-geOwyQPUNQdVE$S+}$< zDK%cet*h@;MNoXM-^87=1B9|F*jxODet*>%Wo=FVIDlMBNVKm4V`*~yuq#M2M*?nB z0KgNpK?dKBIqFv+=AT1_k@CUF#_ve43i@}3r|lK7{BQLDzi_VYkdCg~ybuAw5R3B5 zg1ZO!v-A^p2fM4k>ZsTi?}@i=i|WXCYs`!f+v&xET&XS1p$TpwrNs9+LL#Cfy3-zv zhLc~njCw&5GGq*0gb{#7zcXmq2^s@achTEE!|Gt%x%}P7wW%))#yV$>+8!Nk7Lx1_ zlhs=;sE70f!t*LuBnR_pJV&+l%>08!n=1l%P`z21$v|HYoe^6%1mEvY*GghH8V{3E z<9n3%(!b=Ot2DLp)drfmXqv2)i^0kV8&mo|y6U>gff9uyWp`@x3W;+Q)d#SL8k#!d z4^cG^J0rxrucpvZxZrrKmS}+#%y{ zC~IofpRb)cyhOT~UbA`^XnzcT$Qz6*n+0XLaeYzM7$_C_vBq#>_u#HpE~zRN$v@Di z2+_f#l1yQ@A%!?aJv0wq(3m^9dwAEV_G3olNCLh!4jt$hHy2@bN8|;q!B!M_5>uo;QY8oj_lyk`bQU#|++RnVXp_c9L- zP**T;aj=t&rf8SY6US9RzWV;JvFuQf0djLl<=^}IJ{v#MFUcn(mV~GWL5C@Mb%e#e z1gPEs$iNBb>$Q9rZq&$`g=OIp)h-KT4fh8AT~-^;`Ahp(vp*s{M>TC}jp8=1$;5O)>0(?R)$$-kB~!Nv1C+pnpskpBptViamdOBvuZ zkTQHb@2icS}^pb9EzXpG++1vqb!cuL;Um+TyRYv?8xYq)=J93!x{zP`X!eQS*IW&XG{Eb)fw$+~R2`pHQg&-6MO@2i8` zXG7>$|#y=#6kn!*mh0T08wNaTJYQn#qxD8~n2-7=)zwczQh3xv-cfHO&x)R=`aT#BHMH`E7w{`-m~kO3 zPOn__8X^Z@j}NEIKKqPb5E%I>NpCNQ4$_0Yt^uM!uS=hnjdxBZe?Mo9@RA9mMcdp) zzvO%luW38DRWO`fq*BUPpUTslTLwaLzRQ({JPQ`@_$qZd;|wH{;=QOEDZE^o`z0Qa z6%a^|N#g)r#k%6VCvTnS`z%zOd|=^<765kSnvyd9_VHJl1Dz$X#&!{e9JZU+j^Z~0D$$?f^NOqL5g*D5 zgRBbQUFCN3O^QG5Qu5a@I~>kky3@j-`b%QdFc*1?9;zOXo3z~DKw##$+zn5 z&JV2@xBgSU3%H=i23&qnBUIV>%~V@vquWUrqg8Kg{Y(hg8j6{>M?pW+vFjSjlVTAl z$LF~aL%t8KrA2b3qv91Pj;8`%80M}@_C2E02xZ*kdp0jWllva{mN+3HaArdio`Y3D7mbUcr{F3nfF_!G9vzLfY&x8XWKum5T)MKM>|OKm+5FsHHi4xi)!GkW0h1QAVxAj9US7n!HB4+^f9J zVy?K-`WuV3+7aU5JUOlMp)qjEd1z`JKMb#@ic3r&AeNzEmSLTa*&90 zmtbJ9v*JhQ)jqgVBMy2oCiC<=XIburg&VXNVQ3|#cuKmDPYt4w{WMmfxI>H znx6x;^`<^%r7g)em1pOECdee0rI^jWHz1-f_Tz61L7lwz>YZlTJCOUly4PJh(czSN zYAFl6(XumoD)bkIjxX|l00(6|+A#eiQdo`eV-XoS5vBAwgh2-=am_fJV;}&xDjK#j zd)V9!gQu=W3ZBMg2lX4}7w@=~L1Zl7b0|wk+ctEJ(btG_W4+45jZS5~kUVG7rQ_hh znx0Z;as;(|%FB$*cPS0ql=7{zIoM>T`JwU=+guFwg-+JUlj?>JdHUlHa;a;ip9+aq zJ3>QiNdpI}cCj4j2`x5yKkY8ZyIS=Fia%!B<}>o6ZPXkcS^qHEQ2>b)7Y|2Fk7`az ze!nFT2P@S)s^nSy`oqhSgW^Ii&$s^+@~hZTyh^Kb*S*v9KLRd?kT!|PQgw_!&a%Cd z-lredYIvcEfP;b)CVKAltdFzQ|JGf$8}Aazo+pXsLKH z0_A2QkIE<7()9fU{k0UX8(+J;m)Fwjv1)U-7ZkEEE#)@aE9gA#$&LauERg?|*B?xd zMI6?y!T!_9cY5qP>80wr$NqxO8iWyr*%i<4IelW)1>oGvd|WRUM-w32Ekkk@ZwDvj z?^C}Hd;SZ%_X@I{QF7SYB-p5aTbtdJ0A_OFO5?#emm%lc-_Kk6Ip!^+c81n&DtxF& z=TUO$RThAtB%B_7v9I~Q3SU1ZKJ_|qoo=BW=LSuB{tj_upBM2UVu^8~<+FYqr}LbI zfQB%=B5UUgmiJKTj|=|{3X zerlR&arR%6)tC)PY6Gz+tsxMaU4Yjf%dB(A6wliQM_>r&DkPRpCKk2|d>Nv-9$dJr zRzipx|JEFKE>!vh*oC2 zk^fHGQ>7_)zV3M+B`KJOd2ViC_s4rF+J_RjiZ9y_wo(X2oY@B)+Vrs{Wd`%K#wlO7 zgDH-}S^+0{cUgbZGiH+(-68qyRZD$mD#W&QT#x8o4$`%Uw*KJp0ikLNlU&>s!gAGJ ztnVAcYqFv=Ap@cz(Ejr3Q4U9XbbEtT{f6HL2h`T<^&1oPhl4iublqQ zI#BCtq6^#BeX3ml!4;xu*89tGI(@jb)+)!{E&KM9h!>A=Pp^$ruw7kwR#9Jch zV8MQODJMbwcV#k2Uf`*mKiKSrAq$$*4L_?> z(I(LfJDm(Yyi(YJJQ8iveAGZqBW=+^u?5kIN;LX(9sBF?>$gy9Q&F;i&l~9J<-)B> zeOBv?zrD-JY{%yrac(TpyD&YU8`PQ5S(4$VGg8}xG)v+E5j%lxI_Ud9jW?KjydX3$ zP1RC`n2G3&d1v)oh2C;`x^wB}@*OGKZ=!3eSW{WX!s5=d{pf*p{Pn@~M>hlQ+y=gV zXa-mM7-<2_>-zHjh@4h#KUs2{G$|>42NRLS_fp*?F75%@lG&!3Sybypl9OJQj$X8D zI>6B_R~$Zu*NDlY7Neo~j7Do37Nn6fJof#z4A* zLG}fGk^%2bJh*~X`)?I*(U6YVHD32wB%PtgBQOL$yA7huGWc`cntdc0$AKML5pufN z+lyV=4*jRr8v>T%bPg^671o~#PS+s2NqSwLKcT%ms^*IH^dgTu&=i!Z2?K5R#Scd zYD?&1&5YM|h9ybrX_=e;P`7mv%sM1g@7&SO3b5BfVfD?^Ul7wikJRV&N?nAlv);1j z|L9fiC-f3R8`aPc)O1VGvxD^At`Gzt~B1zqSh3-CWD&q)bq-;HBY}m z_*FLyJ{{3}H4f0PgYNtOIzza(Eh85KPd5(c&F+kzgH4n0ow6yh;Hp~%zgL9KuJGY7 ztVjDxh69hFHAo*Pyp%6~iS=n9y;Itp|Ki``@+^{;9%k8_t2aC_Gd`#cV*ma zy!a_2WEU5^&;xX&D0>(^Y1?~6O=1|@c(dEd=@o3te8d}Ze82S9oETEZ@+)yxgC76x zdm2@dFl)lUh*glcx%lz!qaaViP%+dU<>o(ExgCw{R++Xf!oW3oBi%MZ?<#GvkKL8B z)D6>Hc)y{*DQ`*0GKs15P;^1dAif=(GY4&Gp0t#`(TG*C{-gq>v6FhvpiMzl)L(1B ztEutpu8F=^uA;(M+>Nom1s*JC!IyxmN^SJB8Wbdt}rEOT&|qm}GmyY&t^M zL0d1jmSEpmQSe2@5}UkVNbgx7#iZc8eInnRt(g+n;|_clfvv1X0xtBt0=?+98)JUE zP!M5+{!s}WQI`F4z&(Tfp~*86Ct_Z~n+}ycN-n+U1E>JLbA7MV0OX+7hS`7nRdKfu z@HX|$H<4C|4f_-5qEq7c9`TPRMMzuG$9Js#too6JKb4OG@u1y&d><)c_($7Q2$hhV zZz=tDM%L=aR?(q-3V?i}DLW@NodliWMaK=HO{}5-8FK32fL}UR2vbMHU|U(&2E%s} z2%y?p_LBbMO-Gx4z=m)l}-c(nAsou}ZHx~oT#fbq$j*s_mv1XT1X4&lDOyFSJc=h)>0)B5A zIPNd9b90=b(?Ps3n!GvyX02Oj->fgQshODxaJZzxnR&zM?p<1!OPWl`QXbOJLKo(e z;x}u4=ynmmtT{W@I7hEjq;BYE3P5E}wy(FRZs&BH?ipRnM@$sg!y95JLmhB~B?}fn z;}|Hp_oy;`B7rCf>?1Q4efHu-K-=c*ou50Ev$w#mA)igb?#mKGKDC!7-&Vc*@hB3Y zrp%xCgv~>Y<5jaHQg4e(T%EFbA6&J+U7Mu=-u`r)^{vH<3e>`Vl)GB^)m=HGe6%S! z4mROnDTyF(pvh3~aY&NDwfl2NEw$RJHct2q9oswmGu^Q@C)IMqa8O@8`IBb65uuaG z`dGdZ^4Uy<3%|@7*{xVzTPq?iu5!WRI|A56-jKw@Cjr_j$3lou6T>@vVWs5hVx17* zm0ZMqJ72W*XO%^U%@)A_053t%zEHTm)}z$*_-}4JHQ>8=+wGntz1VN{1w(+g(PI(D zTWC~3qa+-b$Sd0@E?8}^UfA0qqlp1W4?P3n2Ar+8)M)s=z!8eMM|`P;Rw zrgEdqZlV zOLuqf#Lv3%G`eK3r0AEAdw%hG7q_sT+t`20C{%DG9E{`U=eHHi8;gl96=j*Ca^Zes zw+E*qHTjl(R;^~C7kDRY_kCZ_e@k{hqj-A{OAkfWsT)+9O|GeZnA^!|=I;8ETd*v~ zXpE7d-MlHzGuEu!NJ@o9ECD=YoO=^q5^{`rT50;)_WuBeK7w|X(@#&xfFdXfBeI;3 zrvQu-(D9m8k)>BvZTUGXx2WzqbJDYQ+m|dQzx2NU0L<3h%bDy+q&$)8ivWpAvX%?M zBN+6q;^N~@gG+g(xtb}PX*TZ`Hv$hiIKb)u0N1arz+uy%>bu(AKQHUd_>9`TzPB1w z?Av|(_xT)DQb=!1?#!fsK?iXp^gVd*R<35aflOloWKp<~3XFmISCwA8=~I-c>1+1> zne_0b3Cb#6SM}&YCF(rrhGvo=r4=6_4l%d@asL48t5({~w(%;!iy1~S??uC~BcVCx z{{XFCeit{KYc`iRn_8`!x23<~%CCS`DX7au+oSdFDoO;T&XTG`08q|B1Gx9iEK%Fb zHFYv%gj{sGqo7Z2V&JvwakzPpB*eGZ>~ zmw#lpykt^5seW~1(B~Nc03x_mno&wCx7~ezuOs;;M|<*b|Qt<&kRZCCs`yQ*1h ze-t#iuWYP;u|6nh(0|0v)*Fu_`%VBbx3H9KI*@af-HhV|93M5g@n4Pf%hd39#JwI1 zrIaID-A5Ex7V={S9pb=8gn&sawekrVIRmB@rAl7TZ%3!kRG;;^rA|L-myDnkdOz;zj`-b3gqXrRO2c+MW??106+K!n0hhhjaAcsJ8Ad+ zr!Vl^#L{XunwNtT{WSQrLblGVSX@}#G?@#znRv)jGpv&dsqk{>Zi1ap=rqa1OLwJwdTLv$g~^$R0Dr)rF2mMB?mRkQxC zR|~ZUaf6O{H>5l5w?ja4q0@mg*k}IZoUB_ETWi#8T#3&OeX&Xukue;Fg;nS*t8|D=c<;Zp9yUqGH{6=f6ET`g_(Eq)pb91vyAe{8|$MVg3m@B9!*R!{MbY|64(o6dOzu}BaRFdE=tkW|tM$k_f1AsdY zKcA&_+7t~YHWt2>5S0A%O*Pb2#O06JDtY2Whw3}p1ON2m#5 zh2yq_Htb;0Lz06NEvK%haou6Ovug`Gta+}0Yu88{f?7f=#mVVh0hG^oL z0E9=lark@x04k!akzPwPNSj%d6(>0D+o|jS0M@KASa_!AFX@}no|cJ;;uvk?vRkup z=M$DyB#;kKFgo_Cx^kwErptBZ7QAtkMkJpxj|=z{&(gj+vy|qPcW?4X*3gq!ZdSkH zu2HnLzr2FpzD#3RW<-TqK>73vnW9TbCTd;!PNV4$_ z#-}X$g~j8>sT5n}EbI4GdC3F-Fe}{4<0`dcp{sXarM~ug82U-AS6|Zq0CBrDhLL6A zTUYT7lib;^qa)2`&H}TT5mE^@^2|?AH~_G0^shJZmXbV6s9$QHF!3z1SzE~&T|Ukr zzEBDPhBfILt`u|KkEMILmN8J2C`BgHi@n{stz`Wcw(@?bK2t(k)mvSq3KGRVGaJP zbXL;d-L`ou$`y=^db!ThMo%Z4@mgSEUYuN~Eh7i_%55w9UjC@l7fv+ls%h)Z_$b}_ z_VjGMrub7&zSKNDcdA*7*|htw-aKv~x3Y}^mNVt4KPsGnScAaG?^#|y@jr_1vM;n;e-B7I;hg9(TDQSNCC3pDkwT}W(bu07Y zAG;NMcC&U~eK+3vhlo5Znp;T*iQ+9;^?wm+F-<)2`HmLW-IVzeAR%Lql?9I_OXQA& zN5sB3@NdFqhUdih$qVXCVYRc3S>>2T7|XiG3k5{R7q88dK|Fe@QKho~0E77VJe)$F zEvTjMYV`8_v|p***?5CN*R-oWL|VS+ErrY$a@rVW*!fj08RZv-z&&=8T-S?qHP$q% zSd&h%)Wf_)+sy*JQAHaw9jXEI4nRatyPS2&t+}P7qoe+>_Z&3f)VW*v{{UV80N|Kj zBhv1CA#i+YsA*cCihNlms-~Y{lB`zNEg@A9LNS3MVn*-_1q^p6#yI}~5Z&tb_UU64 z(rR8U)lzg=>>Q8Ih*9{&Ij)rKCu zIZ5e$+eK?{H!Z*LB(-NNr}#HfyVC93NNIl6sJI$!sEc&>(GDb^sWC)7Tdoa0`uD=# z0J~zQ-^4y4w;OI9*hy(;CqSvd^IT^npOj-9o}UYh!BNZRu@YCZ_g2dKwf8Mwnf)D= zXZ5q{e^A5wu1)jJZmFv+Hr7(QkM~oSnqNP|<4M$HH+tpF*7i{cH*&^Qw2pa5(Qr8@ zuWtNQ7OpR5dn-$Kk>=vvBf( z&2DuQ+w)KJKHi0BRFhGAY3Zf= zd7>AQ<4~nz$`g#_F#JHtry~%@$p8{Va5sKA{{T3zDxBx-5_V71U+TwHqPcI=`szA2 zxS9U|c*AP~`$-@YKdmgXBb=~Q3PB1Vb~EXp=U$Z-rTk96=X+Y_cC)lPe^)oIpwMEt zvXtr<15CS28P+h)j0PD97~~%QhOsYEV!V4RQ1dcnq9~bW7zdmlnCCd}UHGgu88qM2Fjlf0tze=YCj`J)fRRyucsHOo&0Nv>RJI-ZYmr$aZ)Uh77Y$sR#`fpcRo-QbS6 z;fKrVUL){si}4Y^usloQn@b%^>eg`;#Br%;r34vLIRN=jeB9Kv+>TYHRiKrq_v-jETVvGX=^?{-{h7+@e&j^ z8II&*k_zB8ZumFEmcB3W&4-C}o15J?Q1GUxE#q0GjzEz*o$<&Eg2>@H0Od&C$OgTd zPAUmK{{XA~=ZlJQwW8Bey8F|!{<@xROicK+Pl!#?8 zm6l&DM8g?Q7e0hzIUI`fvkHna+v%#uYTVfE}?!b64jJJeLRd9 z6+9~=V|scvNf_rnwddAuMVHxiOIQr*eqfLil1kj8sKEqCGBcmN2d#Y8GoGd6J)Vob z`hJbyvFyP{F-?EK^Et%Vw4HEF_EvYXN~?izwrvxE(+mju{{Vrg@8;I+U2Oax;;m&#b@zS)kdzo$FRi1O^AYJ7S?Z-I&gZ$#VtmF6k zema@dYN~6g(rGrgjHVPuE`^Y zq?)nmzEj&jo4uY!eT$wz&r`?qr$Vn~631{vw+z`}doFnDc&~!?T#`^rZ|kx3v6^b> zl|{t&(i>}1t8WB^GblMN>C^uJuT8v?2%u1M zIVZJ@n}oP?5xG#Ic#LNxAM5^eij3)kJD8xllH`XwkpRIB)MuV}@9keT^>|dDEN^wT zpO&clMTt?Sq`wkpwu4T!@*>>PmtYAx^BzxMbtM z%b&}N<)YWt71o-+yZZkCfLx;~r8U>}Gp5vpmb!)1HYp9ZnG7jzp^s6Yn4W~@xRI+} z+W!Eg$u7wxmPeR|Ke|JLNPO^dk?oxGUrUwgRnA@i08i`gJeu+5hp~>f)B5@U07%yH z^~5XS-401)ScIN#qEurF9~&|BMM2Z4HRg7Dg~y6tQ@hhNhiGo#NfBg4^4NlM>|1CF zxqF^*j%%+KO{&tAos@Z3+?Q^;Uv1fV8MQ@9J3GHWi~bMldhfy?3F@EN`lMQ_?~Si5 zQr(39Vm;EA+*@eDMcfI&V#WD8Ibpcdd+-UF_{|RQ~`Qr};C#@cb86x@F{TZEDSX zXXcS`>=O-<2x0SJHXWPLY+CaDBwxRY^vf?c>gMB7zgxNFB&64VQ8FGlF~Bi|POMH& z1$($yI!=`-KFZ%U%)a~C+ScYrpU(+8vtGZ0x9H#ZxpzmTYNF@D`deRVHc(%9s!Ib5 z49a|{-J}LXo<`p>^SAhj1D(8h*ThNmPXTz3NAbp|9oLKeUiO9^2T535#F7$x``J_+ zzV>D+pa4cVzyy0WocZk)chj%+)A2mIFP`zexzkPm04#L;Y?}F|bzTqf{{Y1Q02b-~ zAMp>3b)n&STH;MdRgDy-#rO{1R0U2+KnoHMapnLpMSA*bt!d$P)I2|@-g);b;u9j` zMM6)^#~&yihi)^{yJ@LLDNSqF)g__kR&?ht-Fz!V`n7iN`h1aFR+hoF3w;tdajfeC zdw3^D%iAg`GPpg0jyDc>HaMb?JPW& zx2fCBzuS) z5;I;-D-Q|D&U=2J6MnltGxUxV&1+#J8g$;e$@II{5l!|=`t-7TnEpJopTqiIk*6-3 z_GqnvNsiD8T)M1=ATyTOjTk48Se%+sHlyK9F3(p;3>Vsgks+UU3`n>P7oWUI!9BSi zxcLlj8nqlvOj2J2RlQY`x1)FYF6ZufE@y|w<@kI&rGIMWe>Lw(uen+L%NI7+aY&vX z)8K23Nue{|nDe`u4yp*jToKrV`3m{$!VB4bVuDMRwYBfA{{Z5PEL@=@JbD_I!@~O3pq1wa|xeZTtk^SF#W zuH@}#rzdr1zPHz*?9|86!BX~><;xcAo%Hhi$+UZ@VreXI?4ly(F$&1b{-~3~0rmP- zYnw@|^(WHrtqMuI4V5Pg&&)B5kMOTfq?Kwhl;V?4&*qz7llzP#HA@jvDtoSFuWcXc z_nT9AYG`KrHkqkIcc;q>URqA;v@;+ALAR5Y9e$Nx!=59&@a4(YwA(9-r_)a9)+EaP zobe*Jvt;9-1d8|Y_-BN#2*Gn-Yc7h-ehoj7@tL+Vo@JL-RT`(Ky?v8+i(aZ%SMFzP z_EsJd@zff>hGmf!^*cgWP1tNLH%@;n;!RHU39_J4o*Km90Uct+dA zm$G;x#aA%Csc&gD$A`5QBv1AiVmz4%<+fo6B%I(A%9`J>zE2NpHo8W!Bf)Jch`}_? zk#Bl(zj*Vp+o8@0d~sJ!QHpDRpX78;4(cvgD{0KU)9Lcn8J`)vI(2^zU3h}Z`sU8& z&rgwOiqb9a8aGx9pq0+TU!fd1#eDtY{{RzdE1-C<#C|WGE=9n)5vm;g5{uy7+9(S5Er>0K>n)^J;$bT3X9bk(BGBYc~&ds>dC^qdOT^ z+C@nsnGP}X@wJ9}WcJ2M#ap`95%fr>TWl?<5IGDZbwCcr9rzqzj@>!09=;+GZ6$W^ z{cLXv4`{tV%&l>$+QcB#ZgsnKM@4vy#|%O2dCog$+lRI+Mc^>aMykwx{hl%m7{%- ztcYKX@%%XlIL|@|gwxv_0?Z`u@9$F7(}2Wp6IuPPlXX$YqtHS8Q;gF~)s4{3|D0mO*hJnF)sV z4g}I60%h%zcw_J1@UL47&g07L{{Y~BU+@nyq#SD9x3S9VWyJE_5~18=H(Uz{xF=I&}8^J?qrxw%UFL+A0mN>-zryhC2-+`Z%uG1GQ9b`GLoL zbNK%Ng;&;RNUyirKQ3|sYW#}$WrEC;|l#B*AIT;{l z{{XH1D?)jT-ZhMK6jG?F%0qTN`&UjI--C+jZ$HrGuNI|rdew#e7ZE+gs^wIL48sN6 z{gLVZcoh}>!$!B4YKBP^@8Gt=bLJ7zc=SDgm2fH!m%N`(KfLUP zSjwL&{dhL3Ld;x}0sazlM}G90e}ruHRs|ls6PT%<=N&W4=Tl6jK`lYt9b#M~q z^X#H^mTM#k(_YK~Sl1&V5pb9t0OXvLRy4ggL9o^5@v+iXZ$+bK+r7Sf?c}Z0#_;yJbE!wI z_~P)3=(O_+T8)k^t}b`vMv@VhjaWu%b zyH6~)(jq1Tl~Ss~T$U_LK6pYgmd$NtJGZZE?cHhR-@3VsqwJ#;m79;Ncm9^2%KNdt z2G=gNZ5sao;%>PVaB0seO&Z-Z9K%m6p?7XPdCsA;+yZ;oW8xWP)rhp7>&f!vGCHJS zfJn-wM?tfx!8l?nV<#o=f5UI5%VH{}PN%!7PRq{SetVeO*M%)?VLmFhgj`%{b}~Vv zLR2V@d0g*x9=Iqg3&Z~a4Lmoc>T=37lXme)g50@L@^a158bx9Y3crVJjdd+H+qfMlWk?DTpR2CcIpUaNX(8c;U!7VFuruf&U=8P zoxF6~#*3wBHrKk{`ayXXiS}&|NPw>wH-ir$QI1)z7zQI4+Q8Qr)T4P+OM5$fo44O@ z!24`2eO8qkIDTza)z?eP*YfvNoxI<6b1mSVOGB{nebUP{?xg11O18KKl)c2xJmeVr z**VGQ1M#k=Zv^SuY_-4|_Ro39q^++xm?=2)t zXAEOilq(q9lae?9eQQPR?>tSU=$g%~ui9@OVWnNfz<|=me|E&=a#xI=IHgAg8DT9> z9`~Ph%GcoJX^+k2M=?^VG^xccS4he;zpuRnTktoFY_#7SX`UC;kR_`y^!;XVBH{M@H7X5w7amwwrAn`c|LiJ=KXX=3VKx1fwo7g2;CcPI91E(cy5> zl`3^@tXurA`Xqis#Tm6)ILi2CFLtVn`Q5Ak0N_skq|kU5Pw^gws{A&(xplhH<85!k z+KQ=WeLi9sq2rLRjl;G<>?^A9{5~Ro3uw3cs>v?3p%&70LofQfn^M7DTc9HfgdA`i zJ&k*DjA_BR_WZU#JF6!;mU?S-{{U|*+vLuVRPaWZs_8b8HQlY@hC^>*G~^i`)u6(m#@6b`NVK}r=HIS(a$wqfy8|TgGLj-7ft|>#FgePcR096r;tzxM zNG6qs+pS7j+&J3t7B~^O2RovaV4p?}o@yw?)s(5fpRKI_01F<(r5Ir;)mFS+zwOrU zyt==*=KMe7O?$)M2C?x6#9JwBj*)uSTIyWeZ!)1zDm$>dvZL;X>$o!;5|MzN>k2;mv1AMi!Au9c?_x(6Cd61~w{3-Nzqz9A~a@P-?W-{68+*A2(98 zsm{>XdwQq-O?vk{{{Z%4_@UvC2vp0~el-=2pxf1+K#hxH!{_nD_sGC`gyl|mALWf7 z3|Q*gkA}~OrqjfFu8yYbPFW`td6DFq5GuLJQgQ(&AdoR!_^Ndy9%!vK`FxCM)P+bm zx2^T_`TqdH`-)a$S-Xv`n^Mz*?!!mrd2;U0pyxkQJ*#?49a`a)Ztg9nk)trmt8vWH zgZDxX zgm?V&%}9JLabXm8@M&t+DvV@#lm?N{8Noe2A?aT+Ds>@I!h3rE0Kq+)c%^mIuExHn zE}NoQTUkpa>t%Nhv^t=9w>%8UJgHP?0HEUw)F~d7=hwFSwvVh`>H3UP{_0kV<%V3Y z0pYMm8SB#+Ada=^V(_wZy59c)f9t)>sn@SkSG}ZKRr6OEfSutL|Ao#rrtniH*z3a$IB# z9{i8UfBKDS>JUeNX$GPjcK)t;^<^vR{eNHZl-@;AIc+IfUw*&S8fsMAd!D&r1S@Oi zDJrNy4awXA?UU<|(yzy;+S|hMTSVAVmzqF+{{W!>06w+g)T1itQ;wUr{ao~^%aQZT zuLU5fH|#3Lubs@WEbLr6~&F#Xq=I`}!0HZ#h zoDMQisq0=gVFgYOF#eJ|@UNMrFYDB+u1_7ba9-Si%L5Y~ya#hlCro7a2fu!tR|%=< zJ|&Y)yC!#My9*0Oqvb{E_w(Vrs%Pxj(P#^xV|fQ9LW9 zT1NzD?K4`eZz?ZL4#T%zp7oNJ);fNb2D3B8E~Mkjw?zYYn9aivTw^^yD(_Nlsdu`6 zclG^T;;kNPD&1Kt=xu+gtnysTBTpgo0l+^f=XXCS$t0fH1Dec}Ql8&hI&PmVji<{L zut>*|x8+xS4#7jH2m94@rlVJz*YeY1qZKGxD{FsW*T}VdE9sgV!{O8#TpGp0IlA4x z>S$F?RyfJzk-O1AIpp=~B-C`j0{BXJ>}~DsB+(Q}adm9__FlN!s_cK(NT}eFa0b(i zXOE!Dxu{_z+qb5h|w48)HM<+GVu8)19AO<&7PU#;bPc^tLswC7bTy_c)j{{SUx{Lvld_OGq@b{iiE z+`*yvVK0&^Tia1wEVyAm_znICRCmII#k2BoLTX{E`c>C%5>X;Ldj_csK#8MtO) zjnmw}IZ=?Da8FH~oSUg9q>}kX?Wf^xt|@gnYA8lAf?GF!?pJ&IehIhGUjX=D!rB$~ zt##r3HuF-{t<^0r?(SWrDmL$UP!e*?v7(d7%P2iCJr~4FWXYj;XID{kf2f6Yfxvj= zk~A+PxasAq1tcD%C>Z9xhBAVtxmKU>Yql3&x|8Cny#gEuMdU% zG>fTTO|S{CT0E+vC_gM`Y6K(=%C30_HLIrlWzueST^mM&N}A&9U6$G@C-Wo3Qq2-d zK3uWEMq|hP^K9dc`Lo2zGUaRfyVKW3b;Am(!oPG5k!EU(C&6VW+e!40~h+lQM1z)Hd^uFivST4FgS< z{{X{!eZm`vGy^To?ZIpVf3+m}*P&;50pw>OW4&)q7Iv3={we;KI`IlCm)ZXSD!;0Y zzZ;L#w2`N3+7^o1n2n0g$-EHKT|7h=819N3=hgbwJ(Y#-ucP>zS&r~q%i;y{tW*wC zARa4mp5Mmj>M>f*Nxo0&=_J1fbJB#IRYtpf)!ToHG-6@kj|u9x%C9xejfK_ZX9EIK zk;Z@n?zkS+cTUkQbnRclP|Y(iu+ipb^LGUUYOh1a;#}vwL*=P1R=a+G@C=-)(@JrB z^Dn`FnV;eB2Iv}1?wx&S6m12Z7g9~Na?DJH0uMyyOb@0rRJ46FN4xMwwr?#|N8$-} zNVf&$2%VJ=&;BG|~=(@jTXlR)lBI z+TWr&@Y(JnH06hl^={x zTg5+*d?#xhUVfc_4!dJ7ApGbgLC>KW^yazfV5!oJgI8^Sl2`u#$x-d*oJCt0szaS$&k3>c2Jj z6}&Rnx_lZkaL*X@6gE=Yoq(c1^EE{{Rp883#v#_SaN4=0Ry8i|pl`hD*qp#sT{L ztC8uR`K+r?5FLNR`h1s>$7`(ET*~hQVQvhNN@7+&?_*;h`fHr@tZ?+C>ZrY%Z}GbP z-`sjtYQfTSTg9bsCkspEb@-0)E}s4<@Z|bRT*n^06_Pn2im`pg?WNp$5b70&V=2vf zH^aXj-sw8MhNG;6wzb!05NZ&!Z??764&bwb5ALI#eo~}u+(tg=-RR*csMK%zzx*G` z9$c{wRGl~H`DyrR^F2CU5p@k;Q`5DUmA|(%+nqM%8BToDu)Vb2fwruXu>+QmuL8VV z;SRsz-Db-F0K?u3f*GdL5eZI$u3xJ<^KQ#ye$admQSZ&>+bG)9X{tQLt85iaC>ZG7j^P@vj!P zB5>lO>EAakl_F+aVDw3{DC8bDq7c20c#mUex~pvhHp)HQbLb z#)+iNKy$d@GPhuJ$-u8Bqg5&?C2scoS>Fg+9LU1gbqzjcnpu2Xc&#`Q${~n_2Rs$d zF@Q0SdQ=`I@f2<0jU!Ql=j}4Ryp~NdmohuR#Q|bHQ)%a?dQqK9uyT&Qe;@cGbZ(Sd zw!f$R1CPGdg~Uz{5bQ%Ii=_F(>KW&5Q82ev(ZfBjjn zS`oZdlK#C@{SGSWLg_N3w(x0e^4vx|M-@`h*?wjF{{TAXRi4t+ZI9+6WFTj;1F5W?UG9?E5Nb~IN=PiB zaHr@8PI1L~l%S_6$#hmnP9n2~D5tKbw}#=1K+>lX%4EB_az^5QQ-k%#`RPm-(p;k3 z!75L1WZ2S`1!LoqJx_1OzFRX+RGi=UzU>#{dRQ3VTKO1WDoFG=zRMww>f!S&uH+Jf zBMKMX_8dDIgr$N^MmpU4wg8eO!v8k1_;i}^Z!p5izJzbIk=ImU8-onZ=hrsdaV z^J0}(CX}}S0Dw2gTFYs+aYJb$EzSJDF$?pQzIMYTAL)FDKmiL^mu8HZk`zcw5B}O;9($?>ydcR&<>(_3lN32BN4biP^e0O}lNVqpIXs`R- zUipCDNCQ4Ze{gU&ZS*yJP}O`(cW-GnlOUH^)nblij#N~R-pN=P;Z*(~FoJRDs!nig zvZSQ34xK%hUq6K}lzE@{o9ab1PE=J|n>+sin`_oqOZ%xEu9Kzc9v|@JwxM3;-%Ggr zb+~QK5Sl>js~!#|3!R`I2?K#uCb8A^xuDc_d4;LALdJF;Z;m5^0(=EIgVP$uy>r9QTYEY^fQSW42 zLMAWwwty4@#fxNx;2Q0|4SX)wyf?0D9~8WHyD#I@RwS}A2@l#Miw`gW1yTm(0Z9Nk z8SPxu@YN~L+DUt=-!{L=-Tmip)*%W!sr%Bp^i8LC>$iJazt|j zn#!dGS`D?LR{Nf-(@l>{35u2$5R!Lo%THBn{O@n`C}WoPrlY;y^)v%brHs0!w#4Xv5e&BuhW+Y ziI*~<-nze%y8U!MgB^vZUX^TRD5VF<6qiQh&25*@%r37c*M2DJ*R!aS#>Ub{S(U>n zk=K@7XKxI7_O5C#7=x=`t;A?7?PduPjC|oDljZ!zp+&;xPeeJgHb~?w1^v1i?^vNvTsx71vA271-CPx|WIs@Og990ch#Wuz#MFUA1-hNAx;73G{6*Ow@H4 zZlh_e?BTPx45cwB8?lqro#L)(QfU_c9+L6x0JXHVx|_;ENhPEVNGGW$Kc5wzB5B<( zKhORF$s8p|6**~nCHOD%3pp% zT|Y{)wDFa_t+JTqou|9QV{;!N&tCW+r6!pbq+UH~XHE0p_)Zm+MSEU8k2r7o$z{WkvqBSPy{eQUz$sA$(hIp)(Qu^=`NnyMWJM@pP8L&UM{|xiCAK2nPzvV^DeQKOR@&xzzkKtZ3g8uWgr48eN=`%F($C zeRR?lcpXZS<-Qh7o`4*3L9V~yziHE7&zteN;?-_5jVIN9EhxXb&5zeScMZm|;IE55 z8-h!n3iuec7-Di~w{plOjiVoVd-4d#1Rh3w5902ZsQfbc!>l!h)zp3z@j-Xw7K%$* zmvgcV{rKM}93PYefKGIE;|hwbwswClpX74FF{8~-cWc|uE&dvw!SGkd_jj=7r7!oHNtFl(cG9P~u9~!^PNzR*+s$9{x6JY}GKDIfuV?vdZ_ORHzvD|iQDoKQ z3vFpMP@9Qluq?tklspp<0aAzfi5xmNV~T^q{uG|W?V3gP-keUq9{Wk{t&$Hg!-Eru zkcAm? zPSKs&!6V$)C4AB94s4^4+1{xJINge@?TiMFKn}usVDNia&togO&y~Ahug^oX3q>xU z*I&ExI===B(WdGi8`kcnNQxVqLv;Cjc3v1~xEwY)<9}M`bqyy}Yuk%tywxDMiI}26 zda}Z<26+I60Q0~Ek)E7am5Gu`RKAwC_2zbSE@q;?uOk(7KM~)VBh}&4q?2eXHI(hU zKIwoDew7TK9EVQPuC*E3Z!+?Kvc_SFmuzSQIABizu~Em$F^cnQa;|Aby`Sj1dYuZR zNkuI@{{H~b$GSl98{H}>BFR;q%I$P<(YYVRkIYtdmqyP)wzJh8Ozk}PQK~)y?jUtO zyK~20wYCbUy5Q5k%kN+0X*oG9^}p!RnHyZ$+)8x$)$Q9Gkm0)ej_Z@}Mcgp7NpL_5 zhAqbgk&JtPk=ngYTG!Y5zK11AN-|Au_axD-($;6UkSn8}7;sSFkX z$XhQGWwF6M{l2;P;a*wtH$nR zyNc>BkOozdkOv$S_;Knn`PZ!o&ZIPZTg>69OAr#BishdvnffD^1qL zyep?o3Z~(Z+i)|S4*dOny=$VJZ4Gt&di~~6T+5dG9&kCAI`dDZ&1-l}+I+f&)Q=HGEMtxN+(!c( zU=030TB)O4Eu7K3P!TM|?Z+dN+?x4p!U}ZM7xmQk@N!X`TYtbaJZ)hmt<1M-;pHSU zmg|h?KmM=6qk`l?b#3HA^G+9fBXhWP{zv)Osf4BM@H#G+IWaXIYUg ztEIUX;euL+k9qr>RA(6IN#pU&XKAoDji*Vd>W#MU?N>2IqjYWjC<}BWpVql?5m8U> zTJ-yo+ZkSzV!G;bnh%9;JX7%lPiW`B9%+1n{EE8`z25rd2jFHX3|-;8`` zcOB-X2ZSfMhJ9Y*3p00s3`kUrMghp#7*G^-X3i^%+BY=gFO9qRvRZuGZ1pteP)kIY zru#oHbsn?f@{)LF+fLLht?q8%Xl~NdK*(c~P{b^lI1R9#J#aYADHQ5D)}wiIEGo9T zY;6OXWC;?xDH&k62&$RFb;INWYtgAUDzJssmG1o4e@>6o@nse7&HR^?zt7LhW2LwT z$3?Nxbh!b#)?^_Y3>XFgG?*li0u1{7DotC%b{e(rnAeX0(R8I(iUd|NNiTBPO6y(;)S$*36DWrIpi+;kG?kLJufM0}^}lU89G`|wguW+jV*ch^G2$tTT9<}9dG0p0^(h*ueZMO%`CkW| z4r*T)d}i0Kbm=DWpNF*Rzk70@@i3W~JW)uf%nA^vspE0RFi1Zwa@DIT!;+r*-v0nE zKR@ep*P%u-s;507t+&r+{{X}D>86F}zPQwU4SRp%yJoR%LTK%whR8PNO^YVb!|x2| zlYzmm1+~jh3+XUNXm51X)h#dMwYQ#SmPwc@fOaUx50o%RA3sxGMBz^fK4~v`D?gl< z`Tqb&`>d7J#ZhzD=r=$30Ff(w&aep@YJd-+-kel{(5hWbIHUFgsxkv#7V z_Y46b$mBZ$J(VLLoq7j`uk7r61NNC2Wl0gf@B|+%P#!z-r_#ExxV2Kelie@Xrg)jI zPO0E%!VBZ6d-|l({0=HF70ssjTGLlAzV`B4$<@zyl0Y$^_d|jBR#NK6P}VdnrnwoC z=Hf<=3Ou)W&M;e=^DE|2s~E$pj9=py`F=;ehRMFE?Q5vtTB&&?rkCcTEes8=hdbQl^Cl}ZM z0CJ$sSR-yS_mk~!=Nu2)gI zm%;kw)V8W7wYj;PHnmBWM3FE?h=tDsl^OcuHOEsFV_u~hLip! z<=?wj`RsNY-J$r4;J9@=0Ub2r%Qsx=w#6b=+qxY_+%QmmH>Onm2dzi&FI-O*cy|8) zz?!bAR_{h8He=MqaT_U2V>nkl5!VByeKr=KJg?n<_TTUi%`+@dv%)$_Yf69puj6LU zH^#b7ukg#lIu*U$<+c8wWvscoiV%F*!?9SVUqkz;02sy?gPv&AwQXPG4}vw1hL$iJ z?Qg?~xB6wqeqB=9AhFDj8~DI(hn@#8gk$M2l=DObB#)hv(a6@{F(la{{SPN z_(LY0s8~jdUcEj?nT((BT;=g6ucNwuiogB5 zc#N8FjD8tMW#VlS;MJt?dnp@%N4nAFY)KO-&k|{#D6-OQVrfOE zi!|kfN{aneqL%94Y>>9$jf~OY5)W151XomK?ybM|74p5^k24UVTAHaHuKr(Y>!-p} z@T51IR+nk4-&$PCG;=MD)ORJG;6THA!o=@c6<{0L~0-^D4=VbDioB<_Y7ic$m3GO{sh@ z`s$6Mr38}Q7c|cn*<8&H&BmJwn50H~fpr{(ko>F|U=#A31J|EQtK!Ws!n&Qp>Vnqd z3+p)rvAK;EcL07vxr1;(BR<15!;9vXCn$fz+ikp)Iw{3--G5!o8{J;$IMeKGtXeRi zynESDNW>lvRDekDjBskNh&63e{?AX-bzM5e8rZbHa@-aRmnVW4o`7(2J9Az=E?CA& zFJ9d~Uvb$xb0)v74s!9eD^hOs`x_#Y#$%t!g=1qLafS`~gVT<^D+9zf_OZHO-@G?A z+d@M$FO!^btZ|S*>N@qsc44BEQfdDHUa$J{G=<#n7q9iXnQbsJ2`%uXD#msksTt!q zJ?nL^EtgHYv60M)b^@p)ERWC3IPcRRoqEt#R`p$c`ZJplxu4Je36tT?FbQFjX-SD> zD#}UEEP4L`^>-Prg6U={cc-crw}v)hf=FI^fHV14^i*lRGROx@i%|u%+J(uU>gVk7IV406&fNQS{{T3uR(CplSB3^)sSKO8t8h? zaTMiO5gJcqk6xShaB_Xv$t}OMZl3b>Ce(DCDlUeU7-Xr{N-UMZw4CB$Y{$<8_Cp4jHHwYxyJc3LOf zm6mB5Q@j;BkET9{pQ-Cy*qShmqh+z#gq)_EG_NhJmI$6m0xi5~jLf-N7$3SYIp?3k zy!XWVwS>B`YyCjQZycaU8XuXP7$hjqT!Ei%pc?R%CsJ~qwtdfApV_F}vi`rXk!QoH zd!gtrd8Ap%4ymZdw$^jG4q}bu0h`&GfF1Z8bWTc-m0NW#rCF!Ew2 zZs2((oteKbYucw-!k;2qrTFUK=9Ba@rrhegJstEI1Mszk_E&C>i;!R@R5pM4r z`x3>KHmayV^A+?Pb_0*^aampuyq+B*4LUZA&3S&X++O6F0g#~DoSYm!GmdlbipspD zPE_f~c9y=n{-EN ziDTT2xKIEd-Se`1kzdu!l6==+@ZAn-Uk=_+;>%4{?V*V+gG~F`kyNTMOsF}O{{X#^ zgMf3>oSM!p78u5frA2=nQX8ly)C$jf2f1+g8(OagAWZLGpaj490Zthaz`rWc*EI@B8_FcFEzuEag#ytDS z8cwaHTxhas*OFiAaNIS+U0g?)ZQ^O4{ba`qo0-Dx1E2%bK7M0D^y1+4(|?!wA7zna zlrb(9Vw4^B=)LV1t)a97xu16To zE1j{k*LCPWwQVhAOAtx(u^ebf`^>#McOxS?>0c+9##ox3&WpNRyZV2_eaGs&J&1-E z4J=+RE;5rzM_)T6m(BhA4!O98$&*O%=A)?H$uxpX+nB(P-+*{tH!_ZLTOW6Yt^G1> zFj}^+eI$0Skuq9ZXZNzI9jzk*cwBDa@^E?z=c5?7^K*NP&#J%OcK+kjtzKy;N*1d( zs$CSVZfDn)E7JNc4Et?jTk~y>%wg%t{5D3A^MFB@rJ8&_I>aKNJZN3xEhIUJm z@xTMHW@l++EQ23U(zMI!O{$eSo!n&pZ~D-Az8arC9-4|tRf4zoSNuM|@D6iUyLo&) zXKrnpf3n$uC?Keb-crou`i;n=r&HRrJUyp)`_0c~n4a(^E-W}B@lp)f*FfM^I@(ZKw3^~q8uV2~n!AXB!@{#hD>p9k`hm*Q| z$uB1!Lx>(H9vAUlkBMz`<&MKqm1YZ(bOatm}h4W6A;_X4bZX|lhv)%4w7+RizA zs0?5_Dd8V#Kl?$H$M4Wq5urM?8jp0>O&cQ_nNY*yY1Wg!G#nf2b-vzznW^w+U$~8R zJvUe1X{G8>wcWI_CS3_@7z$ zN2$P)Nqu1!rJ~);Ok3XFl(Y}Dh8vnUAdWz0uO;|>apDgQ{7ll?O*->UyoP48)}fkR z%nabhE>W1B$Xupzk;0yGF|6S!RZ2@n?fBpFxyemJoe5KKrT+A`{{XkN`G<5MT)a=UHnI(fz*zidLs4PpB455_& z0DG?P+}D>d41==6>)oj&Hq?2IDG<*@^d4xIGw*Y&RW zt3~>)@A{b5)-9tKLchAx^#*X|kr+q-A1EiEUte$KT~>*yJ=Nre-FDsYR|Err`D3a5 zYp#VJZ9m|CMw);!4k8Uo%X@#o{{S&ksiKed+=kxuA)P0YS?(QoK)E={=RJQ4 zNZx<#rG>3ngNB)zd-`Xf@5U?7$J3X;1-eIm9j;zv^uOW#Zfuz4j^$#CBBl9u01d1C z(dqtk=~KsRaLslmWgcJzGk*vK@yP!GIXJHe350HGx3Becs}YHftcjqS+E`3dIolD$ zVDY$){kzpmtLb$snBa;c&m5U|amXL!SJXm^N%|f$e9xIZjIB=M=3Qt<6e`ML!%7Bv zV*~vE09vPYrAu+*Ygx-~ju?w!M;Qk=`hWWCz^w_kzJJ!|t%s6Hr1Y_3*5(~n7KZXe z5~DnUu{;&T44tA=k z#^2ZV{dGFqYj`A+Lz_|6mRJP#xIq@hX5PC`a(|yvG19!`OngD{3&dLCg>4}hjF4cA zAPm3(!1T|*UiF>*$vACy{b~JZX@qZ?ORbmY%eL3oy0z|`;ExX4OK{Ly+_k_&Q<)@k z&df=|00NAh50nCHMh_DBL*eGB;hP1zvGFFoHo0oEn9v(LFET|}Do+n0h5P3`s44*f z*FN%{{S65U*&%2?KC}4RPgEXG`E(v?Q^PX zA~(ysIe@!>#q*YL_m4tPAgHd(OVG715LsJkw|6kv!y2MVa6kxdTPw097|S9l;YS7X zNX2*<8dJq%Qg21O^1tVHl3nyS#npuxGOZokc3+45A0(ZudM=@c_VD) z!$=pB7dvtY>Omu60~x67!)iA^W#ft6WXgok$Ou!POymxoc<4=ita0(g;+-h$ze^uH zu=1x*np>Ky^o2|KtLem<0R*yr~(=Fm{ABTY=pD$0=ZJE2diN9 zJqJO}cl}}tYLeZ*$ivyRoS#McmhNJ+mKkTbOh6T*W@b5*oCELv&*xmGwQsBH`aR92 zn``79t}OwVYoicBVS#~wat?cpaBzBR&B-W3uV2gY3_YPyPFpAc01x;ai|9Ar64UgR zx|MYeQEcP4w6>Qo4Xc)N(>8O?PZ-DC>w$`o#a3$QomF(>bCB@@2?2`<;8FJ*Eg@US_^(3B8 zu1$C|r8N~!3rRgaBEMVx=ilLRbnDOB)oIERT+dI6ZE5ni<#OfzoiuvYwwtD-yf-nM zWR=|I_7fY(GB_S!bAiq=&MRwG)L^jiXN4eWq>(M|4b{=|%aZSx8;Bpm8vy-l(xFe- zLbF>dq`a>ezoFyfv2w&!!zR<}?WVl5kLURqnuXo_iEbo>$sVtzLvtSBN-r_DIO)LZ zc;NjjqwwXU#c>w2Ue?yg=@&~7j$q>rAwUlt0O#MeXGfYfT75NtDPQ##I=mhVF^<#G zFE<#ie(&-s$Ewfa%N-u_RgO@Xtvu@-K#<;SY@n3{45H_g&JU$^pAw$SO_N_$6A2`S z&qlUb;Q~n`L=s3)k?491plnY#r~;lEy>d+eHUDgQdPyY zzbZLBzyTN>=j0ttX@{n%zh@=V-*@~4{{RkoIO?wu`P0{#wf_KbCjS8RrjC2VT27(h zKZtfZWS~yB8k@!CBC^7)a;&Sk{{Rv;;5j`9OxLA+I=jEP()I5QYLmvdnho)`(rzZl z?*I%48U7`VbJrMCjE;TmCp0N?uj=bV=JN)sH$No)SC#(&;Ql2~8Q9xL@iW7^l<+b) z+MdJhDEUdP?h(`@kG!~Y<379|*x}*TU&OaI+J3hJL*m~L+<~WEl2`4p#{U2^HhP{2 zWNhx_j1$j8nw0I|{FR^HdCOXS$?BKkc_yFA$722#)qFGKokzqT8-m(@x4g}HV(7(h zB63-y0R7e-v7F!>bMth51JZ50JlA)g6pnV&jKcAB`F{PeKP<~0KZL193(qn75nU0C zX*)gjf9Ln^dA0EpuH?Jh@XsRr#ELm3w$v z=xT;aCZ!MO`ovlb;G92PS@h}HU7ZMf zT5Ub;_uc9JbS~<4V@=ng*0hMAl0P`S@v9xIz~?GJ;hB1=>w)RdBjVo#+W2m5Quj-N zS_|{G;@n2TC4+Y5U8;C~hd2P>f3z#g$8yn5ad!UzgQH(^Z5?=K*DPOO(dhkdXZRY~ z>@_52QJUbMNezPY!yv~tk7R*c4Wx}4#Z{{Ro+MVenmH(k1z)F}xo za>t<=&!`pGg-ONRU&qg;!`Wv@y%5 zmI)3(c;5#l8Rnm)~JiP!rFB?6uK7L-1e(7%#vWB-gg6#anC$wxALyv z!j@5`wxHKe8by-?>;YME$m96G$m5#rwJSKy!n3IgtTv1h)2DC8rhgiGCBC<2sIiFlqvJn&BcSAD{{UQ9T%Wa{ zGhdhJ?r};gjWm z2dDDpyOns#pCec4-~I^|X}Q{b*7dLLS~_N( z<_mISRt)=pglDf@_7$z8U)xJyWp$7=%e)e};~hQ!02=h8e|k@)jBdS>*ZTgytC{OK zSQuSH<$T9u5yK4n`s4hH%emDjI*GKllL;tNAAZ~*9loUJ{{YusG@{+*{c3t}sME80 ze_z-2b3aOJt9whyr9}vLsYV>Cl1@lHcw}7N>U{TAUg-pZ%SsHKejlHVKyH!TZuP9n42S2g)8*?u;npk4W&pi*Gfnh_#F8-KQFxSX)3FF+hwEmm?TJ zk@f!of1HwQo;7)Kj*Tlu5qExXWZ$D}PTzSIsPoWuWxLTXi95IRYw!FCyg#a&==C{F zEdjKfDLb4yysegO4u|Hz9GvH%uSCh8r zN1CMSy)<@z*J~MK(t`GHT}qMLr2gTX+y|QC<(Dk{l1m=hBZ1SNc@?pvK^=qy z&v6rB420d*GP=u9ctdg{E+RIa_57~v zV^T4LpAe64)~UkyW`cxV0*%|63}xMzkWNSg*0@up3$KSdd6N1+ zKKoZ(|WZo<5}A7|!;Kep^Y~@D%x4F;TI}X@==(Z% zyZ-=!&PPE@6YXS`uh(UCmj0#fFT*ym&!u>*>3_U2J*E5zNkEOcSvme6pFDaD^s7D> z@EZ7kR@7}-Bsy-R7unbn#H!?&TroVA$r(KkFa24OE_&4r=Xrf1lual_d^k2idEBALnDQ@t%(^qo@A>Zrh?y zE{}eui?}_bdqB&mFmQ(@PfqSJd=QW@sJ2L z(ah7do}cjl0OWYea-}yY@6+$w?ma@=Mz_>0V6fHE&FnEm@JyhG4Y5?@=av}z-ow(W zL3Av2XNvB_%DJ~;yr{xRKItv~@Fbs1^O~9B)N8Bldwts&LWeXPW|xTcD@*$XR*p9N zEK@+NPbxN+L-hGb`~`W+%Xc%}=~K$FT&x9Beg6RKLY(1%IXDZ~IT;{kyd2XQs8{xK z+5UTezwpOS5}J4QGtRkvplZ`J%^Y@@%NE;!Sli3fD&CGa4t+<>Q~2XlwvN`*#X35* z#4;+ybsiYT>KkqkCl~{%IOjYH;Kf&UV&M8a{J*DvnbS@jvQ2f<)B3mIMc|3FxO_np zX;*g%ZyYxey{yu1J6L&veq+woUOv6+#un#R(ywOJmrZH3`-`6?ggD3tJIPVXk<*-d zdety*f)Vok-7-5jZ>1Xj zoyoP5;y7i$vxQOPaJZh^1m$EwkUI7Ir>=WdT~tw&xBkBao^3{Yt^WY8>;4#xc52q? zEKeY~F%cH_J9l7!Pfu+B07F@^*<3tM9I%qoK&-N!Gv7Yg1E0WGT^dfDRodR#TW^-8 zGn{YA;$qxSDH7dJbG;#7loNrR@G;-7L&(P@jAGuX((3*gwVFo-+A;$ZgU3K|gWEo} z+fEU2vwxRQQ&iHDZYzK5U)19@)JZQQxsGkD(QJ7LJ9s|5`*iF1*L~s3!6l{Dt-RZ< zt>i+?PYscbWc@#Gt(>tpG;WU;uqOKTA686s!AP#LCRdVlqWRhLj#xZgZLT*ml~ z269NwKAdCnHPufK1$S-!Tl)DQJ!d6mUbkEzySkKO;NnPz1_wAC@!$3JrmXYpSF=j8 zs@toOV;}_p4*5S`J?ojpIIAFvchu)U))9lR* z7GrEBe4aMoeSgTUt3g7WIqu~oyv}1@GqfV+<|~O59jcyS+P?TuIqU1vsoEshb4PI% zp);ve+Q&Ie;GgCB`qz-DKWECi{rm5+?80%BHFo)a1NA$pY$UvEsMJR}+Icv~pwH9O z1M6AIG>>I1<+_Ct;YT5qpRcbyJ7=2n@k)G-4gQBkH60|M;BuEb6dJ~?x|Xo9n>$Rr zv7-X_FPw<;oTxmOJmhhVns$Y(+}`V^?(PU~Qrwv!w^iE;05TPE{5d_k_s&gu_i&`5 zx-0zeZ_D#%Wa=qLeRlr0U9olU=?|S|w;^wwT-0aS6*Bai7^ji#J+ z9R}w58~CkaCTW?LE!$HhU?}Qy+x5tfYU)E9pC|iLO$Yqu~W}A>3T-L908;a4fGGk2dOp9yUjoHh%MuVPi9NhN)k_5NopV&@{X5`Cg6FXu)` z<&!a}$!7zg$6#@s`_wn^3#;F;92s3Bp5u8N5M+qs`W6}dDXP5ujs2^BD*phL&Zw?g zKQGfy&cSn}BoUJCg?5PWssHhCIq|}5*uk!K+KA}l$BG5I3%7z;Cu1g zHLT+qPnW6JhpTuuC7}C_JA7$<6DW??2@q(*g4>2$k)B8=BLsjbn_A10YXZ6?(jgnZ zX7bl827U6Mmr71bI$zK6{{V(MSNlU;+9h@UFI((lX_oC2S-F5mb$dKdIj^wlyl;&epy4 z@=o7@JX!*2nlIUnyq7;`X?(JXyO(+0k~5B{uhXSlfeOicX=!aEGaogJk$_KZb{|@s zDprb5Ykm*>j8#u;oaH5J-rZKI{-$lsuELVqiKdwuT&@%hgMu(W4z;DGcy~(EZX}Tm zvQ2*w-lf?5xg~Hjg#(Jtnu_c^KGCZ|1m{*Ux2Ne$$% z+-bT}sh!GPd6Ey6S+^6n81AHJ=}T#(-QLRtw^2fo$>g+<7`BL~Mj0S?1ZS^G(bc<3 zFHh-yrxdwTbC<>aGkZ$X?d>guN>r6*4hY=GbC&O(GRN~hDcXgK7^60%B(Xa(06{p& z-njlD-m1L4wKW*MZT)^n3(}`NmX{XpB$!(25e7pD3hNpBhiD@?=yQ&KowHQ+cx~>M zYn3nOz{V$VNpuGo&#n&E$EQm3D&iCrmw&_Y@@CYa-rWc2*XB!~?CaR@myk(-%bb)7 zI`ryWjQ7oX_lWJ}wvF{DVpdx>Qrp;XP@u2`9tJ?_Ju$_2JV86o6J6iv{{T}=B{ZkX z{{XM*#TzuVySR$LMkCXvU$n+1Wn}~Bc8sYXDBO$(wlGC;Hl8oF(WEvFb2JwId)rSL zUp5sl$~NLjUU>d4rz8$5nvH*J2~nR^zZ-cP%8$RywO70RNUW~)9XG~NUp+01IbBh{{Cf;sq>XioL%{~USaParM-M7?QBV3{JavC|k?Hq$GAzOtX;{gH&UgfM831RDgP!!;-AdwE zW1Sh@+^S4G#x1*%oc#wr*~f8RaEub=U#ID*oT(^Dd%Iuy{{TP0$kY$^ZNyf~ChwV< zgY6sgFscFT(Efb!iq(ryShSd|V^!L)q>7yIG1ITpj=Xco#dgq(a`&J0^Zg2)oRdrO z{=crbC~B-H&}|MCE*Xq$PZ(|4JdU{sJwL5<8ex4SMrrO>WLk@vgqxL46kr^5{Cajd z9M^p}%B}uuZ@m#X*(8#^&ac9=M|GxZ5z0((+$a&or1C)eeuwd|J8P%5zP!@!W{`($ zB9Kb2eEo2Kr>O6Z6fB$beg6P7j(TnL%FT5D0D@1WOJStVB)1G3Vc!&m#tF_i2cJRL z+XA1d>y}<3w3gYT#J2J~N0Jw4?T-C%$@*|{T{2E~vc0waH(HHGQ<|xD{eNFBhAj4X z7bYus?n*E2@Y!Mk``dBPJ$c6+eQP&T(oKV*a2S-yDINjK4xvx!$RpHNSCy{)H^1Q0 zI%8FQ3ETSqy?l>ahvKip%`Z%YOo!r!hUU9w%(KU;K+%jIKs&MAbUCY5zZ5Kb(>%l9W(QPo|VyusR+~LZ6=Y;Qk_S4%HPSICXMm0;OeZf+48!li@30p|<#|;N75{h1adIlgDW)@jSAJDrR(P){SepyLuV3{ABo5 zac4f6aq%m{Sl$Xqn(ej-&lo%S>G}IsZ-;(0d@Rv5x0>(bCx&h#ml2^Fy}O0uIVa4= z`R2J3P-*XD(2Xh8ykeTY`hUPIc%S0;!mG&G+WbZEl-^{YENiS=F;UN>@%5|+_^a^j z2sBu{bK&i|^CXdVC`4PbKpVGX->>OjPAd-N^btmt17 zz8=!{%5y%tK+xBtv6P)@P>i$8^cg&kj7-Zp3_ygl_!!-%_{~E&K!&`dI80D9uWB7 z@NZACTRX3c-VKUGQ63*$wF;z=RdeQGfDb1mXK*KjULI$G#!nEcQl&Q(l3G2L(j6+4 zmKxHM=5Fs*yWHp}`2PU#OHQ$tQ}K(z5=s?O6?{WzNhFb+2|9e-pFnC$FWLj(bdPT| zzZtv+fS{6W_>RpK;Gwt})GJJRV3vj~J{BiIEaFLfI#MWH%jidLTmFiTX zQoZ2f^=Wm{echMha>1xRYwh`#A^o5}1T0Z8_|5SBcDV|%_?F15YtGP5na3ZmuXG=@ zAHYFzGk?PD_ly z^Zu-jp(ygD{eN4JgZ6;<5gn38aq+9b61kY*9}?MNM&d(%tn3YELGhpVc#7`gL-CWq zn`4EejQ;?_M`iN{C7&O?Y_}SnYqFF6h%bUa&k^qs0-GkYswm3wYkO&Ktm~^*oZ}fetG_k_Dp%e0BI7vqw4j z&ER9Xinsh!Hiv?^ApHF}%}gOzp3{r_yFc~Hbq^%da**`zaa|qOf zZ(g0px5ux6i35iC(co;b!Ow_n@s0<1J%vFR?FaBa;K3sNYw$W4WN6Djh%CV>MmK+~ z?T^;H>`ZY|vZV=Mrj6|M*w&h*Cw^qtuaN6ckKY86=gx18o(0U&s>l<>R)6adoG=1T z0Uy$$z4+PiPEA7bwEO` zvArqMrzg!N_pX*J+5B<%EpHy0@_bnEUzrQd^R~Haae`P9JkB>BbMK6LaC-N~zlLXD zI<}YbFT*Vj^|`mYjkSAnpobet22YzHo}2(HpESZ^t3sQNDK@{l-`S6sbz>THf~z;o ztiE_N}LUNbvkpF>7OKHmz_zYWVx>8S0k8M1M?csKuiPz$nfMJ0kxAEqP zv4#u~YH*#Uf!w*@f--VFGuYQ7;(v&K8b})6*TvdI=%%jBnrXa4q?bah0KbjZcLBT=&pe)U_2U?* zw9gy(S>{-8JV~UBd0m4kzKt?T$3Hg%la_A3LNVDqC1nPq7u9V40LXRT+aAOi#z9ll8R^IbfOE}v8Yhl?1}?31>3nhF^@C!xl1r(> zwl)W%<$yf){Byw-yP;E+UJvg6tW9?XZeGv+0Z+$%J@6CDG19zmqDsL^7Kc=YgD!di z8}l9ghADhE^ZMCBKKIzErj{LJbv z-KMwKxBNf(mM=VY;CZx%wS&hR6B~Ja%>MvrKv4Q)4gEO$>H5FMF9=`g`hJ}Ui*!W$ zG=5&j)FC6&KYIYbm0 z9SPbSILEJFZYw8V_>J(&e-gH#4~_I9s^N^0>QNot$QW(^G81; z=WQ*_FBAMk@LMaspW_V*SmZ#vS5SqDjGT-H{5U=F)0)rIJ|p-p#wD2eqe&ZB0tMVV zh$GW+C;tGfbIu97HFToh{V(aWOzVyPnu=?n`|pXq8F%|tw~O>uU|LO|Zj6%H$3HRs zIsR34>*7CwuXN;&^Tql+jsq6|0850DJqXXY)6;{+{_;`0m-YVuZ&*@-x|Cm$|JmQ% BLF51c literal 0 HcmV?d00001 diff --git a/modules/xphoto/tutorials/Images/baboon_oil_painting_effect.jpg b/modules/xphoto/tutorials/Images/baboon_oil_painting_effect.jpg new file mode 100644 index 0000000000000000000000000000000000000000..4fb033e46c7b2a115e41440c63711af44b52cb45 GIT binary patch literal 114971 zcmbTdWmFtb@HV=*y9C$8-5ml+&;Y^Rf(6LpfyFIAa9G?!aCdiG9D>8*9yE(Xu*>iN zo_p_?`{BNC&FMZfXKLouGu>yp>Z$6NrI$?rzOuZMJOBX!06=&>052s zm}sbI|D*E1)xGop2+$D$hyWx61^^-f0ulkj%K(7()lQWEG4Ivb|0M{BNXRItXs>2q zy(%=~znYJP^lCK9tHrO{ey{fd$OI^a^n9|YL>d-o3@*g{K?!;2jB>TTB%0H3pulI> zU<^#sH)P}#Ow25-Z0v$U!Xlz#;_u#nkXKMtQr6Pe(bdy8FtoI?wz2(UXYc0z&BGJy ziXvP?*89@xDZ}({@?QdiHqPB7vg_ofc76Q1Vqo*hD3mj zLeGavD64^H;X=f~AB0XUmylQ6i@_+M2`BmNI*myR6x?Du{}0;#Ap8FZEcpKj+5ZFV z|HTCZU?U;C4jvK#KnCzQ*nBSC=|*M9U@z0o#PI$CVTcYlQvc>K@w(b%`WX|fw_P0h zZHnyASP9sv*PE#r=0EFWK0Z5DM{uJ}IR3qTYnVP3x5wGUVd_z2la}a6IR5yP0eQa} zR}v3}8*-V}7aKZGFa8qb97QRgDBlKAB#!8(>^$3Iu362>*fL0-s~RdGQnooT8-Aj6E4jH|F9S*v=J$ANSfja z?dzN5q7XYf`y93ZU6=%7Vr#vbt*_plU7oK69OnhlpG#!2)@xaEZ|d8` z&pz5^T*?YF(Z@>%h@nM4IgAB-2DxoH{ivw)$340gftwwrUW{=Sc+Ns^u~W)Ufo?_> zHpI+~-?@!2Wo>XmuA%9hv>1o@{U}8#CZHYku%msYr9i$*a`LFG03xfz5wZO)2lBX* zvO?y+Z@x9bK(}65jRglxZhIxqXkfg}<|si`a>wg!r|KvuGlc8VnFfKz|3jZS1k6&z zK?@DQ+P~{Avb*iZ^5x-7ePF(DKbAlyT(g+N_o#u+8&Em-BeZ$`+kigfOiRiZuA0e& za{g@;It1~)q}jG94G*(OJB{lALgH`t zKWK&OJ|%A@mE7{BuC&yO6qt&hj!WW8J>Fg7%1(OI2xRau$1cnmwTcliZ|9feZh9Oh zPKtYP(sC1JRF414nn{ARg4FhKVt;io-niT`ZslV5ew}}2^nG`SwWCTT8~(mY^^Mvy zwA;F=rL|GR8R|E>n|Jvcy0Gt?%lRwvNfpvyr?XA}In2X(EX9^rz|#3?WUN1DY~c)kOae;2Oi5JSN<%h|zLYGUW@YO-!< z1WZ8SYaE-{gEG9gs~LQ2UJDuSx*@ojb$mFyH@kcsXVLuaoi+3bq>yxu_{+21gu_`| z(wh9KHfB_q-;12Kq#Ap%`r1gPr9*)pf9 zGC*Ug`+oF|^`Sp@;hj64M*izoKbIL)$M+S2b0-!JT7ay#%}|Zkz)>2}tDH@FTg~{D z6`4O`zpkcW-cx?|>vltf3jM`;o)mtjgjdIQ1Z+Fu{2{t?8g!G1a6e`FP~Q=*K{fSKXUx4oUo1jW*5`A#-yI9sMF)mJd$jt(01WCsf;k!n} z5Mmz_fp|n#rW)d%V`q)1&MPtYF2z4_(rq*Ttji7=HiZt`i$;F5Dv^`J1rT-4$%Od& z$qHe`hltN>7&<$h3YEtjgnv7Ds=FionU)ohoqL+~3@6inFa_&E*gzdEc}XLXX-GRd z;4&!dI)|sl2@C8xHBe`=BGkE&g2eIWKARjaY{kFnx9N5D*O`1`s)vRzvalCG`o3OiQB&(BG;=$E3e5j(6=l?9 z!lISo*;dog7&Zzc2VTfpkZnFD002~=ujcJUp;eEp*5~_)CHCvQv+~K?Mk^61PuvuA z3G{fZ%3>={ihtUjO8j&4itSN?)7ef>rwCrs7#m2RE#<5EGEuuXn)z1?8%Xh-Z z{f6>+ZcZ+wkxjMAwOjeEI{o~0IS5p?B@!;tL?)oWkqz0N&=kECc-OB*aqT>iMGp2* zA{HPICi17^-kdCacoVFn@}>j@8 zS-fJ;B$=*q)_O|oksLv^So%>8*P>82{+*?414#96ezdV)u&@=>WDb5eg6%R!i1rn8 z_HOw>f3O_f_0-TE_Ds`7>YcQpyJ*@Y;=itvM&$7OyJ{?SA1JKL-Su_zvC%u3#0$mZ?@Ng^nL;SYtx-9-Cjd9L#+OuYS`M=8GA&&8L1nvrf~C3Z?{UA zBlXkIklz>LmmV5)*;$)T7A?8TFm^RzpEq)R#Wbcy_NpYiVWgMR3kQr?yiqb?S zsY2-^n2#b?WnnYHuayvVoUD8SVeg#Xxo%Hw?e&bb3_-=o>3aRA6a0%oRk>5jyeX)=OfdEmuH9NEp9u}*Wiqpw(r_aLF-MO%jtantZPm<|*AR zHhNX!`*YO#(sfCOFP>yU_d7rUI`Sq#u&32uCB#WgI>?2 zMLglx5|!RcDQ8Lr@k*3NU$t$-fWEssCD*-$@QNu<>iMyL41y{0SYb`MGwuOgFDlEd zCwmqNnQv(wLfi_Bg>#Ku%rhgiN}0EXHRMK&bR{Dr2eAkTK|{)%)!g&+*;OP3v9b)q zfds8a?0%wj{yHIU&QUT;>Dn?Abo5^Aid4C3;yxMkGZDgUy<{xs`^juR|B?-*CnM{R z|4|p_4ww-hEiU{s&HZUKCN(%I3&9ADrRNv)`X%?$LS= z4?lf(p8j%Mcec2(C3hsj_-SIJjnR47ij#65!TllW~!pFyPPe{hN@qoCZH@Sq5oKZa#G;v#8w5ki-j#pzMO>=*3XV%FM z_{Qm#2$a6sy5f>mPrW(kBiY<&ASqnP-f=Kem4hiVfw;&&r(@Qd@vFU++zBzR?=N%M zFwEAs&w*9`I_ZcqW%=EOI#o2{0xIdZbNNQ8g52b9RlwVi%onyo^S5=F(vy(*bj4Uc zqQL0PsHG7@7kncwC?+3znH6$`eyle4Xi;LeY;@=iEynubfR_9fqCm!1JobA>rYBzt z%qW>Pk~czS>ciKAi6MF-V0>-YpWKp@%{oa?Z_{AsR%*ty-&kq9s)Qe7nXzLjiunRy zcjRbCZm#mX7pmpTE-EcrQvk*)_dLIi%ASc!{si}~U5PD-M+0K^D>0<(Bat>z(HLP+ z#iLte%YICR28hp!m&v|PX)U;k>yxtR9AJ&B%)8PLYCk1q(ZA| z+Pu}v4lm!)W9utnd;}~_qTkY{RYm&>oL6QM9JOtP3Q_t1Mi;dxZPtjrK;wGIRfv4R zSkxJ?^^^}>KsIE^lp@FHFYfY`9nO3Qmf$5GuOxrIV$es>MO~oc)HrX4Rh|W+uhId;{P`Kysj!0bU|Fc64qaSt)6BqEG93-%I}QvSvHCgK~F9d z4QR0M%yz0V?MQD3HVg(*W+!hZ$=V@%DjxzAI_J*z?v1;!NG*`DIUhkNaf^{n798Wu2l#Xy44f z^#Oh2n)7FfTqobnE|6o61*UhqwY@jK;Ez=!rt-b9aI_}&PSX+2f?SB_;`!3gKN=Mr zd3tvh3TL`_qO27yyF;}emdGW4S3DuaXSd3DQnoLq-Kl@Ni-8*rnexDI!`*2~?5Es* zjbLjn-EoU*@FW++!gl2=j&A}WnpDoaO`j4nZp^~XNGpUo33p602XFp$5Ei)~R*Zv) z3su5&z)5i(h!CY-wDk_gffqp28>kcBUHw3YQ1(;w!fDCsyW*#^L98W);iE1C)x2R8 zuXt$>TrsiBGG$ygt|@MI#Tg|jDFX7F< zqYE(-#w2+ftW2;~D8P=EQl(~uMItFhs?%+2R~)}9W%eCh>MYHs=@O(ZO8AGeRek~2!7ATLWLejA%ERmHFMn$e z{sqAgtNtw7b@NznfFiqWT#p&el?e@oq`=NQ|7Pb2$q3g4GsXdH34hRDR@Q;XJasFh zn_XC?VW#W)fSS^X$&s(q_EeBG1H3ze89vwcT@D=3Xg1o>48ia%C(Ci8*DOZVPZ9*P z053!PX{d}oez*UTW;k+mkckr!dlJk^_uJNtj-|U7Efi#=lS0Wwvtu&P(sW6oUT12rrGi)& zh(AQxs@-FQ^o0zKnj^dU+%sBIrf_-bPZ!TT2sF-l?BrCUn2^UWDxsr@Bsw*h@z@epquJ6Z)`zzYdBz94)&5#0rxG3F`aGY`-zWThGH{UxD5t zjmIc?e9Zo-6urA8??uZkOZh3QR8vj;op&rZh-q$Ll4qL-edUpP4mf9f$pdQq2AM?d zR;(6Z$(|M_PqJ21j*ax9eoqk|;eMP6=BWa9p<2I%*ozm#FnucqJ^4do)2_re&vs%# zNZNQ!qP`QOxUQ(U2#nQ^$unTQkLS?jQla(q!faV!GoNxbM(#=E5du3pdvybUbQo0) zU9dxrw&j?|_3Bx6tETO=8G09u0zAJb;rVylx0|AjT|>97XtR?(bl8M)`))LTtogz&ey7IE_PRa~H59r|n|P%qcWf$teA-$f`@ywZKt7T)&` zj?z2DyH9r}oQ+XZ+(HQ(pArUA5qab20jB^_7gld&6JMEr>HkD%R0=X}y3JGO>Q)SyaDN)svFcN8PSi#^WK%j{T44X?iQ zwluS^%DI2`wuwqV3@r+1BDUQWjiqah|D!tDVl;bvnQr$=41jP-+dx{nLreH(_9qd@F6zD^fnndSPKF=ycA zoLL|o4?&Ks(1zN?kEF<(8;z6Ex5IO$l$0Er-LRIAYxhZW38fkI9Ut)GzLj|H1SFSz zY_FXab@a~oXS z%OFvD?(erwYg~i`*#a7|9(h8EMC#;@?O7HNo)uEmL}l$la7$Dm2zya+5CVG zuDEMS{lVKY3s{jbVdU;*b_&|Wqu6*1nCY-SmoaMZgiGB<2~J44AD55)jL(ZfK57ph zqVa9L(C8f_>K&m97*Hp*d#14y-0{kj%B~JCj{79s#nx;gG_|zE7RC|rVIas+#L;}x zn4!evXj}cmQ~L|xOLgco-JMS1s}Eird(}SS%H@jH=Uzhk&H*tZ_U_=*7;^B3s53=i z@AEOf|J%Dt|9`7D-c`k=nJdugE&kQUp$zCd&d`u1R5NUWtQ;@kg?}QCI=M3Yuf~op zlK|59d8{Q_q1UUaxAkTp%V_Kj6);7Sv$FiZ*?wI7D|q~_P*THKU&Rk)em;8hd-fI~ zGWM`e&kASYskNwoD1` zUVolGov*ZwRbdm6r*v%_US`*KX{L-X-C^#c1?g$}cr^Ij8w!KQE9u1~bNAhhGW22^ zCCVEkkJf29UH2FzYVR67rnBsz!@Jc)9G8RYWfB)NI{ zR$@g5J3;DI%VMlD1&0tLr-0BPQ5%Q(7AT?R0?5RWp zaNNh105*c1O^C5e4=|^Arp)vXGCHK0VubFyJr+W5{zej4+Bl)-Z{!v0Tny`))UDW& zdA9B7PMJj13m{UYDFvnpb{oji(myPvDp-k2kvp11Lvl@|vZXrjMFQ%)@{FqU->Cin zQF47| z3C8P3?LUL}Ofp21YBAlKA!t$(1X&MSH@|)A!RA)^6>75s8#ulSRbYc}>4Fa}U+L3S z+}v*D1{p6#a7%FS-|U;E%L9N1nD!O4SjBKESJPutwz-Dg6j^j>_2uv1tHc#4{gIyb z9y+pu`Nf``wrwMXoG^#BuG=$4&)E7#yo%TOflb>mR&4G-#N`W(2(E^#m=-9}tGi6% zYjDo6&3yj)Z>y+Nr6Qf6iy<2#Btggy1H{qcUML1chMPt%@M!6TLJe3PO`QIb33t)P z`gy2utQoF5=rvn=HHou}=`G(jk;0spsoc@3I4lQX)i+PatF^8l+r|3UOxosDyV$l@RRK=KvDY8gPa08DvQD@Qb=E6;FDc_3 z)fZt!Eq>erR5854d_gYEr;jPn&7X(>WS1$rtjoZriV;)_>H?a`v?( ze=z*0+Dei5aX{TwkdsUj?YgnzSH$!Qo zYU#QD9(CS3vN}>Plll!Z^a3Us4P+L^x5A^l$Br6bAN=j1B1boODguC0Wu z9GU2xf&-fCQtuS`X~WxrXRGl622xMikdUQ>6*Q`c>oNu-O4mxiSyGF-nq?xWd8sDCJnh$4IOkRD~Mp zi3hPqq}%~oVhi|fOv8`A?qgis5>L8}oPUBGxso@dyg?jv{N*IWF9028EQBe$2R2`d z^Ul=%H7BU|n}KW^7Kd^$K|><)g}h~ZW6lSM;Vea@59C^ol$H@mIbfQVty8W}q<3-vkL&ktsN8vy&|Q!m$yAwjf3P!}v~G@oAh}Tt zXPOK@ZS@83Ie+}3DfH+@Xa*?{Y_jA>K0RpKl*ftB2(NerJPt<8Eg_;BIU{T<2uk)MUKL zRn>=)sSS0VYd)5rXo8A$2fS%h_xRzwe;Y66r?4siUDURToEROi67@|zQyks{ z+N2H*KBUqZJRPzL6ZsjX{77<@h99#2*#e7kmA*|DS^bm-%6xSyV}GUNct)9mLiRmD z_kY@nR6#ZihjcCRqszFFikK4auhgl%d|R$sLsDNsIY2lOvKsHIuGRn%UPeUW#5)h^ z`FD^p+O+FF7WMve^O z83`u0Wc}$o#1ym{?LM(aw2c?tfyCL|MKz~8e+G;xN@3N>9{5Vd=0T3B95afJON=^9 zR;5W|bB=jTiNH~KxFT}z5fH(kXMv^cft8c@PrRi)H@ z;i;#k+b;l&4{jCUA*Ed740-+2Q(gU2%LrT*0e%idSWz@l9{G##DGDe8X4<1>y4Fk|ud!mxZRrJGAs$%B33b?#sqUQg`M zRIgp;L3AbP-j|VGKDzVkz3OQrnK!!jgPl~31rntT};q7O%1&~1{`NtUS$!V|8XRPEQ zWWDJftwYpQ zyfVNAQd4>XNVz&1aGhZ@TZ1|caAkKE>T^8Pln>R_-@9v$^74TFIdAcP zyb>o01Kl)tZkq7t!jhGV!XqD=qdB<%*KNft&Hyp?D4WYN5mbiK*J9gf zc^IA9>%8uYXz1{7gf*wK8qM)Zun5FH;r`C=-$m_ zQJr`86`@nCCKsGt{?&~OPQP&^18BhLL(D@)u zi&c=j;(fakR`w0Ch?A>!iT+~p@7>MA;Nst_9ke5}@BkV~za47Zf!AD5Z})dlxq`#5 zWmw0*uxgy{wUS<-zCIAKtGNGhUi ze;V1<52G#@8|fsPBY2#C7EXwcy+dkL_bGc6FvH8%d{AmgWg=AEp79h*VkAK!(T}YT zR?>ioxM_hm`rRb;yss*e51G2pNbnUH2pZ~%8qUZ7yG_o@L6Z)QYGE@QeV+av@t)>H zz&J|Z2{QJcEP|MRB#4MhVwNq9sfq3lZOgR+#6dX4l&N;Hit|b$Lbmhay)bln`E%_6 z)a2;ruaa@PgJMSkQ=;=?_4Zlrim?eBP_<3Y5dsJa>I+?}Zui7?q3|8+rH>WJ_@_Q7 zuKvT_#7(mc?%1#pdd6(zIeV7FHGRgUP0}-j732`(lsfUv!VH(VmedDu}Sg;U<|Jgm9%6WE4z!O7mDdvm(MY_ zSdu?e+myvN6pTa8u|mcU#$y6)`N@2o+n%Ryd|;H1tHoJjpJ><#Ggk+?wBRkY2T+1Z zANmgq?j|{qdF_9%a{8NV>wVcpNLLo%liWPhxmlYOjWN?uY{dF==6+?z9P~N*KIl86 zU9VOH(HPOax1KxOgP~_gw~FtzaMlWF;9`mpO!-Xk0>B=tklpr7-bso`MjO5V{M}MA zUJ;F@wp5xJT;7v|x1gtg&Jxq11o#r|w(>=sx;$0)lXKnbM>+g0w}+zPkB9>CF96CT zkvGy9{j8di4!={}APo3|7o=%&XDC}~$UapxR&WS=KWntSF>uP0 z$$aN}NC#Qh(Z#9ZmWG>4Yr)aJOVjvDbe!uf#&j^2IHZVVkgR9s{b~oMi0m)hHg}H_ z6P77PM|S|CPdrbTHk<=``CsE`^^n)E)os1hfHEy)Q5xfadOcM?P}Tf~#m*q9<0s04 z%<@jp%BB2}lSJm|cuk8kSO%nayRZCw+StA@B6ZT({l1|^`b+tsNv;9Rml+nEFcS**kc;_~$XTuf19BBeRNl-p!?UfZ*FhBuws8q^(>pXrs;1nrarUG+4)TECgs0&72k(unD08K*H{69e-bp49-ifOr~FlbY|sDr zrW^c8n3?d@R$9NC7v(DS&9qlKLuU zzmE>_ze z9&K4HN;XskhKd;li8j>ORaER4MWI3%9Ya-0a&(>!%B={V{}>LpDg8{yIk3;WPeK8( z!uSO?;?<=aZ^6DaG&CnVkW2BWBulKkSFexgqb+1Jg_Za+mPD@l58#oV7`6f4)Fy3? zUo}>7tOtgoedvX{9qJO`DvSl?T>tSwA^T&v_mR?Zr@7E*+U2IG_XUt*dmmW{jH1dh zm~_cvWr^#nSW^7`w~fB(7oy7|IhB7{O_HE4kB8YD{>az!&0yoN_ia}%0GUesF%G#p zLF)*O9>&WO?(3Bg4F)s(dqE8RJp>^e)a(wKnNq?iDMq0%ZRCDLeJkuZ)7I@DvIXxP zK4*@V_!Xpp3Y`Z%w_Jugg*iei?L~oGtcdxNiNuH9<*@Q&nwolP-9ZZJ7=< zCz(XDIuE(KI$n(YZCr;lF7E0!=xi8d86Y6x$gIm02zB*d)Y-zw0pTEDu(6+%i0mel z9SJ}MVpl&$usD1#buG^aIqpU&*~SKB2@^$cV!KQ=YA*5sQ&>A<-X@uk?pnXYFOOH~ z-kSg--V#+j;_==Cg#AtObF18507rwerM$eHuJw*`9=lntZ=|{_S&uo=%3L&suc$vS z^nWDX9G>~n`*mDRAea|d4zB)mxn8+)mkH_>DEiY;A1aFGOy!E^DucbqSj5>4l3(v} zOUCJU_Kxg!@gpfx#{n#XPBuw2i4AFK68heMOyeQ#2(48i}B*04Zl0{ zd-4fjD>|nN{-?@4172oH5i-yrh(zRdR?gMB5|w&8#D;R>DG~ktu^1cuZ}bbmuo;<% zKVmD1UZdShbYq0U3Eq>tbJAPvpsgIN{^OlIm_5#ZOg*16*w?kcsu3upY5U2bDp#kEb95cBjKXB8G`Sbnmfh5Jk>RP=!VgAc{wIl@CZ^zYRV87Dr^-pZ6!jWa8;@vX8?^(a^vOL4~m7XJR0R z=pR&v-@7-0#``BJl~*dAF95#2M8|2pum07Q%PL#@)7x%U1ft$(!b4?COmYaR>Y&R&4~grfFW5#P`rhzUJ5zS z(jl^;YN4~-`r;Fv&A*WW7~8J|fDEw-*Lo#!zG@_vHkLKeb&T`?n8?dSP*4KG4m%pZ?VitCAQRp8OLT_p&rFW_rL^071=h6k`W4%b?4?fC zya2@h>5!jU;@+Ib_cm?D?o?W@f!kGTIv%J`VWk|&amf5si0^Cz)m$ZF+EKuygDL|=4v}6=l;m^&hhVW$ z#g$**hLQw&cSOa`-aeLHH-$k`IX>p?8bb9>iG1Vg4`PBCMY$42$jBc**!6B@a+Fx5 zz|MCGKC~&sA=6EYP`Mi?(`rRuYL0CES(Ymp1+aVp-vSDDaXahm7cy}R^NqRI6Dp=0 z*poT9>g#yfds9&qCHYHfLS;|&M+KbRL^PBQ?fp35XwMkk=dXMoX45(JiND95p45)KZpkLDD!SI=^Ic3X?{d#YsZZYCn9E>&aOxZTq_yQn5_6C6SBXQ)OE$zfr z-XtRPdCdSZsne0^v$${69G3i9e5LPBchn={cb8kw;oI4?{V-^v19u@!Ox3&M^$`(> zGjpWU9EKJfrIk5y&j`6RDYL*q!)}*<_pTTJfSQ)?)Vn`YXa;kCL8m)&4Os172= zs8Xhv^k$vCrRzaHqY}Bft(E5Mbn#m9O3aYW+W1?h5TYYDNtJCAB8@mjKR1n;MvU#Q z<~O7_LF8^pcFq_0$hOGVKhT`f&LGl`4a@~s%ipQA8>CQ&2BgW)_p_XFFQiefastke0>h(Y|KkjC<8DMItkO4AyVUsDe5CmRYJWB1X9)RvPp( z<|lSEcqsBS{Q64cE_`dh(ZbKw$ugk<{c4C1cyanPXOuT^9wy&cgZUF7*bL{-<)fI> z_h+^_UlD5;&&vXrQ6aJf;8&bG_Ru8kWcrY-Xc}=E5yiX4ZQAd&SZAF1?M`gp8!T;UVl035^vA$&4K8IoA`RV-!@B4ZGHU(oi68MGfMDhxo$p6SGf}8Q{)HR z$kVG_>Y*Yfyf{g{q7lEFu@PWvQMb0=`JZ<9!S@cffD-i^ z1|M*C=?4gsH%vC z<4!gnB*E)P$0siUf(ovo@aHjq`e3$77O|GA3aO=4O~~;K7&Ab>5yQQI^|y z0AGbh_--@m{56Jclun&uNO^^ZvW5y99msmvaV1@0UF@n>^oQ=)p4^eD#HCmHP2Gyx z5N6V0(?Y6L_|`_>lfx!7rd;LQPD$bHhdvW!rkaFgx>$Z|^C*@PM)%>h0hNBDMsFwV zyPduq{;qk!4QvOEwbd`pQ+8!B;{|S(#Fen=2TPFN@b)%Q`gskB-FMus4=-{FxxhECOCSziE zu)@^KlRjFV2(>51jL?xTk6q7EX;<$ztShPTsb>QO!$EvlZR^A|_{t%oyL+-!^J#4D99IlMJDmmY4=W{f62c)l%_kB|Jozzp! zID%bRg1*MIMgURJE+5Mc=g-!9lY2GhEMEYX+9#(cr%wA#bB&CcP-Tq#5Em9OwZOI1 z9reT)IZNCTByz@8kB4(7$t4pr3R4dfil5(WU8CXe*?A3R zLEoIpBUkVv-@gTO)frNPw$y0rI?MKu{ytTz>0%7NAz31i+tTSS}L zK`$JWAaM0BGv9=pr*Z_t{kuJjoagK5yAZi^?sN|3=AY`H$Iuh<+rlkRxEgq|5uo6m zjrCSDLI=_e@gc6h;R$BBGM?h@9VI!DI)-cmrCTbjv#-@iXFHwWUN_S;$2{7k%D}_# z9FKJzENC;IvaLC{8I~U&5LU7)Vlm0osa*abJ*t?_FO)70+>X z@B#ivFetL}TO}e*zIRd|SD@dr+A+UVMI^L=uXL<>#ZI_1fDd%5^7WVQsC;GW(K~bt zG?~jm3D%*lt4I3*&2mkWnrX-bHy3nW?Q!wixas7deiZiKMrN{Y7Csn64 z+7xfK)G~0UQRB2=i{!(~L&@psFYY(KvAsI4ThkzKN9ZvB`6xbxxW`EMk#S429^vtC zM6meyFvZZU00iv|(<;6P`t}WABh>5&oxvZa;LU-J*&jM2e!X+zF7&wdY*xW#YJ(`z zXin~?nA0c#2<1XT0oYh1e{B4LHspyRW7W!7)2*g!3n_~qE>GI(o)O1toKqJ;y6T`A z-P5Y(zq8f{=Le@KaDf3@1otn#CTLNpc@}Pd)DQ(a2J`(@vG`!jz!?QznAiu5OEH_3 zU4Afh`@OZ3U@{P@608Ou8NNb_bvT|{=^p4_G6Qf6)>`ks0KOijEcn}|H;=%eJN~?$ z0VON3($8*Cya9oAL6=ngUK-bWf15K$mq5~PyZ8uv zD5|{l*YmsUDj)gooM%C!lK1RCoTI(&H9B1uUjTC$n}_zEr2Ffl+>XEBTSSM&gq*&{ zp{HnQA-xB2eOqx~*oL)pl ztUy^{Y)Fxs%XO9T=*5i7E^OFnjBG^fw=xqYJDVnoZr1={5&LlQT zDx=5Sq3W6X2H@PAj|P&v7h`y=poe^ywH%4dxI?|OYvu>qrF>H|z{C*(OUo^7vezX< zPs|=VIqf@K=n!!q)yer^2cGTXUwu8hp}lptFuA@1X1NSwT;nayR-sr zkNpz3XhoQQxZchaLq-F)gF&kl;IaW%e+o6Vg>6Kf3rIT*xq_~ueT zsX^TkX_Na2ln`NdR-87#eWQ~QoCslX6{nb(msI^$_|-(ovZeJ)|K#+l)2b3(*Pdnt z2DR*8sDjYUqmruI+uw~mm`CEaDQ)ZR4y8l>Jfw0H$O8F!m_HP`zU9b;t_0$`il$9N zM1S!lU^58O^Z;a%zil1$lC?Ii7*Uc^jO#^06yXet$^*U&C`$xA*yTB$?TfEdqfX=` zvl=Wg;BZd6E$G=q(UtAOa0ml6Oe@9^$ywS_=ksLU7oebcq+NJA0(?nNDY=o+#YPxq zQklCy23S-!0Dy2uguSmpw zibK#=>yw_cYlppbsqzTZG@D7$={y&=p9sdM-o*(o^C|Sb+a)Y3$h_c{+9kT0T|b>JKzra6+o&xw;;O`AL!)sXe_pp821_KeKTH{rTAk_ zHq#ym4|MLV zjO?CCTy1ToNzYv1@!0mRo5NlRJ~q~^d@E&gmd`jSvp6gf6mL9dlZ4~n9FDZ-M$oc1 zr-+>2y!1J54fuZJ#F~fLE$2w~ruTQx3y=-~>UrtM*1hY%+O5ySJ#yDo()$3P=`zib__-kU`HSun{apEYhtS3QdE|?%>Q9Zh>k(HH< zZmb~PpZu>&)B*k*8kR)KdC<8l}cQc`W!Gpw_Exxa1@!Idn z)}V^!NagVH4Ew-!^9S09EDL9;=RDRoz|Vqm=-;$$o`rL&!>A{RwKs~^;#)}3BoNIc zxeJG7U{RPh?1IWSV<3FSCDNBPmWFXu<946seN$&-(P=Sh*Dsb^WsXLP%Ja7bsTd>J z^{x}+{8DM&AJVlLJd+i@*@k0tdWj)MiI2!-b@LxFugVKK8Neqs*6F?=)HDwqSa?@b zv9gu53)`oPDX#wjdF3?nuzjl=0s;_Mb1q8l<8K`-TIRc_S!;HWrrF1++Q~7~oJWg! zV>mDu+Cy=@Rr}>%9Bt2yDvp;++^EJfT*n>o1H^tA&^`|8ek#;%CUu)pNPMMP#@Qrf zf*65SDz5S}g2|ns(6Ja8y{UN4WQJ9S#^MH@qc*8M`_1-a8>^llJIN{!JvkjRD^B9u zP`~&+b)(CrX?mWgZGRo?kriz=(n;F?0PQN{%JW%vu-(q`?7ul}%uj)M`}U~tSBAAu z?2TR*n^Lp7o()FNNfJ($vqt3#nP*5hgX*ez2b^HGaii^JYiw$rtdQ@E15($#Z>e~W z`qutpk)z$*ogge2SP96NcmxEGoFM_Qq~(Qp5A8?d4Ie|by!d=B(RD#_3tnl_+vCeG z9CCT)MP0HMM1gU*;A5r;uco{=;=5lL_!8gZRBJ7!mvW8-_w2Fl*(r#IJBp03P9r%j=KHFZ6=etXVG34{i1wT;hT*&!ag7IMuyfB z-H2Druxp2aI~Oi?Or^%`f(JNnlrvygqTl>ry8_oi)cj3nCC0GN6}mxf<@wuVXOm(! zSrcz3e=G8W**yHoY2eL%eOezDY91=oCuuGqytvb^?5zx*Vluwn(1lfe2VKfYQo(^G zL9UC$wto=3cdThzN5hQ@;k6hij^|Eeb_|PfS1lizxHyciQdQ2vs!mSO!{w)z-fGre z-kbW_9*s)TX(c1vJ`d}E74E!vY_(s9+P;OP4Ml~vsbzO(cWtRaq4}ON!dMlzL{y@) z27j5ARrhtj2RskrZwdTC(KRi1;s&RD+Ch=^EmnOgVO>?7RUdj3I{@DyQ5oIxoyGVy z%l^+c{{Xb7gXNb@_|D!KlT3SNk|?yxi(C3qPvDa!7$8&ik(LBtg{H<{N zoQ|BI^NLG5yPG*ombX$u%%w}kAybd2uK?A)C45!6&~(<(?sa2(HSFReZwyTw(WGD! zsIUfa^@po44H-Q^+w>QJZfe8Y* z$^)n>3NZ>KRs{UHILj{4<~KIJ5{kmlTe9(lx`{9#y|9Yd#P+0ZQeSjISd|AG9fm^| zB#>*r@n6H=hPRrOsXv8olIm-}wNHC%GpZBGXpTu$55G7H5AOa_pd9V^_k1Q+TX-lE}3QxmCnBu zmoSY@E%(Vf$0Yv%zn^kLnI1#E!9>n+wQ*mhz8JF5;jq`> zC{GBBxZoBfDvo%~bDF1(t?qSMw7m_IODicBIT>LwZ+|W)&Ivn--uZGA@&F$$=ld+G ztt>rHYQEC9q02grP3hS9-}Z+6l(h@5+D?6U!QTtCh;%E9n>n<=kVG`|<=dh+nG889 zo_6xeR0k`_WzJ;yk^3w7M_l+tF1MvvTljxa)9i%v2(*a7k~>wpAvoBDS)9))AH}_kNY@$ zLHIl3N7XNUCoPwTZZ%u0Zw*azaIHPeDCcaBfwuz5<&%|8yeQ_r@bE9hxV2jw?Mp$o zx=AhNYiS_V?e<~gKz6VUO5-7Yx#GOT_K486pV}{0@MncJiy7ZU(zRrs@=5e7xST`? zSGEj_iyAr%7sD_iaM6Ip`DZU-SzA;rE;dxFUF?2$NgKrGHyo)T;O4G)f5d(v@RqL+ zh&(H=Ug?+i`@D&NscDD-DZ6um&Ua6*iH7d5W;QZ5Hq56IB=k|-U z@t=*Y{2OQD9|2xLG}5FJX`VeddW`6Z?5-_V&?zJ?Sb4u740kr)o7JoFyTSf8@o&Sg z71{XL!CL(KcB!Y_dA6696VbM|8A$F2BEUha2HDXjG?-oN3feTbfZyN$jJw+G}3AtzS=2*HdJWU6~jJ+@)4B z+p~{Ooh#?Bi$Ava?CarQ2v1L;nGsl##bL|AjXm_%7Pa~W4yNFtg3eI z$Oq@&_$UYMhvPqpUla8og+2IdC^DAhq)!J_Rd0b24 z9O>dGh0EZYjpF9-y{&lJt6ASyd)oG~=${dOGWet7wxB#;e`rr>0JIk((IN_p z?7?voC_glf&JSL^S3KIKr1r^oZ)Vp~VVv=_0KHE?ddB-s2~c_GCnvwJ*1vG}7+f3`I%!5R*(8!n(OCSBy;;_r zs#TMep6$E0>i0YE2qpc;fj_dXFD+w=@&qdITCU^`8kbha12!@VJoB9L08bd$G*hNX%IzgrCQp+yHY!JR2j|yPz6@;J;b9zx{ft0 zHj(mn1I?G)`?n@ZZ zZ;$t5C>g*E4oSg1bNGKcy>EFlqBM?JoG;9O3dXj%yN)zl*k5^Ho1r<$^!zJtPOv(p z2_3cUNh`{+tW2-C^viszMgYk?=K%53K5bbwxs6;hmXX}CI=!vi*~-Yx8*O5l#z$Oa zQf^YfWak;hc4Oggoq48P-rZ|a#dPr~k=gQ+xA8wD5_##yNaqqwd$AwyPeEDrz#isz5}nN%^p>Gl9l_ znH=C}oQ(efi2gh9_ltDV1(v57c=skHx0m;->mE)380UD#@8Ql)MRe1Q>&0^;hP`~lW_=xs0c+&aw?Re^OGouUEoh0)KMJMJ!7XXp~0000TtD4lWB(pKJXoRplu<6pS z+UfHxyWj=#$stMPg5AF{Oq$4CffTSa4cq~qzlD0yjACUO-EVUOyB~r702#g`d;;-+ z@$bVeO5O{`hwS%JUE3^?U0eB)$k4bTl~ysREQMSSj4PLx#x#rfQ>>4_fQ&J>*XvGz z3wR4k!9dAkPXem87Y&Z1Diz?T2`euI; z(>&i9>e`ou?<0Z}JQuoT*D*Y-r+ULBx;b@1F}cz*!IXvS7p3qw?YsLZ{7v!Ihk<-2 z@pdWo4O;KWv4VXn?%U0ff>i^}5~k)qDyd*uh)_2$2l9TjJSpOhcfkHB(|l>+d+)O9 zdOo2I?wxbxEBQ0T;z-|Xf~|&7aKM9(K^6ICJHaj)uNsrW)vF1#`ByYt6SkMU9Ibu* z>-J~p7+yQgV&bbp5=(bycDn5(uWhtHX8cR4=sp$H>~t+-U9y8x)ml-cX_MYZ9QVR7 z45k#2sgq)m&4Kc%$;Ekh#Se|23iORS$HhA5i}d>oOT9U+tZr^^Q#bGcAAAZ4GYm43 z;bJ`5#BSLL0*7yzMidfw zr^7xBys6T!jl?HWFME>qyS|aSS5~&^Yjd9`$7Cc_<5}Dv&xy;!T!!$>YgfF?Kbush#xy9fzI`YT9qv#mql%UN99$qlC3+ZeY^gq zFUMa9>H6l0YpR_-+wB(jv5BrQIR^+sVn4T9lai!X%Mc zuK3k=9Ii?4f<71c+2g+y{6xPVC%Cjo?~Kuf{>+Wz^3`Ky=m{)NMp?Ho-~tzl!kUVS z&Y{U-_Vbxnfr#Nei(@sSR0rEv1-E8pU+W zyPG{i<~wB7CAVmvIb4{;a)9iLz^RvDJDEuNhVPfwE&dXC3J5|^q&&Mp-7J?<0(IJ-YC1XT(Bj@;n&9JH5Gsk~J z;^Jd2OW%8$D$-HZ^eArOyo_AiTqKD3!^Xg==e9Vg?X=$t!{RG{5^A3b6ScK7Wb z9e!8BmmkB2lL3z0x2Y9G3=9*WdLK>HE*U^5!4qgLBB%g%=N0nxVxxYhk&~#cvB~RN zAH_5A0{-_!(OgX()UsM%y{tg_WscpmIOht$0lOe^fwu$HC4>zwZ+wHV#w_l1W_l2N^%Yed||I(%#`DiB!cRt|fB0 zF~+BJoxSh@IO=hVVFJ8O=IFKd2aXV)3vp{7jFVcp$iD)c-bFmzyvD| zz?CNkxK&xxsG2I2q}lQnos|9`_&;JtiVGLY$DNOghpf-WHU5m1pt-Zk?Xi(vpyo}km-Io zzSH8cOBlqcR^4TJ768btfXvLq4EHQ?+?wfpd*N?|el^$bw6BI*4TM@!&m4BTtTNq; zlE&SfBa4P$6v&U!0m6=X=ia9!O*H)7^w8;&QcK9ItoT)YQ)6Y~sXS-m53=Z*mBjYf z7Iwlbs4rf1k)9zO0zyQai69-Ma8xT-f$Gx9;X5d=;)Zfrt)5ge6#MAz0pp=i2+w1h z_T3{!@cx&r+juL*@ae4#Eq6AbYd&5XC7tcTC?@LrBZ&quPSf|fHL2q-3;ZIxu$ITg zdQO{qvBl=?dQ^bNpTZe z%PF^%HrZiG8Qr5tO{5LdG0EI;O7zA&3`ILmRHH3*{a5IEGp86v>7Qp_>F`UbTM=fZ z7|3QJI42xr{cFwsCwK?Odf$tuy3(|DlF<<(wjyYg3IN-hF1u z+HVotUfqo%dx0(HqbK?jhn%91$Edgp~c8~jf2<+4rVzl_hSTA+q)NtaD@o(e+AdFX}S>H>i-zC+SnJv@#fn$O;`LN6s zlZ83Ll1~GtYV)xQSbR?--42>gmp0@S+h9y804IzLl20Dztw^@_AyO$UQ@#5mKYwA{q;CX;oo z=+kL-QQ9=}Z7~b`R+=s9!G={?PI5RPf~N#$7_Tq7@YbQ>txD=0O3Fwjxs_%i<<5Y_bTVd5V$|3lO860h3rC5j3m+ z01)_S+i89_x6$Bd+k0_6q;thQEDAJDxtC}pkC-q$yYbe`;n;NzB--j$spc{e=#!G9 z=Z~1E_B}s7{CqaDomy`T!)fN3#MZXa8-S`NaAQJuM#@G{B&h=fD8nj#%Lz9%Yn)t; zT@RYz_+PDQ-x2IQ6x!C6b3DLIw>EPbVcMaXjIwfYjlohgjPaVu_^V;4X9~3?wc-n0y%f(`QTkB|U?5?h%gw3-L6Dw?q zRDAKb@bn4JOJ~Bof8yOk$J+j}0pcOwnMAeBCq_t%cKj}h2gJ+`0Y zkFrCiD%!&}taDq5m3+onzjGcpl3eCOGIDn?$sSj%thZ)+>#5PCmG{dus!OvIlEt|s zli%L4qdC%rmdCAu#7c~Pp6K}jQZ~SHM8Z#S6E(%cqJldA0zVZice;BQ^#TF@V~*IBlsJ`9w_mzi6QWx zgLL6{s9(n-Lu_S4-U2hX%;YG-sXUR>@UNgB_DAstguWZY;#qZBuQiCRAZc`4T{OF+ zw#9hEB#a+s=F0#<+D`+gvG`;5QT>}f0(?WhyZC+MeREpY?6+El)-B`mZNGT&&9#Ip z`{gSdZVUq~&H!(lZ(ZUmjUsOgM3HOPT4mSTWRTxk!5qGHK3HIbcx7B{k+ZR~4mjY9 zu~GK$vR~$N*TyL?a`yE8v_4P2(>zz}s#+Y>Yu1~+?Wu{Vz_#}W z3vzH2WWQYg6p=*?j6t1)JDh&)KQwz_GZ zZNo?vyv?!IWZTFJD)>@a;YUA_B(%ve-AIbORs6^c3mx+cP~0b zk^$way9QPSe-bWO70ZqfO6Z@!UMT+ngz6hl5Vf(95-Wi;TVskyv(wsLKpN>bdhXw-mk{{SfYvIy_kX9JF&$4q|_>SER#`*_`=Of}Sn zL$(!mjt*Fp)4mOSmM0k0-L^;FVX|6tr5n9>{{Vnjx6t&-?NMfpy$?G?GRJ0e3Cj@-o;5 z+awN^kKtWs{t(?G#G1yXrC!R1#dl2{R?u#eMI``b1dNUkKE|=bV%0}1ON&G!Y;!WM z7#=gnO8bLO_$8t09vRhi7Spu&TJjf;+V))zBQ>i?UwcNwYh`y3nLj2MuG}A#zi6+7 zFYsgHM7|nLVBcF^+l$*7X=I2qusDcsib0m!_X+9EVb{<uFWAdUL2=}*D95b(7K|NlJ)$DOq z#m@~wRV|`deo1c66xV(h>fRc<`zE_%ZnBw-PR(+FM<5N9Es!!co+p+e-bauA z8~A4G#iBbuvsA?ECPoP{tZYWz+-Dq*Opcr3Pwb;F!zncw?L0fDT79$0+5ayDgOWj@c1XBc&}6OZSTR42TNr&tX9@K6#f~tnIbAfG~3(|8Hr(x zX9_vz1I@lE{{X=(wJ#F*U}?Sr@VCRAGWgxb{{U?kj|0Sul6Ev!+1;I^1QCLJ;EjLP z-0eGkUS0NU^Zd6xI(%o6O=(su{@zdWKQYtbcf?rM%If1ohFg2MBe)-A)$Jv9jk(&v zWj<7x>l^KL<8q4o*Y-5=FYHh7e?;&-kB7Vk;_Wx$9J+0;o8qq#Nh0jO^QKwuZGUlc z7iXM8MJJWKBvC6qH#o8X01kfrpsh5;ztX-Z_(?T2x(aPx;_JvT?auQrk&@f6JhL9$ zbG!I!$^J2Tv&9GECxgBfABDOvfpzZ$Y4$o+scnC6W~qIuCeYXSb4d!vEOP-F{qsu> z!q2>RhbzKWvv9`0;Be?$n zgmq@(;gT)41}0CHWybB(rsIxOGUTrZ!S(Nq*8czrbX3&*N8=lNO`)7XIJ_NS?opgVPUj@8#q1$UZwWYnbyW#%;4bN?;+gRzc+0PvI zg5o4=ak0Wi1Z=VawUjEhYvZjG;zx@7GiEJxS)+p3?J}6HpjVUv#BXARxf|F5*}ym) zab9$3sXNH$P-{iEsq7yb{BfrILh)oiBGUXvsA_1|K^}cdYnF6xGD1;B$IOa1WGDef zP6sBq`ev!(J4=m0p872=&Ud%--p@(COPFFs%JA{KjGeoR=RD^a#c2FH(C&UAYK3%G z-)(DiAKPV=0E&bYf-)I_+Qa3+&vhKsN)5N5`IIB6$7;F`mvgARB*$+x#J?nx+yxtn z>PrxyWaQ@nXSH^}4E!bG4~9CR@vn$JBiSacWv0nI8bT^bktA{`JA{E{-5CtAtE(R{ z9H_x>Pw;NHd8q2M=(ZQOi({oj1ZLH=yO?eOF>$-jBWTLxaOAI24=0!Xro1=e4NJnm z+mLI>G}{>=X|%_;8EFeNerS`fe|V!|z`!Rt;**N(X0Z~fFJ|4Z{dPNl1$;~J$Hd)U ze+_&!znJPU*geFuM;pZ(LUS9SX$UzxlpZjAz&dW**4%gpTZ>KxdF{hU5;6;%hH?~V z107E|&*NV+e#)8+#=G%$1&d3D@hxm;ns_I-Sy7j6!IfrJIA>n0KNEm{uD4PJX&!h8;(wQW3uh%oSvBH()=5y=$`HAbTB+QzT&{{Y4wBhWOf^Y%ZqEYaGc1&$|{HXy2;h1--I zV{nZ@;{bVe9XgdgoMWr*j+!yDQ*T0-iKQMC@k}WOoA%b9R{I=LeTqAWR!_3a=EEF- z;oT-=*a*qm#O?zf_Ni?ed_1`EEIL)rpDd7~3rouZZ!AtO6LXlsAxjlz$8i4j$b3-n zHNDM;hOc}fqFLI_4V0HRb4_9L+%O2=Feu(&8yJwluGSyIX>Y#YrRc3?VW8=@cDJ|l z+}(YZyvKx3<;@fe`?V3rutq&uq2mECe7dofB;wV(e_p1t>=m{yERa5kY+g~vSRuXy80@Qv5S zsCAp~3TRf=-`bZGYVk*DB(HVmS*FRPGVk1c-T4YY%PW;ES?jp)pM!jS{vgz}jRQiu z)K^cDpwuI<)NQS?AY!U_Tt@j{mQDhL(#H}C zL{T#d7Lj{) zH0a-B=kEFAG3GS>Eu;n@eexU3FW%1YLVM+u6=J_$y;A+V4h8rwFUu`Rn07fIMBHc&0o1{X<&Prh?Jr zwAFOG)q-VqJ1``S5HgJ5fr3Y|=iQ?5oKe}yd3A3hMjHVlJC979=M{(Ip9^?{!YyrY zaJIzxQ3;`n`6ZS&E0T_&0=+Yk3V=Y~-Ax$Y;#V=v0Yzx}IhTIi*O>FWE1GS^U=bqbD@P4(g z={CME{@ID`t`b%z@&>nfGb2btt}>b4TMxB|%r=0apDg$juibcy!v6s9rF3r%H=g>i z)Xn@wiYn}m1Li1Gv;tL&4l$kvIrlAVN%2Ltm2qire`yhHELQJ6B#oJ0e1M=NAN53J z#5pNHGVE2PM7;+S7GxFXqnvfnTRJGTsw zN8S44CmvPd{WAW-+fuPUBc0{Dj`-T%PYSo$M9UyW3;aSb`2mT}+++*^+gSLP-pf$4 z*ED;3h*<*tseaLeafjU7i0WA9EJw|ekTG1Dg#_#Kr*-pIGsDJQjwgL%;|&AFFg=En z^TRtx7)2$ENI(Hbe|M0p&}5!D_O1t8w)n52d`7s_Zc%fVkHr^pTCLu-KUK4u(%(sf zSDxxySml#`p$opZMCT4OA~WzEGlHX zTaBh75P=@n1e_26Ba9L0fpy^U#O52Qp}#i^V{sbXJ&nNxtjbgjWdidcBps?)7Qw|m z;E`A|TFRgS!Rk&q!N47J^!;n4(6rq)#EBx-C%c|lLlmA;{y;x@RPG=K~(j z5~uGsIOQ2~oLuSVK=JuV`;d*2AC&6pYSy@YI6{eviQoY0t5^zr7 zo7GFMI1Zy}$id*_(Y`NgcOD$luQmSw5BMGpZfj}0sqJqrW)c&Cidu4-ZXgbtSEf+QVp;Vth=A8czAc7}$op%P#k*W`>lV)o@d056Ke5X zUTV9{$p)Pby6+BEocU@2EwmGWppr=p$8~hC6jCz0k*gGK$Vkr9f-*f02_K2Cq@x(g zSmmmfHq+IaTHTJD7m2U0^i%d};1P?t;nPg4UBTX}MowBbUBO33$;l@e^Z1I^c97j_ zGCL#u;!wnfI8rcq$i@$*FmZ~t@geOzIp9ryQ-ayu@0HEQ`PqqiLc_Z(P6C3sQGfz~ zFGj}rV} z_?>yC>3%A?lJd?=h*d4`&XeUuaPYf{9vK{V3{0}QU&FEy1jY_cQ=616D^*npUKLqdfuM*qY-~Q770Pu+1-6}_==s((`c`jpS zAtg`W#>`!d00?uHz+y0~c3;?2$BP~E_^0CAq|DOn&F@};f0h#3tLm3M@sbJ-p z1!iW>#rpR}@TY}uE^Kw_{5xkQ=8$ENNx7QZH*pi(->&hRKVI;B#rX!$03{U=f(V8@ps2J+9s*0=vqa)>Dp!F7BJ2w zjKs1@4bT}-12L6jkcLtb7CaD3D_86EJ`KFN{qkPH<=}FgiRtJCa$mGB?786|+GF8l zzYe@s>Sl<%+GXLIZI)MNDWi_$MvR_ePcuGSHpa&zy={!)G^qaWTCI~`uTQws1;!rI zs`jwocAx2Q)qaQKuC1wR`rL_qt=RdOE{tZ9Io36d0;)K{+;O*nLExU5B0VEP)-^d{ z((QCNy}rJ<5m?1%a&pYW1+mrSR@qg@R28FE4;(+=qVV^5*$Kk8^qd0PMeO;fwE$o*cXJpNe78Z0v86`YXw! zj6>!?-fG7q$tnnyf)xw{9mPi9n|eW)l*s+ZspaK~;3Jx^@Zo&wNDm*N-FJW1iZ*llGO6Sdu> zku%90aZ4ic)i^*f+4-3L+<{(+W8lWU)U}Cx7j88jFGkdEY(}*m%pw`qCM;x8=8{pD z4jYyEfZdV-uj4HhbgdvW>T#JF)HEA;Vb4#*bvWtxADPUhhg9uz>+&o;SxGdtEa=zX z9@MRc$A+!77;WQ?VQBRh%N9|c;BFvfFzJEE09RS?>r2yhjb=+-O3h_dgUv$3@IxrZ zGlDtf5PDad_&3Cso)^@mzP-{~^(D4wj4O1|^<_CFLCE76_x7)C_+37W;#>QjKfsn_ zEvLbCDmBl~%R234W5HfK^X3lNC*$$dnx`iTCF`Y+(ek=-op{BkFD0vb9+PXY*b4}u zI))|@sAiHUZ<_--$6wB*i&}*22IXYTggY&}s0+0E=eQr8O<~}B3v?0P?w(!i^KRNY z=Kur7M+dLADp|ZeV`F;FJgEwV-5f$wl0c{_bfr_@e|J;qG1+xmbR3}` zy5FIXta#(ZmR=Cs;k_B|FD0{>$1HJNNa-dH#@dj|rHMJivZ?j!x8~m#cxzGpp?)<@ zbE?APEWGTYnz7H8{`CrB#6m;qI%k39Ln(`}#-3Ymb!lS0`t~V=Wt0v|2 zVAwnpU$EuansqR+o$sggkLRr00aBhWr70^ryE}e9osQSS{{XXIx8r}>KGXJP@UM$> zxi!1*G{JLs=S2izE#$cZLLy?UVnA?#z%B;vxcw;okiTJ%0shHQ-|Ch=Be>VK{aOUK zz16O4qJ?9LB$2{EfHTCb8b2{ijvb*!`EUTl@JGNKokQX+w~V}P`y%{1(yp|xi`tC3 zX0xSf7SUWC4J>Y2%TsoaVq~~`wulvQc9s%(DDkYR^gj13kV!qO_Kp_Fu-G>1)s5z! zji#)v+4a@yugLs2iu0USG7-bjovFC4Wuv>h>bhvO)6V3u+o3qzp!LgORmFlK07gY& z)Z}L;)~bP!PI?Nn5*V$IbBx#A$)?h|@K|*9la0!EtY&bFmD!Lmed(ZJVxJ&mmNAi* z``D&csw(%7QvR^hwE6{pPX64}r;h&sYY!gy+fLk;k?XN(Zj;1O{M%b}wvdc&Ql+4B zK5XErD!Z{?sy-;YdwnV4MRE3kVlqc5LYW7URE7r`!5up0zDxMq`w!?h)}A8q$Ao-k zeGSf`cYUgAwt9xgj#ig0>l>m25KvrzLy|&*K*>KR#n~QXnPB7fc&RA9XR1#{=j-d( z`yLL@uo-qXPPCj{mnwF;)vn%$!x{yxg@Q+>$EB>>+>Pc|S7tm8bF_Bt+wrex_(`sO zFVl4WO3PohTPus{6hmcmJdFZNw(2sd${Q#mxKt}Ma#^xYGhCOAei!Qg3GrT^YiBr; zGj0n@3NBD(!OkN9k^$s{&r{N`>3R-}0^G@WrQGUwJNH`0A{C8OVKO^}0G0(*j9_5C zc>vese#&s0O>BOzDJrns=`{;Kg%^5Wt^WWB^cJ>rydFf?7B3qcf}t3BE1kF|NaHHF z+}O_~8t?uK#T|}`CXolkL9NAW9BCD-mcC53EA!!9SowfA@b3fVQMZcm{Ss-c^J8n_ zsLIKEn@e(yD?*{vgp9FcmM9qY`LI9)3eWK@)*4jzQQ6uuzM>vWsZ57+Zjl%-%eN{F zd(t{ilBnPE=-iK#@sOffE4~Bj#NdcZY64uF~iUvkAC(7)y?owFp z7~I7}g$FxJbe$_$(tJ?*P~U5->1zzIL34D4r=6 z)@}4(6;0tWBv%t!u@lR0Ix-Wql8f^O+#7-j<7v(~&xd#x-%`2ouCbZ`{+{z*Zep;A7J*tt3ff zwrhoL*8XNxh5+s(0FJeRt6cmx(7br^?Hx-Cj;4vnP1~9n1hK{{Sk?-!Nhd z3}BI-Dvy%-b8b2FO|5KI(7Yew9b;d*(H}#dX47PZYETK`-x|m_DO0?uC3B1ujB|?U zyfN_q0K-2IG^@>bMr~Z1@{KfFoQ))k;J4l^Hv(CXOB3zeHEn(%LE(QB-KK+}={i-M znT6tx&?1*ygm-9@a~;Q~F@__KTDklG0FB-+w3=-$>J2*mQdS0gi$)%3-H>n@Mml5V z2LKbza7Ug=sUq(PYK?fi4S?KWg~Jil93Boi z{gtZO?doe8xkB+gyW>CY5#e8knuUe8h5QAm+}m9v$qCdZg56XME>Ol~EtWC^xnm<7 zZU;5zBjN{(Jb&S9{{R>2I(@CHw43F7d-f5|k;MDZN0%{>sHY4-Z09(|bbl2!mXlWS z*M=k1^g}kK9J4|H00|&pvRkA-Xju|Ma>z?MGVSZ;jN^F+%`Ekg73kI)zlJq07QuUD zmX|QV*4Jwyw5Zz@M#Kjwc5nyERfimrU9jbAZ5d7yoH=ZhG`>9@BS_J0bt!x?CB(Oy zid&njB~dJHV{NS=*h@qLo!pFJaqZ_9ZD{ul)(}Y?M;j7pL$KqVuvG`2VO&-BihOl_ zsd@Upj-{SUcVig5zG+Yv7+?{y2hf3n209FFcz<5LzbS92PYljM3oX202I_gh1CE_4 zDP@%?Lsx&i`iM$fGvB{rY4j_9AL>H-;z;l2(>$vME`m81czG8D?rAWJ$`_5RAw30q zroSekB=EkgYYaCA58g#@Ih6;@*uxc4c*pRMPI}kK{{Rd%KZrU{if!(G8$!oYo>jKD zkXgkp*N_|lWm2e0hxxc6ck{P(dar@+{wqWAUe{Xq(PezMT91cJI&6nd9LMLz!B{|; zLZyjq;1t|9V~bp);fAMgXQbW5sNGw`0Ju_* zEWt^3UO~z9QIB4Fvz_E z8~Aet-jbHrS2j0VmY9;wERe>#W8WRdN=YY0^3~Z}8+m3dgmU4p1@T}yh#Gx+xUXoC0m4xY`2(R zc%Ztw5Ug$iAhVo(+>`TRPB|bPkC{JcYu^j}U4VQ>@jaZDclS0Q+4`iq3rRQIW8RX& zo?9%QNsZ%HBxJBG2^m~_ulz3$0MFovwG00M5?X1G9M*APN2p$#ZzW!IjmVR7WC6J3 z9tJl7owf4k$1jZfABXhV6XE`}HCqdrrF|ar?AVHUfQ?E_rDG#tX21xfK69O`kAEwT zNKLI?zF}6L+`0+ji!CoiuwM;nan7k^pc5=lhAo!JasaD9RKEhTCnW9Q6O0Z8VtD)F zbRGxs4xOh>51RzhNhSKEM9PbdMo^Xu%LdMK!0pC(Ei>YmjP-qTNR9MyCD1sD1B8Ww z51DY`zk{J-xn?-#srbW2*0pP=)}_>@yk$-!m5Vy4{uT8claJ<2eRdtmEl)nC9dq7V z+|%(V#u)rvqU*jJ*5F%cC5c~2k{C&m%FK+ZAlyeQ$zVWTrvZrqy!_tYwYu6h+@>Ta zWJW`^bDZFG8Oi+XE^o9QMeULzAMGay`3H7!f)7f(mUofrGu!QwRy#y%8j_~~laGFR z`d3vtbEzw~bGXKqh_B*{gt@$iMVVZSWe!w>hRMh{=xZ{%D^G_S-n%WmpM{~i)ioR0 zNQ+Llv@I(gjUxpECGen}0rx>Y0k5k+VgCU5C%=I{B>XqF_^PS`R)W0V^6&E2%gFpAKjOT95ZAo@+IRP1eZF>Aer&x9>C;57 zZ*CwyW+aX@z#jcDPBHpb`xufrS~$0S!EhU{d93SLqY;EJ{A9K;KbiKeyL(pqKv#7I zNF-;kdg!fHSm(o2l(lHT6K!$FUMXztKFK_w;DT_C-x)vsYO$o+8<{scW-<4UNcv)| z+-Y*P&LAiij{vY3{{TMK;bJPrPnPG=;i*a~O2-lLyWwZU4~%{Y{{VzD;?IMvwY@Fx zVwr8O0R}lxk|ak`uN!UNyOe@e*-66?e>p#EuYsQez5;&K*7|?L{XonKv1Z~d#PTVF~ou5$!y9>+_CjO|3)b`GnC z=D#=NO89&>6;52d_g4O9wcD@Xru}Swx#7lNjmOQ^h( z?}=nnD{=wPOcTdnPo;i~>5}S67-Nh$ zAQA~4XI|O+Dfmjs^sP(AayILSpX^aDBg;hzBOK=kab)er&JQNOPd&y;hFLlDwDd~P ztACes?D$tLjypQ1N;Klut=(y4xApDk<#W^Kk_$zTF#r$&7*IY?F^qnlDj7A2q>$(4 zTzsX6BaiW|Lt_g%vqzA)INouer+SY608B~3wY+K_Ngp#1Fmg!a-2VWcmGL+{#u{_C zbM(A-4$G2BC2rr+JfHS}@QtU5d?dQWlX-U|#+*Bkm7Kan z*F5#+xsQXt544YkKM!=@3243*(X@FI&J(Iz=rJ-|$#fw^l0aYglH{Npx8tv{f2m_v->m{^^x0H{C9R@Ss{3~(pOuM82DPxikIOeNLGQ^%wt}EHW z)u|Mf-`;q*+BBQyQA_1x7W+iq5Kv3wvZg(G>s;0C*V*OU3KFDnTDz*{HS1X8)umNt z;kR;qaNo|pn+H+e(mp>hr)^?kUWL>nG2E(={3mG2{SRv3J}qn74}<(Gac`~7``i0F znC-3QiOS4E0koLO+6iDYxOM6}*MD$Ly18MEfRnrb0IizH@i&LAHSIoaInapip?Kyo zNH;F!+HhEUW4Bz_sfkmT7D|njn$qg)?z;T`{f{pLQZU6u*1sxx+1csmXZd+(d@18^ z0Jn=Z>s@8_nXL`AxsS+I+>&ITTali;dKzrWqxd7hx`vmiYa&mziKA9nj#fvD3WN>V zBn;%^sIOu8)$lI&;a#nct!Z{{tY-@Z_YWe57dU1(ObjC^IOT}iz@NLHCGqcvU&Q(s z*#+o_?DBcaS#k~)zFtTJ?{%-|%tjj>fX39Lh>fLh&fQg$)3N;ng2&;pm}pg_E5ZJs ziNO3Z*L*eL?Ly~L*KMvYWfQY$@>{6=(zfuxg31m<4xsnxT(^wQp{jVNRo88=VxLZ* zQj_fMG=5y9FbqCS=V-|Ri0Y>}JPwb;dJGr(P4=ZF;0+WmzE75{N6H9qn>g+`0P(@C zoipK9t>V2V%Snp)1*e<#m$~wOXbh2!z=Gp&I}i*Gx#&9i7>ZI*N3N?uRBf{Fz>kJH zZO)%<+&n^cu<=SE$z z$Fd@dtbmYQ7Tl~=g0FCE&>(^vXj0nR6^=O6EODZMs-R#12SHvZbvC`Cd}q6pS4*}_ z%|q}1LeaV9v;c@j;wRXO`s+3Qhi?tzQOrLpqharoCs;FrEb;Z!4JRxzwE_M$Dza#H3{9S@!k8 z9k{N$!6|F3>NY+h(>M+|zMhJZJ zatA;N9M?0cc*n$kDW2;}@g}-f#v67Pu-rhbQf1l~c-TvvgPevVCmi!!)90x#d;0r} zjI4U+hOB%rb=^rI)8)OpiuGPbmf1E$-eKhnechz<&Q8pzIK^be;U5I**E+@Sx8c1* zP`HayxFz5cjltyGu}U}$R1kT=0P)i`&v?oS^p6go66qQ|w{gpJ2wAPMi+!Xv@IsI? z!u-IgEI7!fKBH#$cN!(tyq52&T|%jHZmp$>Av0yX$Bt4L7*-?<{G9+b5sHqX&Yp(> z@ngaoABO%b+UPzKyS39Gmge1Tp})EcsWYra0sBLJ=^d378}Bv{WSm#Yzqh}~e~Xd) zK=ChwCAGNl>gb*-iq}e)PS!%omMdnh5`N_uDKDA!pP9=cltxGH!5?RQNAOLqix!uu z_(R6t9@BN1Z*@%vPxxt}d@a!aDfo*}@h^xxGpgxO&poxZq!E3uV>3fCI7N+>R3kKb z&knLE&eCgxzp&J_j~7{3$E|2LGFw?hziEp}2HrT>$bicm+k-27tVkhGrlop@Ia+&7BI#k76{C2(`18S%HI<6zo=+eWYu3C` z{i8k3gW{+>GvaA(Z7wYAU9~1ch|z70QxUYDR`&$6GwoJ$o?D213w$c@XNP{r;=3Oa zL#^IHrzMr@#XK`v?-8J7P?4`f0UN$!kj;`wuD`_kMX!r=`(tmb&uL{1)vfitu9G51 z1g{G`h)4=|t1}@ZI3_5_!33WN6H+xXN%UG1&uMOYZ^I2=Nxaczhs3%%3zTSXrjAM3 zl@V7A4$wnv+~4o+$3e$O@gL(~gT5YUQtFc3t@Xy@mX?;xNS;h7+vWgOKnw{!#0-&& z@treL)h!R2mrfa9D9y_Q>Ivyqbi#zmt^8|aX=rTTY0-q1NhGd@Hb4xUm4-2b z3LJ(Q01`)O2ZOW-F9q+|BVw@_);Ea?s+VWrV~iJIJpn$o=Nd1BJWt{6F5km<@W?dz zrF5DLd=-{l7Tlyn(ql33cHo1^=Ofjvtl_m)NS;y=NFHSF=aZgG6Q8N+(y*LmHLTk; z=ci5Rh<~#5yK67(cr-Zv$#F0#l@2OlZI;AD^mKVQ*rwRX2_Jz1?pEXBf^K#&oD50@fvI{M@egCOPJ zKg7Kv&I?TsO}4ydyfFEa!z(0lmQW>UGc%Ey7b}c_u72ui}i|bS& zN>twWU!mn*6aN5_g5UlJ{{WyG?CVFuUk|(?Yv7r$bzctZNw3PV8(A-8PbLNoOO*)u z`ID%TGN%A^Em2-*msTZ2&Kq#Z@?&{DI_y)9z5f8EeLfoUNu+U9txKyht~7lLGbW)n zjcU%hk)Q0!Se~Tk9c#~Zd)u2|5^5eI(=^M8E%fPQH&VxJ<||CU6)5layxo=G_4glw@eVq+b&Yjo?-buI%F(`yPxwBpf}d?} zE@$%DhyZ7gtyqss%M8j$1Lnf>_*R9ck#Pb3Y#d_%9OI|H zN9A8Di>l(9N89D}d8C_GG>MMZOhp0!K*$5|{*`9gR#YwJk(M9B#Xz$ca}ui^qyl#F zoM##Oe=%0=VU!KcF4f)lLF-;TtGk~3FzVW#cl%TLk52G+z~2;KYn~d`wOd=w66(%N zT?*NrZIau%yR(FKw~bJ<^f zN1V6=XgDj*4gnSSm+i<B(x)8@cd>hNmU0{w9t~7nV3+k(%776Q(46$+;MhF=LP~ zPm!G*d_~}I2HSX1Zp2eOpJ*}Xaovr(y#V#E=g$=Qf}C^6VIePm5m#2*n_bhp(_WU- zyFamf0pVH8hALxfL)@!T+24LuZJM%I((3K&eUYK5{AT!{4y_HFK_#p*ZVMrT1|dR& zx%TfFELneqU@ude;5=XAU4LA-7CN=lJQmki5?iB0tF`8n%#pGb6S8O>)}cvf3|NME}`eq6U1JF&N^83P#TM@syPdCgu_rzZ5ZuJ!xwe?V8^ zxMF{Y6&t(W%S88DCH;CHbzaxtEB3wcUY&682=?0uwwVThc1(Ha9d_s2HOTm%KsQmf z>5X!Le61RuJ(%(bQ`FaQ;hib;eFoP~lW;M^^PymH>`OS~gYy$!em@mY7lqqfo%}zO zVlv#yX}iV8e)_9-?90h0b}Npa;L#(9(77Ew@%-v5WO(Eu!5JCkkLgUi2L>c&BXA{2 z{(EiqU>|xX-ZJKGsp+6 zbDk-9-syJao}0182cgG3Yi{cFBN*U0BlwSF^sY)@Ii+{FBYAe;$m`y{{2lImwmn7Y zMI>nCGaw{)BB5(+$?_n^dBETd{c6Zv)Zn2<74A`t+;==0(x(}1bBy@I;9>D2z_;EK zfZD}!e+;fi4?@GsyR>ZyVW3sdzh7)1z3A+AJlF#NmpRWg)T@ zf__qZ5%m?~W_eBv5b9Q(Z#M@U{wwExzb%hzEX{GW9V$_kpr)nzKb5+C_dhqhE8xEv z+-X{-w+)TOo}UGgGu%xJd2*8&kz)k#SjKk(Ix7RwhI>DTy8eZ0eGi9p&0Ehi#z7KA zF5>FB$SuOI1AM(X7{)pDi?0yf*!W{!&@MHLRJ?8^x17J5=EiN~C0H>-!pXOPPOGIy*+cyPDxf zk8>PW(W6OoAx(#Izyl0PIR}h!j(UvwZ;P5OOX7L7w6wNMwAIDAY3+vLDm)4akyxB> zh>n~qHa_>u?fwz*uZHAA(4n-NOTy9a5ZN@F^Ckm)fRnQz^w0Nlc&P1sF{fMjvsl&U z(yZiy=0q?d(iR!gMP_L?Zbf#>qBt$i;m}|c<5$Az?wwR|9?ng)Q1B0eHEly!xYISS z55cI}OCA?gw!1JriP+>55hu(n*aHNCwDF0Tbot0##BrQp zXN=;y9|!3c`j($9+r>4j84PT(5WANE^T$1E-Iv4d8qaeZiKcgqp?Q)c$rvmK&7k8w z2N}r00FNeA7kipYyPLDn=T#k%9U`NCpMaJ>8e&ZyE1mtu3dKx4qhF_y+_M^f?6gtW_uUhBjVIAg;?e9nYtI|0X0 z*R6A20oVLLqG(pO+H|)!A|hDbysI-z4&tSx$lP%KagRU-D|Xw&T9&`BTfw91QrpIg zB)N(0nbpus7(AqM707M5Vu}f0n0N9W7Y(dw%-hu7oLkWCu3j4Z3Y?k`(lU%I*620_lz?gl-pq||;8d^ObdD-Rmp_`dADrK7XjK{A$> zMV2-!q1SLlXWBs>B#)H?=G4$WANW#l4r(_;TaxK~hG&dgsx&8ens+X6#~==%93Dye zhfI`xoxF_HTb<5hR`E6Wf;1~{4r!Mv(%k8h{i0a*NfWQ#$IhfWFyEEH{u8*2gU-)ZyQ*n-8nkN#!@#PR>lADt1)~Z^&<+8{Hx9k~ z;;8B#4{L)D*(QksKoUc<8<-Eh$FF}+dh_Q;*|SAbH!(bY;0-t8H^ZCVdj9}Ww6(ag zwrTEXxq?QEWHDWc*JLcFJ%)C0Ra>A19DJwc%ijoE_?J*`4;G63MZ*{*iJml*Xg@IA z6|hD~+yUp14SkW~yjb`nSGBRwn(-ym=21urL<`I6XnHIk`rpn%|*RrFiI%6Zn(x*TvrrwOH2QK)cng zulLOikPYJ4=a>jZ&J-2HHgmZ0aB;=!`u?k98)^6c8J5C%V+?}oJQAeiJ6#4r!4>b9 z-XgQqJVmLdzv0>J2f_9FT>QKd0vQu9(sxw^Hk>=V@hK0Vpsa-dR zZ1nH6JQDd9n+rEpV&p%uBMPIIIA$zP4~slKrD@(Fxx0yGN18PTX{BZ=x!tu3lZD(* z0|Pu`fn8pmtZ5TZb$g^}@q}iLS*q{imE`k4)Dk;;FnC_fR14&84-++641W z1+wmSJAn+!6|mVkAd|&BJFMDH>qVjU3N1UGU&2^?eK&~oeJ@Ye^{BL#)a`!N6~3V* zx=9Pq5-|lCOC78^T(D7|6>>hIv-n-$yA5Iude*||T-#ZttSs8C%PPW%5mRB1sTctA zId7Q!+}F>(5t0dfJ!>VZ;v)hWm!213Aal>>&34m#Pw@%TBhjs8@}q<7pJ(||yuT$z zdapa3Rrx$^#~_;U^AB%Ywcz=BK9}{eai1=X^&7k22|{JJTcqckoB&oz`75`eFwvrdaj4!(V)dO+S+}J_Tk}{;#Q5EG)Pc_ z;UjV#aOx3=I0m@t(3B}S^WW4IQ`ckNJXv#hrA=WDrv=5Fa$bn;nA`*r?nVk4M0_qu zR{Pk(u{|+cw$sIR65Lze!!&FTB!WeCJoaTIA5Oh%&+Ns;&xdsVA6{mUM1AE4KGo&)@L$7rf++A{Iw2Mkz{8r_nep9IXL++ zG4p4}d=L9X{BhKLai#cLZx(AhXNM#4T3cAdZ=*vCtgUg8Yb@vzL_1x#eD2CXAxQv_ zZ_^~W)*nt^>?0$s>~Y^Q1>wABk;=m&h~x^axm~D*m@9qk0bC#LQQ%JpXule~C8>Nh z(pOBqlf-9I*Df^;6|CcjCeAdFB#8@24(KLxhBrMO?9o-)l2`*lYqx3NSD}g!q}JX?{5HJ>Hieh)t9N>NKAC zCir(O+e$IU4jgSbVYQd$BLz>EXj(3ZZ>Xl7tLm28hMi?+a5M@w5rM)Jfdb+ z45f)Yl0e!M-^*#u!%de(g!af)9v{LDwAMoGXVtBlX8quTk9UXG{cXcIm z#y1i;^y9$wy+2XYuZ&uropEaHp_V&{iZLBCgWDkU?O#QN<*Kwf<$G#Tng}jpFx*0t zBYos`1RucH=%$2{e`qYp8!%3!59`ozp0)YiU!l5e?Qd`-RnF7b10z3C>7Vn(ey!pB zB?#iY`9JpK^FI)5)*9d6{{Y(#p057@V>z{3gt+_48*i3QGCi_QR8YJ)0f%0^5n7Vp zBI)2k12EaQ=Zx(Gr#$}vTKfv~lwZ1hULFvd_l*5II46|^%zk5zSH6G!RkNnc=Q}x> zi7E<$bH;n|{&QJ6MU~RZk;x2uGF+Ea^9%rfy|G%>Rx%`E=8OUd%eOpodHk_lm1^^8 zbGC&GG}0|d=VJ_ZH3J|}IT`xX)d&m=XEfO(DgoV^@~fuLYYyy7rMgFd8_3vDc{{O= zJ!`44(y=2*#JBG-N1S^ec;_Fbaq7&h83_a&f;x)pd?l$|>Ne87)5c1;;do<_$s^zT zA4>7DQIc0jzk-xoB&Ud^Q6R_&$V zM3UJ4>H0NeF?fy?#Nnzt)2CJPUhkKhF>WgQDBkk2`%;sC5lcQqRobh#jHoA^_o}xLOK&HYDqw-wb@#8vn{I2d{U;g;Em1C$r;Sqe zEWGb5xj1dP#uT2Pg?3A)Dkwy702lx#0=bU~T3yYnCDpnDu%F&D9)N-|*F5z0uC1n( zK4*smJp*>Z@BaYSuS$!j^=9U`WH>)-?vzOeT3&|N^22Or zc^XKZtcp=yL9vJ3IZnO0j%&@l_;Zgje>(NQ*{a3~Jbj@@b!LvNWta&7VUZM!jn6^| zQauOEW%B{s z<+kh`9AoM~onMB{Ry;`;C$4aDSzabs@fEat!Dq~i$OLDM@#;U%6@?0lrCwBa*QV)F za%VG)ak!j!W0HR!^;-VQDJ{uZu-Pm&FC?B1`Sz_D?MCv!h|g?PZxe0#a7Y{sV!pEu z(z8A*6$f^Xc`W2|Om4Ub9Mn?C(9B?HnV59gI`Nv*nkj9VBdd1%&zyU7s#mvhTh2El z6P)A&>H62R8mckS@MS^DT9hv0BrJ_+(UY9Edj9~0LSUQ9X_6OZKuOqzkKhL+`wnYT zY+b_>7?`U`$RoEr@l3Lc;@{6OLlIKPYRH?nfJnz)Kl=5}QuBHpboptc;ZKWR7x5m2 z;+yO3PfV5wZm*`A7bJYh&$(FO@CaoiIL>&i9TwPMU)#fRBDy?{lq_??=bRDvA6(bm ze-S)ArfXVl)t;r{-8HT+;3_U=wcbGhV|EB;UVyIQk;ZXfAbe%fF1#J%x6-Y&`&)Q4 z_~W*M=T5SFc;-G*NZH)(S-_b=C5a0@Vpj)_RD+HN4`uM@!!Y=N zN{j6!$lpK{h_sm?X2UGCK0)sRDh#8x|YEW zo_WZVk)E4+U6+$<_TM>J+$?NB0CTVm@z;O`eK0#_w(Pu97MB&Jh1QE_J-V@ZT3b-k zV86|@?!h<%k_SLL171cVDc&(Rrza<B`>;CUOMerQkgZ&fqvNPFeL6iiQSq2Yy1RX62!4QKmc*MKo@#vb?BEtMte2af7MiAB-Ll(4$8ePd?}pck+~FBVZYF7^x+c@BldAw$aUa zWb@B;JKWsN@<}6>l1UhrW+x<)dXj5S*Tk=s6Wf_3DI9Gna5AW&5C9jTRZ-u$&o#%0 zZrW;etTb5v0E=Ef*7a`^#V?6I9cnjG>8&d1`)#oUG>E+AcPTqpkW1}3$4brdMyC~} zoNaO8QEM1fc>Jis#Kqzy5=vmdCyaGY_^D;mY-hcD*+k^LrN~>SP&3pGq++vvAhpJs zX$&?Rg~5X6Sp=UunA>Wgz-Kwm9PSty`AOZzIPVIQxApmxD8`%)Ci7d>^)DUI;u$o# zMVxl#(%vW_FSQho0Rcze$-*L)(NVdAvwb<@jJZ?`a1a}f>u`xGB3?Q6_0YZGmy?6t!J!z$UKeW{n&MjI?h@qZo z<9o}=T&&L079rT+t{s5ql5%pyvB@T@d#hz_v@_?1=Z;-H<*7E>Wb0%A8j?{PKJM1c+gEX}ki=sNv6{x#@!ejn3yoBi_Ls&BK3Qw_2N z!!YNJoDKoU`(vM3)8W2{9bu*Vj0~G={%8W4tXB~JM9gatApEDClR*IC;b}e>$nwm}eXt!F8-j}Ca z!~Lsgacg*q9u=aPeChzeL68UwfHsT_5)VP~3q|;a;#~qCi%Ib##2RdRh0;cBH2b3+ zngs?jA_8LS$IHnjF}Sy0Gs~&SuW9%x;~xX~kKybd3ZF-PX75a${?n&Jr+ulEG~juP zpdH(M8b8%^-qVUI#d=)6Snj4ucQu4tKul9_^M2j0R zBXcnY#^6soh#-=2#|!aa#gTZveKv0kTKPX_xOs0<@EFC%`mm~ew#xz&2as?V2a3)A z0EG259S>OWzNhfUYa5R*REEy_ZK3Q5j^F$-50?-iuIAg$Ko#eHE%4Rtmw+#H z_^&SKNV7R>ubIEr2V?TCNy#TCJxL@1#+W=6IX~V(-uikzrWG5NO&yPT(7bozKZ};r z_+Q2sI(k`IUM1a~jj}j>zEO;(<_OHF#O3zknaKxc%G`Y}3u%KRvBHCfBd<#F-+>Wp zo&>qE@RjVkeXyCNns-}7GR|8dD40fM#|n0m7v%NEeQ!e7E__9%#j9#!IOdu+l68R< z6##4xmv%-+&A`XgiYn2CDYZ>|t8eSh#Ks)En;snaiLUq$TC$T%&}6@Z`$7w=h;5^h zr*j*5TO-)Zl4H1(?KuopbCuku6XHL_JMW7>5UhN5JSVA1b7Ox3#cOG!IWbtrG}0j6 zCvftzy6zhkZe9xEw{?CF(I5MI%I50ZQBBv$Es>8;EVDozF)KFVw0y&M0|f*f$2CXd z9*LxC(dk-$gf4X*GU822^fcDiFKQTh*K0Jy>!e9|h*H^RC8dy`o>3MyDwQL703F+hJOD|qKjPMTu*yR%9eM%W4xwE&F zHcO0A9!;9F4c8=j}ht#d#PMVMDjpHle2#9WGoYt_d@_c>5-b` z{vhj@I)8*@4K2fnw;OoH(<(;$S%Yopd*|12)j7^%wFQ-63^5iUO*t8*Wd`N{pW6nD?$W_f_yu#7$oJK(|+eU5*GXZ6v!_#L`4u z%^_qhyC}HJ^Mzb>!1Al_6Ki^)o(Z+9xoxDBkrT+uj5lO_n}{6qj&Vnab^S-e`qjR@ zr7{WaoRsqya*#m;5$Hi9j(OmN&3%Sbho??zbzRn*cK-l|F|SHWGK_cW>U|CHQ}%w- zHBS@<@ou}OeV!MEmK&%UzS2pK+e2#_TUlGIYJeP z0025y&cCp~jl6U5BgY!u_MxNLu9>H3;Vv#M$wpbFl}u@dkdg|;G2n5tk}@;&{jG}z zcSsi?t^*Eo4tVt9zi{EIcuH6vY6V7B2HStr-eU)iz6tqvizavvXSuUek z@1r4tdYqqs%dUNEWicE=6;ZWM9DC-mU=haY^NuIQu<>+M~*rSD&% z<6$MGu1V(1938`M4nZCG{{ZXM%F#&zg(@9e=3)j%IjZE~fAy$ahB6#RHh?lVdJpGb zRNa~E(p<&F-LP(8PB|i*Fv|Wk<;E3Nfy(C~iXI6h3PO?BxaP5yq;^3#vJ6#?DsLkG zIZf}`w&(Z4J==IayZU}LUX&px86SzRI`q?4Jq$G3mCPU8YsFp|vi+a+9SZkZfL&`c z!5*1zA9Gw7?jn*xpmtSLmOKJfXDp!nfqf2>soITGN3?5D0|}v6{$0Q+<7nV=c{u1e z9lf9SpZFDVed0@RAL!9t$hY$q*Jf!D#cHULM-fH9VY_RBPT{*~%IBXpxzO!&JZaEd zg+m&a%NFwvFj(i*gV+yh{zdURrfZ1eir-nJsm7X&BfI8}+@mYmZ_Mv)6ZdZ1TR+lI zqy7ga!gzT`SQ_rEt4dWWXqP2RMiQrMw`lS!H>{KAv|}WfDAqz9z+OkWbCn9<=eYZ| z7}FnWP(*7b67Z5Oet&{DToE3a%Yd z{Q*k~r5d0AjM=dEYWaI&)H4iubo zS2aMZ5|F%xstnEdi0SQKRQ=bf>QJVfZiO<2pU!2^Il-?&@KxdQ0JXD0GtD6p>=|P2 zdH`|BB#u4sE6$!k>|Bw_>?^DAMy;r6QA4Zf_m>uzP?l7fOoZ^fPY*r2XEh;PWw|idNUwtpWmp<0gn^U;cZCg>cRJ@WDHxR~h z7D5K)7$-dBbw66%k3_ReXym$iL$qa>5r7XI5sde$-v%So{7LZhNY^6NBfXYOD17^% zcmDJs-PGhTU_tM@Af78~^7;s5XiB>}lB6pT0nZ~pg@16<#jH&zI#+7R-%Go$`+U#x zOBt5D7B;jiB%Ea>Yc!KmX{4U2-JYvvRyvusUn(_5P`FarC;C=R(U$V+ONR;r6T*+c zRm+gmKK;k)$0n-EL^2hSlaZThr~8NRVz&IuI%gIN7tnA0|CxO zk$}cxSm;tcK74cr}M8J{h;iw@1fG7hfEhSAG8T}xZfT^VU!Vr`HXwl zxLhfC83%ES`FrCfmxz1~i+D1k| z-N^@o>1!gXCnuAfV!TE(sMuVlp{L!>v&VLl#{U3mbBd0e36q7(wLGnfB zp%D-O3`RiR-)P9UKuv71XY-Bxh?uY_dqZ*sDiAw;oy(l~7MD*C6#E=DeI#6m;r!P?ns-bUV#f(I@jGvjSP9z*xkX z3`k`8^YZog01l@W+IX7M#`{WpJNB7UQWU%d2OQ+!p2rwI z#<08zVWR0;)uy$m-Cj>B!7NV*!oy4uT=59 z)}s~db~@#efUS&i!4a`Y!o;lD0WhN-K;pU|6KI-W#Jxr)l9?fy ze6~jU$7f;=?g3+roR2i|jpF!GE)K2YIOe~$IhGc-RX2NtDHvQ4u;tl_0kR|8g)O*w z)hW%iuV>h~)aQ-*71zT$b&aHhPtRX z+{kiq->xbvy;gh4eAkXO`9Ru$f&Bjf&MUX-vgYPKku=#`z_kYj}-h?)g;q=ISECG#+I)jwt5+AHD@!0Y?VPXk%$(!;Ia zT3hN;URylAUdE6hQmmm^i5%ePr?H|?#9;8P;q2wo=5;8id!5h0@7aIiOL)sm@iwjF zp<`VB10sMtXUNb;zn(wygQ?K z{!6=$5NizlrZ3OurYM>x%KJ~sHLW1(9tIu*sN_m7qlyKevj z0mwtgUgUH=dq3ls!!P(jd<>V`XO69|zSS{AjTs@3ra*Q<<`XFUs=;~($>TNV`jdEe zUl7S}emuEUA!*~5Lcw36eJxzTs8B(%QpEC5ZoTcnUXgNAu)&EHajXY0PQXFZLduDVelhN*E~<7cw@zP zi6ZJ(@LS$XXpWLa<}#ysZd|Vfk_#cvaoByH0*vu9P^R~>soeFz*B5-sOrl@~v-`R{P2i)K}i%Ff^*=FjiM&qdCYvoegRDfjq58=81xmK4J(AFgjLaMvO35smZU1#zu6p z5~lh#kE6p*6QrlyNGzb0*-hHom4MJjS7=Z@4RpQ{({DBX zRWz*^PM-GmWhUO*))taS02XX2f=&R>&>wpBxP4W4_)~(`T6+0<^j>y6+~%byVP#gN zz1XX}*(Gh;eY(EN=jaE+ty@o*;jW2!rfKHV+4MU}Eo_!!DS|T!m5+0B*ce=%Pad^W z?&s}SF96^`AHQ%}j`k#OJmawZs~h1xw~f3z@TW=8ylrkGzqGY$c@WJR^3ffHOZ&X3 z#9=uHC%-wZSc}adRyoP!?&iO|vUthhY1Eu~Ta0d+vsx>rx;5LO{zdUOv!$KlXwsUT zV^V2JNy$kmG^C{Ul515f>a_+{VTJ;ryonY)(eT}ddeJja6oxq;l|8CCndd@|-MFuE z9_v10e)4)0WK$s8rv#4llOwccRDy7L1F!f~riNYH1YqFxCZmi8$};2?!LFrI-$Ra6 z^fTFrghp}0dh=3SBM9A>0P*u=a6hG7Yb#a&7)JxQ6y|~^1xzb~G19#{6%pj(sXH9| zj5!-|&reFraEQdO8=E*MHL-hb_F2q%`E$Wzip#r=l6NEzzCpqIe~oNbq)Wpi*Ggbo2^`B(wC#(=R6fDQ(EuH7oDlj=~9hm3wdpXOxFtVhf;wK?5+-Y&ls;i9fgK2gy~dTHP`R_H@`z{9wJy;k*QBc zpY`|c=6sQ*X$rm^zwtD>O6m=36l-m#E&AKE&hA4KBV;bc4A{ZW-)?;a{t$nLc8eYT z-L!Et+M_&gctMdsB}r6lF&S^W!6&{K9Nx8IYv8X9>ULU2vM=PdzC-rOU~6caHjUUF zq_G8X!zUo)BLT2Bz8z^0YW6oWYB9X=wX_RwaV&yT14IiIVxSNS8&5wj)5dXMfnwn3 z%a!i8>-eoc6WjJB>!pB#9q*m*sfD$qF&a>G)S0sW{Va z=ci5kr_=ghjlLaRcnS+k?-(h@2(e=B%J4%|~-%D8`xkB>5rBgDj zGAvSpGET;nw%_8$2=86~o33i!G0?Q%2xtdP(V^0`7PymD)bCZ&S)HO+$WlZ(nVgN= zvI>x(5D$-9oTEN#=yr2+D;MCnx3~!Q^DC^Yn3-Q8#y4bo@Co`1)$2=GXNL_0?Cx7@ zpc@7@_x1U@9;2s2j$%f$@cp)nrQUd&*K}~&waBrVW)UAQL||l%Tkf76LmaCN2I@Kj z_LA#wr9*o;8g13wQoK=|7T+8y%vU=`?2e;O#U^?HlHS#1+2R_09k@aUj&kRkPdtPHPPz2Y0@BK_qUVoZ#<7U7F;@h?Q?(= zBys3kxri@dyti3xjl&{>qD!_0N96KI`s3&YbL!5wCCj;H3#+X@X8SG92skAURlml( zkKzZ!ZwqSrfoqQw$vp8~M69RzPqFRL;W0Hzv3%YugCyH5Jt~ zcLLtg=b5flL>fOTSj<6*$Yytqa0YTg>IHTFBKUT?{{V(OKNg*1V?2=DCAPBba;xOs zO?Mh2$jg>!nlh?3d7DoDH*P1*{wr8`x8e7RuDmC!+umum^4Ligq&6CY&mF?uY>uIS-r8-nFjpP1(Z>TrK5 z(bH_TduuDFx3pz)6l{_*HxHX6XQ?08zZEi)WxD*UVuy(J3rYN6soBAC1F~OETqNMS zks$;X>^k;hCk8PJwc}SSZdMuF^24 z9SJzcP%EJE&%=Ka_!Gl6z9QBFL~g`}J6REgiLymQxDkP!;DQOr=DoL8l4>eipGzmn zGlua#gA~@r`rU#wD#etaybEqTlgA~GzH#YUQ(ZQdaXyoKrkIRQsUm%&cMPiBV~&m5 zyRV13cZGa=<9iRzI_(a6H*9B9+_na!(k|asDUM`~{@=ghSxF zw!E>83bo_d`7JAlZ=6P0?F0qKImaXhBnpLCsW|nu%Z%H0WN@mjss)e{xwe81LX(gW z;BnWrZhR!U@XUT4)R$e-jnwlrs}noA?PCeqAYd_+bG(7eU@LG%S@55N^)#tbrkqcsz6I(30Pu%+-YEPzZ3H$_cuK~5<8eO07FIc4Rgj}F zJEoDgZd5rL#>K}^EQZZ`db0X(Kie6Y#$n3WO8DmLYnbN7!p z^WTTMl->`qXVWYZmgddik}X9yHpgwmFj5A6y$>Tb=RPIz&x|}v@tW_(eihMYv(@FD zmMbe|7jGLZK3jqEVg6NP_jn&n*NY4X)-h6@O;V2c>aD*1XEjRmi)Yck5%}G4Z=`={ z+4x;v&fe$9l?n0+x9?ZWDADCeWNwNvvj?qpz7Y727MpDPJ^uiPZ*9%Bq!X-@YM*O) zBb5ZI%RpOkb%mcR?~ zC&t}J;x4OvUsaD)w$dBRjCrp+THLy)%Im)f7=e-iIU$HW>)XoW>c%sh+~#!MrGBR` z;?Eyl>b@ggcTUrE>xPQ%ON%+LwDPjsF_nrGB1Xe)SlEz88z5vTW9a_?v&Zcv;_FX~ zKMnLh5PUh&^_@RK)kU?AnPVxmYnPRkEsKdH7Vh@)c~1$EKtm8a(Z6^+gX|yl*Z%+= zuW9{}{{UtW6#P!{O|Oq`b=%Jm>3TiwwcW0!nqQdrawO#9-^~5f6)`?o?h4xhMg-&a zUL2>3sgI{m2X`$tw#lhI^y$}5oll?7s$i()wIz$Pg__p;$vElDuU?wIXPpKj`a8<5~=3|4lDO+%az@;`M!&DT&WK* z#~^5lR4gYl6P~SE9no~>eA$RV@%f6sfr7yf<@>Zgrj59*FJ->g{{Tup zjCe@l{5PdqHC(-|Nw)`UQ)*n6j+gh8V>fqe%S4^q#FgT6=BXQr`GE$c)D64sYj7~i zdMO?1DHCo+%wYC3Ng$ILiB|(3D6hj;!qt!I-)E|KI!^`JnJ#0uhXV<{il%eG2h;OE z;480vE+Dx{SYy;@`ByFQ*7i${LF~+q5<7CjF(JV@QJi$?U8R1dl3}UT$|F)eTl^2s zbISE8W-goPm*R6;=AP_VeW{glN|_GAr`xV;1#M$8ltm5$0l8$)UY}a){6iow97;I~ zPJX>Vm2>7uEwaKDf&4E_AUhuL56LM;wx@l0@i=7DSPLW@TTQNCC6PGC0zq9cD>60~qxcso>uc z$KhWRX?`MWZ#(-o{u_Y~{k~_G>f3i<<2c4}ap_(81|pshHN)4IoRfr}{Uo1DKe^wr z=kX>Ewrh}MFmP9OX;gw*Zzwpgi8%H9Nyoae_ok(JCB)_^*z8u|5Drc;pY!#ot*(Sj z9f4)r#w$8|nHc$~?g2R&G>v}Iz^H)aU=y=EW9whvu%l?${{SFr)%Tftawm3~oGCka zKTdxtiks%6aIz^qhH2D4cS2)!u0cGEv#P9k%Pv}~L|8Y=_|}zHo)EH`LF?NU(MMCB zyRgbIGn{iqN3AC1Cjp1&UZoXio-QHYMmLBCFBN-veLoXflf~x5Vpb|oa4TcPW9Ezg z1^p{2jvJ78uV#$>#C+B!HmK1>Y@}#B^q6CxUY+W#+!0zLI`fHZPhKxk^8wNbctUDNIMz#?IQw1TWA^RQ2oUvKzkjXvB`Jd%mc?rsp4&p~#o%mpOO-i1J zO1gHjs=CgLX&Gs*VrWn9-BafnAn-s3j00UJg*^J7gs-)a59$+`KGEgeLXZ-Y5URzP z9uCkH<(C{UJaN}t>G~dpJ@<>vvd24Hm%F$u$8sW$pl5&-bRUO2zV}M_d!XprgWOu# zTG^z+OZAK82_Qwl!t$(FZWLgh-3e}ZYF#d4ccVuI28kuskO+$Aa)2aIEu+i5Mh64} zIOmUQ=rlPrF9um!&#W!{s}@!r_Rg+fc2^;>w*VXijDgVBC9jPB7{JMGrg&n`VHLNX zFh`z9W5d4n+azn8AXeO08=n9YyxH*{vumr_T50zBY!+rYfdxwxEEM1cA8|(~9P|V0 zj+37(mgewnM&j!l?6=al_I9PJqzvTwcRGVOE1amtGBNH+_u`_1Sh=>*bkV)q)jAWb)a@y~Up2EcG3F0P#T~rYQ`HhMGWZi}w0!BKKxN**Kc@1OY zmy9lBjV?7yG$u0_+bY9yS>gf<2|ulmbv2J5bHXPz1E?rMKf5wZDfWJtGI3X zz#tQnpx}?dbgwHC<7S!J8gq-WbK(`NU!}FAK3AEwoENx63Ni**vjC&FILRX!s}T5B z$6C^KYwNpXG`3LOTgE22M~Re3&AEPJ2mq0j#~<#R=XDF~tyWP!qac-)LaAgN43mH{ z>QCoZ^c_+iJ~MAAR6{OF+H;MhcKRs%Ys#BWNVHzM_(92{pVoh#ex_ujXVEwZ>bG!{xy5&2&Z? zqtzfX#8(d*V3E~TbJOtr>FuuXm`v8}aVT)UapMb&erG=Q&lNj+kD>Zh)LOie@-DTd zYrY)T*7H|OPcjsb$!Sb?F)>*FLGtcNF|-1$k(>tv7OscDo(9u&%QTN(v$ndsSeQ#8 z21IY0Ab`Ue0|Ph*t$H_!wLb>g_`_7X*EEZbYV0+y*{>wN^6(T!C5eP;qm}a)b_oSX z8Ov8MV=SZ3Ht-|LV=WrU`$0W{ARGhS;QbAI4z+r*isiR={d7FajdJq#AK|-Myg1hn zVDZ}^M0hxGPT*z_>bZqvEmsnwCME=*vP{Wh!sHq zf;#28jP?8nL5Wn>>HNl+DrL@26an}Fz#hV+hI@;d(%v|?Gq_b%Qb{EA0=p=|Q`z1`9G zZRWjUV?37f?=2bzV4!y+fs@JSKT6;~XwQxF{4wwn-gsJDW2)*BtTvu>idqF_V$z8D z-cxFfACxqRPDje$40y}-wD{C+XTG1s8j`_xG(?L{P{Fa03V;GCgai^uTm~Q($pDTw z#lN&Ki@ZT{mzqxd8Cl)#<&ssnYldPD;$1Qha&zBzG)EVn2syBITdzZ$)+J{=z zFRlDZ;wY6M)2F&^D$Omo?fXQm#aYI|BL&*MSLKKtWU+4y_=)>K_^09(vuL`dg^TI& z-6Xc?U}TfzFM`BB49eJSamUNIoblIswZ-g9MYwHhRGYiZY$$!iyP~^L8fU&e9yHc zjwxAu#oQkaf-(atwhsWPJYysEW8f!&^!q>A^T66PdS0Krcw0?3H(GVfQY5kqIKxUM zh?STUIFVVyWDrQ^zg+P14?5Yat$QkJ@6VYum!|L4F30BHAmb@e%2gDu>N|RJwD0TF z(Z1)W_zwQxQqes7dmBg(oXa9vN3nNt+Z-Hi?th@@El42X9^FlHJ|3`}L$muhpDpKk zgoDO=99L~;409m5&P1vhagMzDn*C!Iw7K}!7Ax9ZVIT~XPlgtq!YKoua!2_zUO>v3 zi*6191mhX+l4{MO2xG{QF(>9Ka=9Lr<5!m|(DrCUnU>K6Xb^M*12tg0;@wZlv?<5S z&N3=Z8D4dLhVwd~N`PYM5qEfRyhJ_a>sUfy78KGHZesDP)RqJ~M>VW~t~|vtkXM4kJaO`ZeuF)!j?W;&w&DKQHR+9O3&|tMfrPPybz}q(Gr{90 z?;Z~yna`YSQKVYM+)*G^TbTl?i~u(t1$5yt{{UN)O*8H|zJJn}yZ`zPX+yt4c?@dC$r zEJyny;kPE-;6}u+AdD~@Pka-C4h?)&tjf=LVJK7}8C}`WQV-;7`LoA}`z+#xb-bzD zr%6lv_42ik??0kNS675_m`;$d%(Zv-slh$;wd19_-u`u2*~ujJG?Y-Mb8 ze*#9+c(%?2a;+n>s}97e72nvnU?a~UHaO@wt^>gk3A{%J`DF(-ySex8}*^2K1@&*nI2#_kSJ zeEv1?nX7LZJ8gD*S!EaOApF0tz>+J7*pw}d4(JYl!=+pBrPiPS011whZK+(x4ZG?v zt<=*jWg|l(<%p0JAPkeZ6~|CUMPyo;yuz$cPD$pAJ6N@CdfQ7kR`%a$x=5Pl>RpjW z8G`P1{uLcb>?@-yrj{a(+;3#j2at z74Pn?Zl}nQ$UM)HRPsm3kOn@!oee;XZybT&YJxJm`i`CIJ9w_r=gW%R7gyy^VhBHn zr{*bcB)xabf__rD9PoPAWjCU+<=2g_+8l0emSW*~1E?#5@7Jw(SMA#q-Fz>C*2l&% zSV*^CeEMA4lrXNP0uPuj>=|7c#=!$)l1OIq#d}2P!5@;XgU;OG`s2NMhsXO%ZA;*{ ziq4}tqD7)y+`Nw*Y@o!3P)LzkK*|nrk=07D3^+6DKUvAE(ocB5!(T7*?{%S`TUAlb zD9Np)zZQHybu@O+2|;38?t;RwE%keU6<@r5ABuaqaCTcFlOu&0B~$`&_*H!x>rI;a zS)#CLZf-KuIJqSx=Yg{r1OwOW(>2-nU%>h>73aZm^gphVBG0nB|dUmu~QOf{gn~$T?h`RTw;J_EaC*UJJRK&BSOg5RWcG zPtKbN+`|B%n4{K_{05s1cpcs8`G!I&edEJCud4 z$yrmfIU=XKHSazu>i!q-v>qI`xV6>p(&~AytiIVKk~wn9(a0k_jLKMoN6f#(GDl(X z+s581z3{!=*1xaI_LQ-b;y7}Wm{5fvoyx3aR$?}jv<^O=Q>0u^t!l#J??$q=iZ_r) zZ*Lm~LOi389J3M|C+1>u#~2Ety8Q!J{>eAHw(Yvp<+or|l6PYm><-`w&tQAvxs@l& zd;b7h8v8|}u`h_Vp{vf%W6`Ticpq@@Mis>W2cegQ#cOi$%O{8NR_j+^A zf6o=qIHpFhN%7W&5e#{S|N^K|Htz^I->_>*{AV(_rh12 z9G(F1E{h~9Ypa)g>y1t3M@Zh}B1Sm@F*#sHKJm`u^Pex&G>No@@~3FzE>wvDY_A6( zbBt%(JPw?S>%31i7B4;3)$iHkj|}oEj+p6!4o^Q)eznisYL*&m z8yzv8M{Wrtwg(+W3utt~&AYQ0f-p$y(yUtAT}uS79gD~ed^ld8FywmrekQHWV-%9K zZw$a8auhJmH+%K#pYf}DMf7@nM$_z)f}{p5AtNO5$3@Ti&2Utv+^iKUa;uYRF-;zs zZjBoT3i(1g``i=X{{YukLP)3Q10-hvenObWBDszhL6S!Eob&ahp5}N!Fxj+&V95>N zJu%HpX*+qG+R9$1N2cm>c#_U5@j5q|%z+3#TNPZX$9!N^#>#OZj{}kShHxv9_;Y_Q zhb_c6dNu5Z>PXTyiXapfEDq*k0`hv3#tv~>ZQ|H%d`zpUTU{BVGDi)PBy!4ktQ%Aq zn4@HeJTX1G@l#HnK2-KT`mJiWYS%d5kG>td(XFn$Sz{um>nHhwI}<7+5XXX`U?{;O zI6QSV!c;SDD9`$!Ax^)i`~Bp}C(;DWdZ4xI;M&#%0EU5+Vap2F_l>uU%% zTik~+5X&%ZDfu}8N4^{Vs`7sw{65tDWp87q=rh>crLOPY%^L%Z0HHP`5C8`wfzz%y z^=Rn?pF@RBIeW)~c%NKLj~82B-rL2t)WjuAdsyQP18+Yn013hBYo*itb>RH8(LdRW z$CfPy(~N0cQmoPZ+SB`t;;qf4mxl?WgWV4-!;`w+15%ceU6Dv4SF5Toy=F3ab3Xs zl33Nzutq@{2bzD)xBvz*$<1@xP`2>x)yRe^ifu@vieJ2_j&KjSR&QL82OVpB!v|Qv z#ifif{uVSjZgbgXlTuHC6Q;3r@9*Zm5ZGxW#WJ)!ykP*Z?lYuyWsc zj)QOcb=a8ZlXb0^0aGJfLBD+M`nO7KrXgX%f_#dGzo;@=qfdPyPEmr#)T zR}sqh7N;NqleJiNKc~KH8^yYnj;7al8hnni$rqZ8Az`_91TE8{Y>&s9_9@105sZI`#X3He zG#5*YmyAZP(QcppV_>jDpS{Q!@5dEU_He4Bexb9mhjrs?TWDpQPSq}@mF3|jB&v>1 zKs~!-Iq6@ZKk!O_+YaC2ev>!BPl^8k5vP;Hx^z)R;aw)?&e{ui(_nxu$R0EgEbE48 z7Dg;%L}bp{i2T~Sf#Ojb!lbu3OdJEq7Q(!G2B3G3k7-y43~-wre@Z8J}~WbqPS zyjrZY#}JOzH@bII2@U3|LeCf{VUbWs3Ks|TULD3yF2~b!b>?X`ebdvYZky_S=M-g_ zOv@*$8rpIvBd}p4xRkW^yx(){cfJhC@6uf(n(u1dvV-LOrWD#8!V}zrsMt z8z|UIWFK6Ahxm%t(yxo@=_JuINTdMF*)4zwZ^pl8sjVxY&XMTt}6`1(!MLoPL=6de=-{Bnu>M zm1I&6s33aR&f_l{*XYlu!9_eeT~OY4bmQw<8f3Svr(HvBIagH8zH!4~@y{HQR9ZPz zOBkPlo)nsjU4HMww|iRCd{V`nZrXPP>x0mC_pdsn9c9ZKH~vSbhn#Tp=9SXxZ!@PZ z^232RjhTAjZbOf$86SwQ3&r|r(zUlqB{F%#%?{Yf$vMsd9YN{a6=-rIAa zlO9}6or!<|8%}aK2OM*sULx_$%-8o8_ogBtmH=R40AdIPfLo1)xGs6&24pCEp4iLTFw6equ)lp490Mu0{w3nZft9fXxX=F zQl}4R&7w+Q6KOWA*0;J(RgWD9<4d&Bzs_IkJnI(TTqvat)s%FM)`oD)^92?uWn z*NV9_e5G)C?^NysXDqIOP~ zHP+tf3-+~m*X3sUQ~(uyvFU+S^}Q49HZ6T=DxIe+kH8D<>Uw|r=)+^FDK9fTUIMJ3 z^w{LjwM%Fbr$t~6N#Kf}=^A;7l&Jq~%Q`viA5Cuj|jbI^L%xeBUi`RbHi zHm+N1YczI~$cQ^cT6h4<-r5GDm9Z!`?E~^YOm&v}|HKZoA#aHxBjk$NUuY#z>zJw9kh6XNzHmTg^xN zPU_m$@5!B(HbDSoMg`+6?%TE>;8 z31idsxh|x*xl}_lt4jW2B6sAB9CQR=jB#9i8bZT&=Witx9iKNjBOlb&RVK$Ji=%WBBI3$tB86f)ClYAiYUY%zc@WsTJFCE38kzl=;BnDwC zhS(KLFvh|?8Du!_Ju|}=)-pvqzMQdzot0m3lX8???IbDN$y^bh4^VlZtV&YlxysaF z?P4uE##Yn#t{pN-QBWhs(r}?OI zC@Ugyl1D&s*CPPajx9zlN!^g?I*#dBNoDeoutLWNY63FH9R^6R9r5<1q-)yLnx&ew z6SyB~NiICVSSqLr1Y>UloRi7ziu9j}TBe0>EcO~fnEZibmRBWZQ``(G7!BxfLF9__ zjZZ|jz29<*!fmG;TZTB}Ir@876pedcXRxg4FA%{W=Q9H60SZSQ52vWES^L@@@Jn*WsjCSzDJ_w=#MZ?MfLLzHU~$-vIXx<_h{3ej z&yXWH!vLFe=za1r%{uGB*Hb|>2;gjEBur2fA=&^?cX88_K<(*PH2(kyTxolnElV_t*INB`blr%nO_@m){M$1&!EF+EW^t8H?)fN>}im$bThAKvUvy5jTG04am^EiGR zY3mRs@e=3sI-A1-spzfoUUYdS}UHFniBTc{+NFK-ODaXgF*I+Pg%V*qSi z0D2Ftc+bRNhdQT%?*7*erNp{qq%2q7LkNU~6Xh4=Zo-p{=WY#pcpP-2cUZ%Jq2NSU&2=&D!G{z|zfStDy^yK?HR7AJ5i_^i31Q*DytW8-r_ZEm|XmR!lP{ z2q5va6WrtKYgbxIS8qdfl1DLV;cb6Qlxocy#<6|&VY_m-2ZB0twELfKA=jn6y@PCq zGO;#LEJ~yeXP=Z3Jx;k~DMMyplUhHMDAN<%UEOKJPLok!$5Y7xe+XH>ZR zVPz$4FkT>jZ2aFSCu;C=c?TU0cYp9tzuQZ|{{XT_?Jzzod_nN`zpLmkpIaw0VIxEyIPQ~lTTD_oQN3jucu*g&;rv7?W^^jme6dnZx7+T2*HyXU=kzP$vTQ{v zQRbAQ(p~=m75V(0&-Y$bNu={-P+KROYz*xRw2+wCj!=+rexk8H7koj{{w;ho@bAS> z4%*zor+Aw}v(>C2y+v80hUOHR7C@}Z94ml8W*N>2>s!_P%A92mWb|kAZAi)!<&v{b z%(Z9xxJ0d~G$VP!g(MO&&mUU7Z+~jjo!6p5>;z-VBX3?ak9xIyUDj}0yxf2 zdRLoXj3%3J^8WxUo{kc{;UyTQ_rLS8xiSY(rGV#*_c-8wb<)~i*=ag$sk^#uxLxe( zSmfm6>5r{)HjH%xGRbhtsS`@uRAghOJ$rHb*4?eE#Ry3CDJ4LDQrJ8O>6~Y$9e)b> zY-AI%Z2L?baaT8Hv#``PIqbgIa~rCH(W8KbV07c$XX{3x;e@=7IPBgukx3b7!tco) zN{-)3&yU5kBeaDq!!TX!s&d3<->0QdZQ|J$WqYY15wmA-2Z8O3{{Wv(-fO3cg`9dG zlxKvKai3rFF|~VEu%25<4=UIP)O82)s(PbAtl5hVM#?E-Fc@V?cRI@%7%IWZ7{+)2 z4o?-)__RQ6X2dEbHv{Gi$xw<0segmCmGMn$^deNhi})zU$QZ>*5`u(|mib zSQNKY2C;J<+gLoPhS^wriIcH-;c{>=GHV~sZ$bFfYauJN_7tFka1DQ+7|QXlim6pb z%1yg(YrES0ZQTC=XfPN_;IK5PRF^Y^V;3u0?If>mm)_k8#L8qx;YoqiXEABWQ1y`Ly?bOA*t7}+VNgn`{g-}Vr z1fO7QvkgtvlwlQi_FY@@^A&2bqX|^0D@7-E^htGX?2_uwyL>Nw;l%KMm;V3=jiCO` z{?CK^J8)tI9$51J{{YN>Tz&3+d8>l;RwBMimXHh+{5;e)Iwj49i)&#d>nyhR=#t7e zpD?Q6pPilgBR?}S^t8jl1(-4ZT7H=0{I7y2T$|qTb>2f#-pWqa?Y(SyAV}33@aRs z-HFIOIuEI?GS^hOvbLJi+^*S_t1~Yk9=Q6C{tFlj-2pu z`Tc8>z7f==C4G7oLl&u2i?>TN(a6ZfRMstJpG}rKb&S5;fif3fx#@$G>A~j}S3=Y! zyp>Y&S4jjxigSWUJag0k0MK4CeOE**@{MAT8?p0xr;$nV-8SS`pUR5d; zBV8vXt!>XvwRlR4e68HTxen9F$`E|#<&6j&lh6^s`t~BTwS}J>cHk)aiEg#Buu70I zeZ`0cfjK0M`}@{ry9%Vyv4ro=cW=P$Utxqv$s~MMI`NB>D`@OMkQ`%CW+awka!EZ)9M{`Fw_k_8A$(5omX+aO1IcZ58M%^8XHUc{C~uU*Dm

zEXFkXTBil0wvJC%XV*(D^l9ne?>IJ|8|pHt%$-R+RrN_|uDWY?=XI}Z6$IL5qjwd+ zwYFwfxmeq5B>evXBI6^za52`L_nKX*f5gW6NT7*_nqW}!?%KsvWDp7e0BeE)?}9r$ z8qdSlnn1OCX{Uki)m&;e@+(a%$h%7d6t~REGmIQy+(cL+JOO9f546n9Sg@d4yyYOkz@?pD&OG zGn0;UTM=k_RjeXATNvXjYAx1PQM^V50`5GK!0YK*nm5DG59s=gSGsG>0Y=>FWoB70 z4gneU=zCWTqcpCGa)Xwo-E+i|>$eSXwx%tM<%M&SKqr&vdFk!ev!&Lw?LIKKj_HLh z^1|#foOJ;ABl8}jmsW<`N7YkG`)WyXa6xDyW!#xhFcP5fHj$60u4~0w>q^OOVX3Ku z%5DDuXP>TmgM-r;{LOPI&zk3E9-Zcq*SzjPj5#U^AxYp9jQ;>3`BGOIpm>Kpma=X;)aOEJpwzPD6i-?P2JT?jCLC!0KlEcJuh-0_Z zt|PaMg(2BI=K|o6>~Kf=oMdN`IR_^`gDg?c6GJNHT}rUeP-~j;HkEIuJW@a~WoZil zFb6pp9k32R3bfVAi{&!rNUgNXHNLrdBz9OXBuPKkO2{KFSc1*yI&gX7mdbAs&WRkF z(%_;vMj)0#4s+kr>z=ihuW2yd?7260F}lbZe5uF*fZ%{~0T}I$wSLFMO9&rqws#>m zhDnIe9Aq4f=c)JnDqSm~`$UmTQGG(*VA_VK=UYnH{{TgsC6kbTUW0&rv)-y`+MU*z zeETD@!-fnA?VdfyBoJ!Wy?!-vr(;9{kO7ppQ<6qU9ls$|6$E2oImHewA#>dpUsAc0 zyUxZ(l|Yt9k;^y)5Dz?#2jnX5ovZzU;J#yWj*tk1kjO?*Ic>Z*Jd$vKmMc0FY83h5 z^V@DJO;+hG>{H9OZJUPEkN_kT^*`sDo<{a6>Q;&O#lL`IXdtz{l1D|w~g}NW^y@htBmAzz_>ZuA{|qU&%0d zwNR+d=S(GD5QW+pVNdYnanBw2s{RY`<>kv;YO-9yZT@rRhW+A^xC4xJ3~~-@p^lpscaMT0@~o~RI5=&n|FE~wWD-==letb zg|#gsQqw$L{iOu(+%iS>u_%u>48?&{jij-Raln8KoxFMLTre2`53Olxo+0s0yK1(2 z&x$YaAy*EN-Cju|2EhS0)s7V+YgF=2A;x zqVDw06f_|T<916Nb>q{K&U^Ir<-A*Wt4FC^EwfuQvqlhZ!vIk8hB(egAB{Th^6u(! zHO!B_9I^%{_h;KZD>mWcI;2pTcQ!%E1JS?w$MF39T6Ei$-`s0W>QARwoq97a-%Gpg)J_yjLsr9b~zY=HC+ZxF_+chSqrCGC>#$$l zJ*kD_WdNX;g5JD#{Oj@m0R9Mfpla72wsrN#hrCiW$ZY%(eKxIZwo5tGEzH)@tQ(!P z4kwZs_pc|&+0oe7>)o!KYHrf&?Gn7IfVK!xkN_tge+>8ZuiSWR8(SNbMx}p=Hm{<+ zo|+_*(@&B7`NjEW8!ykNPY0l>#2Bxa z?V^}WG?2}(7q3z)(R|Afxi>CehZZci37Mi;C zN9RH@IsX86Jt-PSR>pry>;5r(D4*d+j_&*@+JfA}gDsS?hd;PxZGoBNMR(c;;~rET zjN}kGHMUph&*$8K_3Qlj$K|-JyBSjpiH|Jc+*-JR9PVN?8*X&zo4bR2Px#qQoN4L=BlHH_? z6B`*}Ldts`tm~24i0Dmt^WSV>8X^Hal55^SVQm*tyYUve;-jZVETXhqMZA?{3}j|k zF~^UQhSdf0mITL)208lA4luH>#yB*U`DJ(VP5y_#_}PkB9}Dw2&Q|89%C)uJh7$r979*f1j&b>e`quY|66W(v;w1$o z3>9A|Zr*di=O>`g^d2Qja*ib?^maXn$x4H=)g0Y(y2OS}MqIgIrvoG$dvX4Kd97=` zUMp+};|_N)VZQ}%aafbYCb)Zp$zo4FxhMM9+T~QI8M(=6Z4ZRbYC?3?IK6MF43VU$ zV{wqf1Xez?rpIcc=Gj1uD9VCK&#&^Wg8@elWNw(oc0r+g1cw!z8l6^Xx#W8x{?*8NlP78`)0+zcY0!d8}qcx>*-` zWNdCapVz17Urv9)LqBT`SK!{UKf#X+Xxd9lu4s27Te;M%FFw->+$PnQ-S)>8FkccQ z$~?q%WkVm&@y3(!B28;rOU+j1&NCcDhLSamj6UGIk0%+%+~Wg0k(2nx9pmWZa~M&C zuk7xhlXm|AFTDLTgL3NlOa!Y*SyZ!LX}Iy@afQG z@gAbLGCXp9rsm{t^FcxcO_RW71P;9M?ZRrhgI?QB3`KWL2hZe$Wyhmro_b{G9jV?J zwY#*jM8Og?%*d#qZOd_upnXRj{{Ra3Si;W7)>P6rJ=((eQfX4x%oBuyR+)kT!GH|C zU#2$`-yH`SY2R83a}JktF3<}sJ6!wVWE0apI3G&$%_ckPtRtHCNYJWb)!3I~f>h(^ z4t>b!&O0l8Mh!#3*0)xE7l9tu86^^V+l9v2G9!^fhHttthU|J|Ry8Hfbz=`@3#MZD zt6PrO$M9WiGff-CV{A99Uo<=I)rjPrfL*vCkT~osk`HFmIf^~1R{#@_=6;ndnw7Sp zt^WXN>hK9s*-YyOBl8FV7T|R!lZ<4Oj8oukHs1v-1mC@5nVE)D7z5=a-2MZ$MR3k4 zI-aEj@25c0?`|QvoorCE+(OYX1991aSd4ow;45O^#l9qmK4L7{>E=OE2)$G>w_rX(&0L&2nY<+YV1j`MRN9$Uo6<;Dmg_UrkI5^}MN zOus&#Z+~RkRjrySae*rUWZ;(T!0YG%zymePym73?C5^I*LuI;<4?KZ^?bf>sDI<#R zDOysA!7RfaS3UcGL!K)WSMcDH_3t#<;uf;8WhWp;F_Vx7133fmt*KtdF)>^t9v6%b z3C}eJ>xd9Y7ddQVr|w6g#Z=W?g-G$#s( z#~;|P-B>Zs*V-}f(?9;Y&Plc)9#~=z9P>zZ2+OYhpaY-vgVK_MM$m&&Qa?^K%`!VF z;*Ro0x+xguP5~i-?Z!HcdLI31O;*NjS5A`7)!I3Hr`YjfSe^>xfLj2A!0H(LV)S}^ z(^|(oHtb6~0^H*O40Ygho`1rmwz1Uh=Kah$EHT55Yx(YtcAeKl^=g!p-I#h;hWt~c zY4>_?@e+B`1Z!v8zsr1l+qWsgoM0bp<2+X_sayD$Le<8e(wo?zkhF3$xj}?w8R{1s zxgOZhdi449*aI}rZ4+`v;=a8{>VG=G@g<5NeL^^sZhv}*jEo+Bq~o`L#=Y7Yl`VUo zeM%2wi17%z){&xxkpPfw+(^m+(Br;xe=5=Nt**bO*vAlx*u;&GoVa2RPDckkkL^|#=8b)BVTW@?f7(Fu#6+`}&$Mh;gP>s-FCcPtm*XO9XY z$SQ>6CxeXoj0)S<^%Z@v+FhJri2^af2Ooj&T=t;mE47gobF=uA5PJ4C_m~wawB&Iu zYFL`tOtCDF`?NU%Nd^~z?boGMB_8o55ve7ymK=eDT_&F=n_&y%8Hsc9w z@8_>uY20a76V8H3p=1(*=on*+j@aqXT-Rlz_?0v*JuWocGzHTWmw=L8RRBLJ9A&f5 zQ|X%L<-4^Dxn)LS$N+;&1h%&W3xdsnskbDaIIp6{Q;s4xlF<2F644jXzrr&^mAZYd%Qp>ME*3n50AiCWnhAP7< z09>5)$?3Np>*ccu)TxK&j9Y8^{BE%tQrJg!#1^?tvZv#2z(+!rmpe+JHeUZbbi ztuWh80VY14hPjKciT77pjJIb;iDGk2SJZx-x*$_8-DRn-!$AiXBpeaEC9*|^Ue#N2N4C!gp!0Ln$|5}mB)3;_2zB! zb6I>Wq;9UQ<}DoVIpaO*DJ7Ct-7Jj97|R^dDcvDpI47=uN^O2qNw)*~O~qd2-3xiW zDx~9KECJ*B`}_X@TIj{5+g~t9a>@xEtDVqgSnmoI$#fw|9QywNpQUc8F9vdQ2I4W( zkSp{|lDu%aJfydG`5y_NVW*1BQhO_W$Lq7laICKi#x|C1**!;IbJL#Hi!c#QBxDB3 z!NEAs>E5T+{Lq*xHZ}n}k5Qae6@QcfJ9n>-#p0EGYm;3+&-6Z%EyB7uJ9Pg5h8{rd zfPFJxVSdFvA@F_w0KzytH=;aaRMTXVO=dK=D0j;=zFRY32?>o9WD|g@4lo6LbY;NF z91gYickIVyduQ-dL54V{5t~^h0`lL=W4>p6fs#s{*;f7~A+R%n`u_lf6y;Nhs?HWk zQ{U9JZB})GA%e-Ip|NbfTPJGmN>K zi;TTK{_O-NB#+E4ykPNEt*uPb0Ox9tyicZookKU8!)X8pAaRq;S+u%XKO$B=m+{;YeBYfDSf)Yv?dGvY-n z4nAGjInFcBBd7lWuBnD)1OxYm54~vEU#u2nH~=8X8@~5!bmN-ht16O-+eQ@QEsVPj zRy`|Px4Qn%Gnm!c_Gfrqypi-9k33^NI5oRBkMDo7#r~h+yP+A6o2gX!YWc?m3^2$8 zIUM>`T|Y|GZ#8MPn;Z5XUB1?VEKH$%*qK!A$0G+jaC#i#v9(VWffT+Lf=g?QV{nqk zc@>htN!iHQ2M0JA;P81M;5u|6imw=`Ue>+uw_h(k^&-9^SXvU7J+FIO&t9H=Ew+Uj zB$8 z0&Ahab4|}4wM3_}`3?JNd|kBtp}%MiU&p>2@YbJcr^FV+Pr9&1M$}-0vZdVH!m*Lp z00OE~HI6f#n~#(YA5tU%ZIhk`;r=z;{9m{5rjzk=#X3iT{Fl(JJVkpBizT(!ofFzD z?jb2A<}xn8xMEJ>gOi-sJr(5e+^msE0%UImGDy!o>-ow(Yg=)5!hj z2Tq*~9XL`}ib~1vYc2fCzYO$?1=p?h4ON{yi-NO4`xQzwZGsrMIVadCAH|Xs`)$k` zU860{rJN2B0Glv!c)`zdFnbg4*1VhHnqF%9-;pb)nFKy`Y(7wouDHfJ^&NdH(Ng1B zg4^r{<+tU3(jMRt27NZ}JRVO|kHGRMyBXpiHB`GDr-d~=HY*#{)C(iWD(+CI`P~r# zMnO6I-EhB~X11f^8z{UfZ=zV)Nc)~oG&jy-*mseT04D?rk&-zcmDMoAgL9D)exT5qE1#_ns?w!_NXj@Bo*C#lAF zbKAGpvUR@{OQPLMS4y~PA;^W5TyNkI0SZAG9G-gM;<+k9OLMZEts5=Pje6Hiu(u(g zb!LZBqU_JDV$rn6k8sGL}2BlZ62101Ok3 z4{URx;tkWljc;ji6^`xgZpyrZah@`NKdok>rQ~fG*;$EqbfF^hoMu)VcMhZckx|Db z)Rw!*RXd4XsXTGovu*xY1)(6R&g0*>$2D%|_Gz@#v$uf!l4eN*F=LaTpcr0#ht{*Q ziw2&>>ucwl*Z0hf#Xww2cMJ?paiyl zP(5nqrEM&6N{UOBT#OF*$Q86_Z4BKj%R<=G^f2+Q#+s}OfC|mGAE?jN*E{1lY@@r3 z+1r?LZZ<{+;Qs(KWR}iz)O0;7PQp9bt>l(iL1oKrAh07I#2lZkXZVLlnnz7mG%Axu zzGwseTjRJr1~J_8$E9ZE)`qcyPgZlTWRoBvz&@25sr#fKe`>t(2wb3YeMww%QO60I z@J4=RBP|-^b92+_?@ynhx{9&-nFMbY+)y;XazaXj#xM`+1}c40=4hQwyoD8k8*`j~ zHBJ!J;obkpn{{Yt&Vb)8(AhMRjA2SMiWO{Vsznq~yRDQtdrtVJ# z(Ydz$?BFro^6fpj`qnRs?bh!_m=r9@^B~=hdVgBpWr)HQmI$McIt{c7F|3OSSzsq*j=|44JRg*fq;S7V_Aqt-0DG>7 z1}=*GCzE*B!&(fMvTJW|vh1{Hc$L3+>ca;F;~{b|F~&|a&3y0i2jO;ws%u(}{*8Zm z71Z}KN<{32F)5I!+r<{nPUGe7Tz%jQfsFCaIv>ZJxr#Y16U~j}T;nk>%zlEpFBg1J)vi2S zcW*Mha}XhmD1^qbvvHBeNi2FExX%FBJoj=NlXRae6OoJzeggyW#w+yPBC8nQNb;o{ z8h6(s#?lWXdZBed6*AbtzyZ7PD-T%K(&Qzp85z;ragq?E9tJr4b57ND`-X@?FpRP= zWGxUm>JJBl*0Exl!v!ZfZuRIxM}DG3)Rrc4i;c&UG3-CYQ|hI*rfqHnkricS>$`#v z)9|ZltH(TTyh6O=llqL~)YkOer0rrV-p00rszYgOEO#dggL>?Uu{;uf=;ZOh>Us>< ziOgYXovqQ9GRI=O?jUvqfHHmXK9%eiHxVplS&?viw_4zJ%`;55noFk8%qYaS%_atN zGlf%tIqkR{NF`$D5QUF@TC90BtVPqlvI{{X=_{vK+74nJZ~hrS%w z<+PgOZ5{O`dsb#&D)!=A$dr~NehS6;hY=6-+T95EGgs!E!=Q@ii*%Foej zf06W@NTyKx20-hMYSawKORhK>5YVMIwEgA30=K;0>w38OZ=-gTcdb$Q9jbT7i#7 zN0&%8-cxxZ0d}$l3-a*8Iq8fX5JB|KaJtGQ+DsRZBPxXpCI&~>9XgNK+L@!<>99d} zZ5^(r+L|!jBZPTyqR54dju}WQdFV1L=PTjWM6UY(09}uu$L$u@^;Af13&{hTY?cS+!*LN+si0!}tdQ@q4(m^nu<(T}xeUGod;Y~u# z!nYVFicqB*QF<3C%B+^ASH$g8`xD_ei5g8v+ea>ma*kSUf!X6_R5{?1%oGmgvEIHP z)!4HxIT`!8&N}w~wfCLXyjq2fmN%BmG!jP9&lHFm9T;G%1HlAjVD-&>4|japh3waJ z7{rpw&mzSV#-Njvg-{hoJpcf709W&$j(C6eoF!ZQQIbmE%HrFFO(}v%Zc6-6$lK&J+ySIittEM}6OL1CD-~{{TMKtu#{&xXA`EN9A8lMx?0a?M3c* zSg1m_Eprg+5{V*z-4)!~1JjdPS;K7vF|1HSZGecXFcc^_01N;JL0=gB3HSx#UyoiQ zlS$JqKF6n8WBXH7*phvha!Aqs=*W!wnlisHOyt+x);<=$vC>i-ol$OXk^$yP90oLb z0`s*?w#6r)EZEOe*1w{>6~baLxLj5ytQv(*MHxQ4yxi97YqhPdbk**fKZ|~r8I}Vu z#^u>|8nTsY3aqL@H+cI+NyD4$-Kfd(x6Go`w=9!+meQoeEU0n_!4h};`Tc1x*;ey% zu1Ln<-3g?I=1;UUs2P5_^b}vXl3y@LgmhA;{QB4L-B03)buU}r!*D{6l$`KSr}_SM zri7bt8a}{aionx`C)~`KL5|0h#cRHyZ8eO^1;O)Uws<9|YLrc>)X}*U z>oGo|;mtyMd`)W6$s8DlB>5pb*RIgdlZ+2?e+~v4g6;DuN692~=QV3plI|;A_Gb^D zKzRIXGt4sqGag)JxbAD+%dk$I8*cai0DyefZJ2vWMI~z*GG5H=5oTe99r2To*QG31 z_farqn4An@xy@(D;oEiq`VO=$(m0d5?!A|}#{7CpC`#;(1KMH(hsA)GkuZg14uCHN8-a`bIw~Zi2Aha!*(1{ak zsT?ph^quos>dPFCo0JTp50Qh8Ml0ce_$%MW{{RT;dIpjEKIklNb!#sW4NqDiO21+& zYJ8~h$+k~1Zp&pKzPkM_-e~lWA8g zb3KenG?8O&{5r|Of4V?W2m3j|Jl9zT<-P5&yN(hBs2)7^0Q1j1Ysq8Ptdis~S+*Ua zi8&x;vU>B^fKTOKm!aH87l&;wuC5hO+aqs$C;)+gdG`a}qEfsqyE0T%9m_8EYkv>+ zfO86+(kd=X4^E@5G3{MU9wXB=4;9IKCdgattR|jGlM*pyAbg~+9P~cjtB$^Ol0=d= z46PU{z~mmi4^K)J_NWYEJcH*ZSmzua z*y;G!Gvgc9xp>-LPU;vgE=rlLR1`?n!t%w2z)sV<82Z**T-ze=dxQWS5?o_A&MQAv z@eCI>O<@~JBIIFMkc4gwM^JEaT-B6i9nI)dYIm{F_!`dC>Fs=HH!?KDtn(@tP*r%y zW+RTogU?Fpu5MBE*0FL9_>pi)I2;qf$n?fBiu3IUM!eEBfvir@#cK+*lSOW2Wl$qw zyO4Th@=x(#bppEGTgA58J-l#D1h3}|Zc;u_6a&}aADKP5<4Wg5pxo|>?evW;{>cPU zkj5fsQMm4W4l~=5$B#<7wzjAUTWG*NKta!M>VGMcq$S!uShtfnMG8Ojpa=dZ6dpRV1RY>aZa1h^`rzqix9Y+U$$?^8np z%-f4@MRriXpwCR!Pl&V)as-Z9w8=IoV$C1U6aWb)Zg4)nhNY;aRBX(Pd%K%bO|z|AlGYbevr5gul#&SR!2>zZWB&lwtn>2y?mo3OoxC%d45<+-8QJDb zw++~jU*%l&BvOiOh3({;0utD`E(u^VR{-??06w18J+6ffzAq2@;0VFaK=k0_^sPv& z;~{{XIdq)6SDb17ar9<|Flj^^==kI~5pEJ)AePF6b;4A~FH4^A=1 z;A>w~(ygqeF4oS<fhz&@DU#X)Cg%pOEU=joWR;KEqOPu0oVbL( z<~w;KB%EO8ur+;d-sav*Skcrg;zp5h1`p;sdsY7c8)>?Qy@(0^wckgRlbN#I8-D6A{D0z0Z3YNsMU=+kMZAtJ zf!GkCKxR|xTzK*S0Eu5zk5AJzWr++sM1nZmJ40<98;`>^d&f6$_=@7V9Fn1n_Wo4D{nYIjl_&!|+;argpkyYh_ciV5^oZ&mf$EpVV?|)uB?Fi+z8u^E|vw z38${cRriGMwJ7A%Zmfinu*-h*C}0m5IUT^`t$6puFAQ6F8&tT5P}Ox*`&FyPvJEG2 ze5ec+!zgkx4*(8;usJpFI`4<>?`~3UIuR)=i5X;2IQpFD{{XFAPmXP@G~E_WCtKGe z)1;BM`I@AG5%5bWR$>7pgUHVdz&Nj<%CRnuRQFGGzu}+ceBLgb*L@FzJagdx0PNoo z+}>Pjk={)#vP*9%AtrP#M)@Nd3!Ia~5DrF8Gg$K2-Nf5Xtb+@a#z(oxuR;B)yk%)G z#0YflCU~!frkE|w+o@!XiRL9?A-1$$i-}UyGysexMzaWQ7gM{l2z&f&&iLe;QEa8ta}X{K{NTT;E2Wu z0|cDs2k`X&02AmzMliD}MBeb@+F9ytayMp6UzwZ)P(rX)VxAksc=sy; zS#Yd*AE&Qx&ber8)=0eA)GjulA)7eJIO|(Fexz-X*!_phW|%UnF&y!LI+Mt)DOcpt zqYANK5wmX^Aj%?+*$d5J>-sh1db!n~h~&Z~fm9#6oO|>ELZo^5jtQrI4sO!WTiqn{ z1h|c43}KWI7z3T8sRswA1Rp{x(Y_G)r{T7Xu0wZq;LDHg$#3>)gHDx;^E~Wzl_$*i^RfD``z~I5Mw{Wah0l+?YZkRN z?TmMJYSyJ@w~5pcvQ3}gk_xdULk4HdIKdv5Z#~4)5hb}r85tn;7_SQOf5aP~4QaM| z1(uf>hR)tAYa<=WjG`)p8=1470OyYRuS)R8j&!>#aUQ!kw7NT<@(FJvaS<#4Vt6AU zueMLUe$PXb*(ml}@A_lqDyr15m$ zqmm>fFe5vG=zVJ2O3fzXzk4N{-npvAJldT&X;hqaS08bEdt;|&)>hmkQ5xqXEZ}s= z^*!m@H;sH#t=yeUQ`J1l=dgQsa{>*}@8xg+9eeet8Wp)dOT?}mfw6!focq(QEZ0tO zUr!Lq(3UaA>yFtNQP(~FtH-ZGo$k_X`rI9AjtV-f7n2AM21y|E?Vs_dt;=9CFU~5gc23bI`*Z8CuGF%?K$9X%~+zp zBHKjI={W6ni(VbKLwP167%_a`E^s$3YhA;ZG7?4<6Y`vOKb29?G;--+rUJM&+~;{gKtxwdB>-{d$hS_fl2=WTb>>zOY4oV>teL25|AU4c*j33 zFlreSXeDD9$51NK`#hKtApute9{iqiDN3nbqyjw+dC;R7OLKo|G>@o%V0~LjPlmde zhmNUl_WuCw$*w-aW?wtW@@?15*`3=re7muX@m}k3aRsC;adRj{L6&3Mz60FrKS-8S1wl1IL_Gsyb{1fMe-us{K_PXP4ndV^512V4?5_swwH-l^h=d~#s9 z(i+!Kj^0CUalK1VBD7w{@&Itv(6VS z#{_=0m2Ie{;(6N{MlCOZP}!l##rElJRhk1 z>*(o1G@;6TeksbVxr_IA(OcU*s=%_27d`5_T?zOyl_iESm?xf`=dVhwsKaWIsE*_B z9F5J>@B`ks8;>7&l5Y>ZR(5j2MWV!RX0}NZS=b|Gk+Je^5^xV8*QP-ZP1w#9ob)L8 z+xDaIC&BL&H-vmirRujbn;7mO{?1sX{m+-XEX>ib01yh3ourU5Gw}z-9b;Vmpfo=a z{6W{Cx4YFZwK*PnKeJ7*c)L=O z?kAqo3xt;CZQylSL|8x+w*eI6esHHOd-(o?p-Z5ABA>v}&Yn%>@VmXad#ILiBFPy* zkdwIp@|Pil6UpFo`3&{fuP(F3uI#rZwQw`0;WoB5_hSQElGlSO|AJ4sH1tE(W2?wH_ zU{j)IfV)7&45JbiINmXgA6^L`jZBsIBAQL;U6Jje@aimfBVd#&Be5fpTXuT){4z&0 z+g%Z^b+HMy+im8z%%rjvUVir(2OoQmyn0rpkB4TpwqvMDCEQif?VW;S18*Y(xALnJ zTSqKjL$mDLf;XN=x$9nacgZb|*l87Emhwdqig;z3MKQX|8F@CpDhjYC?&NZZAdLNM zpuEx~)HM4mtAix5#S*{o=JPUG4cRZbk6xU1^aik#P1A&th#(Lu$G7ApOWl4M58`>4BM+%>|Oz-A==L7?c z;2pRf!Tl>;V<3Fd=kcuV6)jfWA}I3#C9*m02kHFlMiOK%`^E(a8B>P(9+dYpdy?t! z#}&t%jKxxMd?CgGx<6BF`$hkI#%MAW{IyC#lYR0sec`Xo@2xJizMtYNQ^ZgyVieR9ubsJ+WJDl{a-49L>Ni31GD{#3dAbhHQy=v9%yAXz1 z3xH1qaa=A5Pjf{R^($4=+U98FF)_e7Dl?Jjf6sGJC92wk8pKy8IBfp_THjdI4pe?r z*=+5mVDiEVUZ3Z^e=pL;@~bp{z^Wyo&1%|RzOiK1H!R^8f=V$5kLUR0XSWsRlUPr0 zGuqrmi4pcT7-2{_ImcS|jY`S`2KeI$S0t5A*gl_!HHQboojT_6^^qZ%OyWTX+yrcb z*~vSyK_5bWvFK68-Dq^ut4T$zhfIArz5MGL}1-?hU}tBR@=T>C&h@ zyQ+E2fU9x4J%7(N?tU%!Ssks()U@kZq-(ctI^B^$9D*=#0bYY0Mh9Npi)k8LC_`Zv z1RR6_@N?R|IvBoZW<^*+q~!CpmmY5pn-;(F8Sv;AR78}QqkVt+}&t4_UUmRSP5;6yT>PLk1+sj z;{==zoDQEWe%6{JT>M6t#2!2G>{dx==>>q*wUKRQ42=@*5kmXImqZM4AS^~m7{z^` z49YcgN^);V>u#^7>U_>=M%Z~PZ=vzm#0^^Z9Y5@n=_vrbv>#}BP&A5E=gYwZ8*|k6 zV~i1+;;w$cw~#8LgfX#kgUapT{{TOF-0^>mZ~Rv&z0@ruh_2(CG{DKgJy`R`e>%su zmO1WYMM;_V{F~Gqk6&MII`Ln=VPPs%tk$Q)%AYFtObfS;4Pmd^5hNaIAq1N@F9QR( z>;7?6D{I7-+I!quPP<}Thi^LJK{)|}md1Nv^u}v4`r6vnqFZ~>Hux3f+PK)nWT(D3 z=lm0fH@sb z2H~D}!S)t9j=yVfeRPqpo}?s+xn##XPI%`S{Cn4`LuqSokF(oGm{6l)0fig^$8HDZ zQ!Yf_hc+&%iseRpwil^G`2vfLGT&Fz=Cr(uPc5(u#8eg9a(O&;7&WO- z-c4l`L2svyHIc$EnIK)vdI9Qq=}A;eq2_x@NWs>8J)vq^n_tUe`_ke3<(Y%-1B1C+ zw`?9TJu7R&ek$=7hHb@$ldjxF0xnh=XL%EFEWxmI^KLzTlpYiTUMAAwv1{waWkuVT zWne}?9Xj>RQq#39ChqNRp5*327BCd@#Nc+Xa}26DrxedNv?n{Ju8+_kgx?wd9{gOI z6X4sa?`2e3ZglsxmN^h*H%3m~yMc95RIth5p0(=`-64+ghr;QT&V&gSLjc2ai~+Q5 z_4!6}0qv3Suk63^f?t6CC>|iZ)Bf3~Gx-l}XKdP;UM6|fNGimv02KvG6i!CaYwxWu z#hRr0fP(fbc8*t7j6{sAq>wU6W1jtmeyfw_Ut7c8u9EAg{5koSZnX(K@yDoT|o0o+jh$Z)}wx1-|4J*Ueh~pQY>2_@i0ZG>tEQr+n6O%#cbZFZ z%y`Kl0D2DH_^rJf_w6tniDL4PnIf`o-GUsc=kU#V*X=#=)57=u8<*k7hNQRE2BmKt zvuZY%sPS9vomeN!oy>f*kV@b(o^yfmyg|g6T#qlQimN4bpDK6vrO|1wuF1WX?(C1! zI4goPPB71?Ww>}r#!`>8l1to${pmK^S5do3>n5y|dL9MwJH&^^9yru|NhGg}$(i92 zBB>FKgi;rbg$fU^Jd$%Vw`%?_%<)sk<7(EM zyr$fn^KR__08+9{wvJVoQNmG;p-wT3S7j8EUnGi@07<|ZC!niwM#aQ|GmiN8t5)!| zw;MweUka)K>zd$&8BS><+jUeT%X)U7JKJY^6=D2ImN-7RVl&}*6ICje9dZ(yIrTvyU?dLd}kVQYq{5=O(?}e5HAaR#xAI4bQm2uY3KLJ|*fJ z-IU)9^)-k8v47_h zz-ST>a(au4d}hB#@ZT`2fZ{qn&Dl+;wcRxI{a2bl81c^}!e;yfiglxRN-l7HRFjUY z<#g9n&!L5-^l+axJ*t3^8}X{fAk8oucoIimn0fh#8FDethVhSZV$`ykXI)eJn`7q6Q}r(#u}s-Iu^O2M+(?n zvfJIX@oc!;lmS&8nLxoLxK{aq+mLJA!zjaEr-zECDwkK$9ZunZf4$Qpvfss4$$2HJ z*+{`RhGk{llmxfRPfTRzzf4wD<^H3mp_V;0G3WNGsSUuDQ%%ce`aNvYKd`emD!OPZz%0z9D4Gsge#Q?vQ?B`tnQ7zIlK_emo>eMrxo>z@%XbRCfbE-q!6UTH25m_&R6aLPj* zDFY;6;Pe&i68Lw*144@GZAu_zU*5OcOoTBDlu#6I13l0j9zgB$2gT1D_<}DRTthE~ zq0_D4j71D?{%6c0SqL%>s_mH+-~d2n7$=jQtHKeyjc~Y6Z#NjNjH|yA_{UN4ZlMmH z4xbrg6pmg3BSMkwQ5udT!m}va23I-FalRx7~(oUXq5Q4@?4iGjsamQXdjxsnSHRU&2 zbWlk4iw~FO$ir(8#ZMy{@AdYtR`C{{tk~+N-&V1^hDQLzmv+q?vSfflkT}RaxxuVC zd|Tlg7~1<$hfdUEiWVPa-yZ2n4URx3Ic^&Sf!qOKo@P{itht=6Zs*lt=HUdQueQel z6^K+Qb`~dwBeqAW!0Gy$=rrpn>@9>bka9^Z1~PyBSgcKF#IWjmt6tmb<_mnWiquLz zLHsMdRY_I(M?ByjMr)|i*242ohW6Sb71KLei(vF4p13{ztHX^aQM)tIsV1VXh<<{# zZu}prTB+MLysQoyIHmcAPH;f=U;F4&78q4ZEK7#Q;f}b@GwY0>%-30Et=iw)yC`)i z04&Rm#QFeF^Y2vf@#WN*RFoxjCZ7OpHam89+9CQ>7Ly1X3V^#_Q#y`)kUea~Qpo&>8{KjUJaoT_nO!nrv zrpK;5e}p|VT0&7 z_xgTSdKv9wv-=a-?^2{b=?^4~6Ya;Pb4o4hk<_DQp^2plZoC<`z?`pODX8P0RRk-P6zqLXr;17#gSAJdVz|NalsiK$E{U7S0hORR+48i zs>o(z0vFnile;_&C>?$C`PU_Vp(U1`aVfbnw2ZGV$j;UPu{)1L>yy(S_37r$-_J7$ z`jB>>Kp^B04@1-P6~%m7(R5uCM?NQl+(1%Q7Yw=DRN+U;JLerRI_I@|RB=Airz+}o z;pYpewQoQ3Jip=}iFAJqcw*-MSfQ3pn2y|E3uc#}m@J(`1>8U%Hym?{`BUN-f_yFU zTU0vN#2qDdE2acA^2o}}q~~eaMpSlQi`Wd;(mxfY({T_SHaJqD8bH?gj_Gy1#*2jmOG^+Bw zkA(bd;T?OzTDSI2r{U|%An|X3Z!LC7A`IpFbjUw|=CF>{%dy8Cl6bGAziK@y(^>Hi zo~@+#!pF~DCPg}T+9p{XBQXV9BxMD>!lQXW3gi=lSH!$gW#S!sP8wFD;rPo>Czoo{ z-AA=1bttS)L5+o;(9MnEB&liBFj@I{FpEnP6HRa;j*~J`S9mNSC5-=T; zC8Y{_hOdAB0D@8e#^14L#D9S&SNO|grt025I+ferY3E+Lvb(aeMvO*=7;Y2JjOAqW zc75rDWac~%zO|1NiSDGd()9lTDKMKZR_&DKlsWkT+nljdbJQC4BU6%{uc`A`%v99v z2V?U)z#s5S%Z*>dcQ>%rM9}aS(aJDNiXjrGPs475_0hm;S9;y z+<(C+-$3wLn_2j#B-C!FUoPSFc2Bad18gw)qvqkm633{(8%b}u{>6JZNvvRYm1HCs zd29fjoHRVanx4} z<3AK!SVIV(MYX!Ol^!`h(GxI+LyfW_3^5=Zv64q8Aol%HkKwz;h18+H zdynlnyeVfD#Pe_7v-z>8WMFfVhAeQwhTogu&-f^RhGDt=p!NM)eNxUyUxOAExB2DuwDkR(ea%AZk|BO}}qUNfhD&X)RV zifBAd8chp_j%f7kGO#%W6CogvT-T#%wzFAj*7jEyO+1joi1WW$2mls2CzIEyuWJud zbmODk^Re`>*qYqy`tvASXdX7d({4Oe(=3JW{?RlbsGH0uK4CyO1&0gVjD^QF^bdf( zIQ(VP^lN!MRW6k^^fNmXHl9nk370W%&);E z+aMkZz-1jyckeOGO*dzUPHU9ISl#cko3t#p{9Rm@sU zX5C%D$C$xSE=Drl_APb(68)-vBY1Aw{tZ>^wRxp6{f0}Tku9K7cZOKeOq+pG%MGLs zyw?q=*!_ZW51YR!yE}2*{{V$W96n-~WjGvX@UO=)JZ;1jXC|vXZ+&ktau*%Q6+NsH$jY%HX5$-2 z>s~!4DbCFL38=ysA04Doi~`5pnz^JbYkwFZV?F(FaZXEFfK+I?9Zoo@?O|n;3O13@ z?eAXh5`&FI?0I;K>QvgfqOBUpB2F;91~4&?@upmd#z`A{GU}8Zee8dj;sOE6; zFu>sTuU`=*$a#>8aw^?z5eU=~j&W6iBc)!PV{QOEo!oY+a-ZHd6o9|%{{V%2^?4|> z)1a=bM(?~1M^15CJ`V9-v*3Rd+4#3XkptU+KttmAqw9{LrwNKS_CmVsoV{p^M*MgKLoMf81agwu5c56nDto{}Jd+^u9 zjWFEmv)JhOt$+4weLCY-N0x7u3bKL}oU;`G1Iqpt()hCBlG-a}$PzIuLF_wzzomRr zTAmm2Uccb`=hXZ+fA(qK6BECbkCY@5Fu;zgKPvsthdf)Zr3yKP9(!*%w43wgvWtH> zqxmO|zKu93dt6pYiuP&zG^ZCRuFKkUIi=>~H-97P`R^_5oFvbJMtWwbwa106_sKPc z3BFRy=GYzVdbb0q$5UP>2geVHS7rz`Y1T+kv3r;;);U~rh1|-~^&_HZ3tAe###^0s z(X_byFd!_$Gqm1lOdS2w7za4VKDGN!QO8*ZV-?Fc7p9V3{MFW-Zte2a{$t`l2>81t zo9CvcwY!9swDOlMoz|%&+tFI?#lMQ56D+(pZ>w4Od0I=+Yb3UFMYqb2IU%xg4j1MF z1Re%PNgq3WQ}~;&_>TVoOxB{-?h^4W0Gj6BM~IdiRNxF_=8T>`T$7Aqy-!}WO;1a@ zhT+cXEgmmB%Q7;lLc9UVz~~3kxGDY$=#mRdokPU8zDl9r6joT0LFN}A2^*0p){nYCL#HfamHK9U%-F(ru#%A}G{@c#fR?61BJSxGeV=)NOo zhsJM2d@-bcxuZ{h4gt^+G(vM9&7Dg*eqFcI*hMxO6HXuMeNzT zsfSU#62GVX12@1v9koFF?b9RLx@~8|clQ=CSokVyNbO*{ zkdY*Qc*rS`36NliR|h#Dj@YhcY;=2jSZ0dkeWl?H$gZqNU=DB(O!xQiTiVCO?MBup z@3f5>?gS`&%KuI3c>JOy6HyUMgq>v#Ez^$93M<5_x&rUwA8%Eir33T&eZcHlL|Xz z@xY<3b#zSBuc4QHrAK1z9ki@sjg=Q90@a8ue1f+hxkdzAdb}C2G(6V^>0jOMJREflyw;D4r$A$*lbp5CMB>HLV!um zIIBr*BQhe|&xBAE$hhzH{{T3y8!Mgdu3H@iyvuO{%%krPo`#+P86&@1qo-NiMGKO^ zZygo+93NxqKhG6nD5Y6L7dTYfz_~d;FFiiA+qsI0xedm*9gd)u{{Ul#ObixeJC`G~ z6ZzvFl;h$HX(S5K6~W4ka7gXeuw(`+wn^nBk0TG#~rg$1sii&Ce(^b=xz_Ca^DrT z8*42Z-U;AY8cU3zX)p#9pC5#yjS`_x6CbxPwTv*6gi|x=LYxBo8p> z1$u*!Hn(Gq-sF!*2m8v=irurX3mB@Y%VWztXQ$s!Db!No=7m&~89YJ&1B{;d$-wPj zKm11;4cCe<8^l(&F-t2DjWQ}ck&lsB6Z0Myu6uEc_Z??a)u*%aZlJr0H#l!Q0ay@n zydvj5nfxoq{y2DlQ1K?07MPm?RD7k zbLhfRUd^<;&k+5iyer|GUkq6IpH9=`7iQ)wRk}$S?t^5E7p@N=bJvczuO_m#w2t0g zUgp-y)G%$ng!FD7Nq9w9?)P%rhzx z!36Fja~xo<0X+q0cw^z8!kr^ml=!1ijdX!`8$Xp~w^taFFzXr?z*WMw81DPoJgHXw ze<;i-VepEauG;LqG(R`S!d%Sy+x98=YoPcK_I>c1Po`+;tLpX(d3|?f0*P+pou!`L zWo@CPWR7HCn;}kBNf^(wN3+XQ7B&?dHuT4}ay}8Z(yiyxVDR!o9fWb)8x%;yF{A-h zqN?$+LSO~Q000MS>onLJ&rgEhdx-7=XAK)172xAPo)4xfV~?IDq?_p9=l=i%@+XIn zH=8v4FK;XOhRWq-bV#Iq_#Z3gHUJa#BOm^(Qt=PMZxiYo#of-8sn{ENOR7V22~djM z?F+Go85m*CM`AeG@Xh26s6zt6BVEUC<}J^rKOgH_o-6S!)`g(m>Xx>jyoP0tA37&0 z`74rfj1E`>oDv5-fnLTIag=Ryj;v)DvEzOvw!K%q&~I!Rqqmvjj7KsY1#ECau5q+u z<>%0JuY!Nzt3R{mkz?X73;aaCvb(Xqzqg*(P>rRIBR`k0#VW$f<~iETjUe0rNR*ZN z0sH#$?rY1LZ?5FsB(Bm*_ya6XNx-j@f8eEl1o1D#%ijiC_)AQZ?R3a>N%ct)(FL?S ztW?NMjEjuAj-X|L$ggt=B^t>$YySX|5a)!{li2VoDoX`>nN!Zu?@?V?;!zrv#?lGH zu*WBi?)gs@cvxBj35Pf!kXZBW*1c*p>dqVfCp6;Jj*C!+=6iXp?V}!C%D*(1E=sU$ zoCA;sG1DK*9qxys*Rsm!fRbBzX>yPu^xOkTzDi}^=?9=}Mf_|6b)=3OjW60yon%l|f@AwxibZaXK zOwj_&e(7_aymqUI?;8h=%8}56gGtBZMSncznZ6?zjg?B1a(i#s{^#M$gA11BROr#B zp&jg(SGzRZ#J3k%d-dMxm<+fX{3~0-uGe;^X)XRkD{L-%an29r*R^uh)_79gS4N4W z02vvJ65UR5-=_dpcq~OsO-oJek7E;tr-i3@D_qO*7N0zKA)|l@$zq#Z>Dsf5GDgKE zjg*d|h7EPPj-L(LRGp8?58WV+YK`xQh2+gKyxL0>k1st>*0}N6T<13F>*aO-008u` zIlVZ>FsSY4uly6A*^)M#XP!lD>2`^22JmuZ0F#=M4+lvktDBZ&Cz2z^K;(c)#&P_` zUbxXOY+{71tcEE7SQ~;{jt3q80G%ujRf(kCNyBct{zpbDGs9I%5T5@4FU+m9xd^%E z(0fv(C>>%+$t-!wV6K0iO{Bwc*YQr#5SU}0-3Y6-?_sc>(j3Q?Ulr`<%2$HUcW{Ul zuq0)=V;xQ^tcxN!SyYDZ2*Is;5IpAN_Y+$B?V8am0fJaZ4LQFoJg;611vG zqO*~nDjSzRQz%o$Iqg!Ow9ADp2~Y{?(0kX()So@v3*G zR!t#R`HMx*^{rUEBWSj3CeqTF`Bz@K?e!kDRB+X%u8grb{51($PRB5+&cP8$VsHQ) zlTyWNbmf&ToRvQ?3Qj(?)7j~1WX3pQQMHP(QP&>6v?K;HLn{JKaK!%rTJE7vbfl!- zr;m%wDdHgM!YQLZ+fR~f3wQ;FjY@ zUkFKXSs>Py;^!u4qPigYM*=nj1&GEDa0tmGJl8t1%8F4WV5EXTJQ6d5`k&5;HEl*2 z4AEcCB-%lBm4jfMk(~D@KU)5T;jT7WgyTx2b$)s;KQGGX@&_9DUHy?xc#2c^V|^{F z>X)DAWqX;o7cFqee562`!p67 zdIQvTuBHj1)Fx|aw4ml<#HXA=B<&}Y{_pwk9-$tkq1(qK`gx8m;eJGs+^^eUKRDTY;1jtU<*btL2rXXQOR=f&{AK_rphYVn1M7x!>RbDf2V z$-o1Q1I|Zb(zJdo*qCf=0;M7ELn+S7?Lu0?O2`;N$+kXH#(e& z6cLSx&iF0KRsQJvq+pTln(*t;qs_@E>W^N8s=9pYT0fa?-oyJ4c{Z!^I3=0fl1L}E zFgPQprC!l=Idy0+bt&g$wuPemRl~}5!mQW;E_o!5Fb}x^)(x!l$*WyYb8mP{MB)G$ zRK`nXavTs;bMlNILMzeq4IfO5SYI7bnNjmd4^mvfHyAUGPuFo4&3CQ8n+}J zmd8}4;cJ{##CFnO+<6lKo^cVF)NLwB^&IlP&A!QS6tWfGRD~*bf(Ogj>)$-}ryGb&ra!eH zIRGeeoad2`^Y~P(EDt_*QO{QYXBoZ)`lG~2#oby^f9JIKfQi4`>jS@gfD}vkukH-V^&owpNLRUax z-+*um=CnLDpxjS(ZVr_u$ne03xZRFBdK~^$%Kkeebu`gp!qLvDce*qs92I^tHxhoN z^ZI=&qS7qpwhYq(G6n{E)x8(PdVRdI-6g-7G~6>v#fL%A9tR+wQIa}wS}<67S3AX& zY)B&x2vOG^IIHBeY{+xDO%O3YTJOSTgA8NWp{EOLsKI8lYypy44gjv#N7Jq0jc&fm zfy#o7)Ts0xoMWf-rfNDT+hum%0=^CubDHz2X{s(VTQlzT)*}ocWhL982P2-Gij>{5 zW6WR)Ju~{%SnOp<7kdIT&MJSh#_|SKI8*a(z|TIyzm>5VdNkF~*W)NXizw=046F&y zP-M;d#y1{Rx3ujY zjrn!tF&t+-#djK~h4qaRIU;ZMBwCM?HVN&POBEb6zv??(a&p@QuEhEfkq9 zhuKvA?V}2;HvkV{KqHZd>~L%LjG9-qILUJ9YcI#l@bhSUMC7l{*5{vmMb_rK@h+#O zTEw>YiFDBmbio-zfROpm;yTJ}SSplz2y1)Y5YlFbfFEd4Wo%(EeL4 zcBx$BgMxE{4KEPe&1tXST3kraBv+E8j`Eoqm^lQNAZ|YR8S8;wv+$?D9yIXZh%M}O z4;X~DMngTdtiEQ;V=9?UYaqao@&PDU<|jF?(eU{Cv}xWFwU2_1Pp6Rxj388O;!=vB0&pZa=o^alEepXB4Gky0*EK1dFXmlb z+bbC`vOYsABAf&xg&dKb@@vUFCEAHreCEV6F>-M0qm&=vd?nnU`F>}D<=li1=8{n!?yY{n< z-(9uq*H(GhiWOre$sfB?PYw7RN4nJRw8N~(TFo5H(G!p6>qYGKL#yu(KAT&9G+P=F4 zs7fhQwY-lf5gFa{D>Kfneji@KsIlK9k0h-eam1@5GX~p?D-+4+dN)y#SRWMr1xe!% z3*UH4#1|LVv0Pe75R^wWN+xhbGL;O5MN+KZQ=P6yBP++z-WTx(lc=I;nrsUhjuPyV zvTa|SuSLfv8@OCyhp4VM_se4&2b=x2$|gUR9utz3U;Y&K7*}~4fui= zu+$qnY;O?9F~SGo8w`F@4^D?Qm#_GfPw?y>edJdRH>#g50y$tv!E6Q?9FR^c)x&eB z-5nE$G}Ai`FwEBKV6qdaRm!xa6dOhd%D>LNVj%=k1h!OEA9NrX{VU9V2I@LTiTpKn ztXo;OMe{;T>NCP4a56yq-;dxc(X{OOC!gX!(!V+J4;5AzU){>qZ}C5={0+)zPZp(C z9LjM`ZKo~w(^cieY_8F`y(I_GtGVyE3ELN zd0JdVe1%+>b?OdtpRO_9u;aFhJdL1&bI9pi8YGP!jEbusHxdIkQ-Q`YUqO~psR>=4 zPCA`A#>m#WHib}Id7Fkq?*j*(2*>rN+nZp_Zk5Q|b_64q?VoCf-brS*Stbe_BpsmR zf=7BDK#rbKbNxqD4l+L7;1eZ7okTL1=b5TbWvdAKeHfJXRRAiI%t0H_R;T~{tn!jSZ zZXwiC5rC@M9r4@OpzB?Q65vA^jANd1PvhE%wOhB5i(L%h%_f=X-Q1& z48t6ZdVAKAs*nyk(vlQs&{xb=r-zjJqXeI!>MUk2k-^Qh%6EF4c9IC&b1?wm1JImy z2AdV@qWtlK*y=bRl|iaW8$4lMOALdKzvqKcTV9Ka1ZqL!o(*=k{W_!aJ~rX(Elech zmqzUM=*5dspGuxP>w9LEl0XU}86cbwx)FQJ+NlG}57vAME za5=^S9r3}h>D&f7l(10M-pKv~;w%j4=5=o#udkV5sZWHSu^$vyvJN+8xFu@ci<|7-Zj$h zKFu)EnV#rn_fEv2&fb80!yw}r>Dx4_W>ZOWHGe<&2Zi-}bTzf916>3k!h<|_>;4sk zYw=gXHy4uMN3Wwyf%aP)Y4`pg@B2SoP907yv&L4-oHLpn`>KbN^J3$Pp^GzIh+J_lpPdj$x`gO;8@+#tLO1;-t z*zTo(hqJuj;&+}P*EGKqOK2`MYiJ>}B-_Win_vwY*?^&Tl~TCcaezmqZFqkDwS+c$ zMwZe%ON6(zQr{>X05A_gcmsedi$`W=1~y%-fKEPc0m#ApImb%tehuok8dr_2rAY0J zMZeM-bU;xKQ*yadQycPdM&K|`Dk@%6xh|6Sc3lpWN3hm_p5I&Web|Oec@?IT$=3)} zWeWfZQWuk)=bGqzH{snO6`n|LCYU3uEVjdLLt`uEF5L0PPt*=T?xT`9qgkPmT^&JI zQ;RHTKc{S8gW(U(% z+Avwrz;ZbI$J4hp%J_=bM!tKCM3DWaQpz!sSe{g4>MOyoO|8z{9dF({oNll1pm8p0JeLqf@P#4W8kBzAi$vMV8_pNtImoUU)EBn=4Vn9Y1 zdiVO)Hm856L!-+KW*yBW%O(iOJGud!o~Pd*oq3a#qdOztr#Uom_PT7jChju7KLdYN z$NBG0n@EAMVgxdRRGAOn_aB{GQ#1bZ;R3q=SOp^-4!Q43U9{uQhbU1RU|!yL}-cNZZH?6yV`U9WXyYKPth|bZK=-OOv)V>cw&i{_j!S(z=9- zI9F^@Du6f&F-g*lUW7JD5;1jDUQgZPujzJ8E})T1AQ6&Sgj`j#JDEcIO1s>}*Whd@{#z=DV)u+sFX)8TB3gD)gFULMDpc zNn^-o>)YDAx{FgqBkdU0Y2#TVLCN`mVZfl7-vOF@-aR=j&FVCX*a+q*qD{{TOgO+DSUu?sYy6VPKn z%CNOWA&_;05{8=cFkpn!!<8>_2Qz|hBw474>yc1Qu5+6 z94jPyo*2C8LjBSLy1L_>@SySa&&YqYPlFRm)8X+>trVkGywsUwWMmMS%5FGCz*1Zm z$N-jk3uhv}!SQaS(%Lqk9FnB)s+4q-YUd%l5!)Sl8u^R%h4C%@{j}O(iWre^j5ElQ zkt=|*Cf(rjgbbA+Cl^8upstCEz{sGIH)rlPD*qiWtO(=}LU z@NT^|jm)wv9%K&4PFxHz9akU{F^)Uet#~^7#CndscVl;U63Q8EEp3BotOGozQ@LEp z^X*ko-Ls4Z!QJDpa}A&u6RNVQ$woL0-yKI^V_Vt|p{i*b@z>N!0lHpyf<-cXKgjjyoM-Io;l@FzE)=h z7GME5!NyNQIL9^mZVFMaX}voi8;PeXDcfJ`)bJ15ul8-w{v`O0+u|mey$6EL;aE)-n6pc5RNrdN;x?#6SIfnM!v6Gd;iBn*t%MjymGAIGhH@!*^L z4IT8m@3FChCyl(lhdgpm8+qW6P60UT4?jU@H&E(+9<j z=YxvB1nTM$pDul?^0kBZO*Vf`(8b2GX%g0^l>mE9%HugCfC)MO0646z>ykGP2R_xO zq{$>PJZ#8D&_ax4XV>x{hAY;=awVybDl%(BPAI~{sMt8?kyY-cjc$VNW-2qm>EF_p z-s@~+$tLfcjN^`Rfq_-t;ldR`fu3>CAC+V5KbvFL!r^Dkr6gy0*9JBc z+{yF$Bb_xC?qwP&osr!bOm&z0KPJpFmV?dw!jVS3XfVvU>+Z1%1Mb zxI?^Yj%) zd7`(7%`;&~Q;PnU%jY=YqMWb)00930J~)6TwSo%? zxMP!yF$A5vdIQ?L>r(iYt|iQfi)IiXmNr=l$6#=9Prve_rX!kdBgvtKb7|Px@ujj@ zYC30zyeZ@R=C_MZw^p5<6EcuPs91Uh!Y&<&Rt`5FO;2Uvonu#;9X<7{M46bc+GL3! zOmK48`9=nN5`E49iVuwm;=8b(Bhqx8FaoIx>2^L+Hg|4m2`AA1MwmVcR#d66NJVT`T_rR9%U)^1QXj@$8$+?O)c-h8RXUwX@h1?D{useZaxYx9J zf5L-I)3nP=Jr>mJih*x#qjqn!NJu!ujkG8^00mr(Zpr4kO$Xt}iS>JL49P!w% zm$?We0pE;~Nz_qyxyOj6qLq>~ygA|T66wAjx74-wRWdKh5SjoK1|S3x^V4oeIQHhR z+n~CIZ&oE_EHF%?a3GP&_0ClG^z|9N=it&lTpn=87!jnpv#xyrC;H%*aBLPBI45#zqG`*R{!MaU4Qt@noK1Md6POIv$e zL<;6SswzrL? zCOE!!^zLdnBbj1VnYT7RX7~JsT+_;})MFi7bNJUB+9^oWx3DQ^65t6ojrn46fyOxF z9-X+Ws<#g+tSJ~g^`_R2o2E=>Mr8yHmr;!4kMq{N>alhyNc#QtNEjV}kEpDRo79f| zZZ6ocP#A*TseABy;cYRo*jsc_dNqB(4+^3G1G@=ku@U3|=3b zRDQ39af{Tqb8!{Sf#QK<0Ama5S-0$b(hCv+;CgT?LM<*!afp<*;0Yx3_Mq4^He`S{ z=f(~?pScCat$!u*WAB|+p`_57&Q;q;92lLHsc$ZEw zMrKw}B2Cgquza}ANF&<^AO5Q62CZWIe|wCMK~u*Wt_fkKN>*t0Ftwpp7e+?6XQ?#v zUrTJO7IBcn1at=(&pcO&{9*W5HFzf0w8Pt5x``lu;_1zyug{M_--7GsM0sO@~SRSW27*ULIz^-;naTJ>%fI0;Q3WJTL z0zRA&aqnNCP^%iy(D9xIlup!9Zs*O`Q6t&eCH z`a~%mwDDU-JCI#tP`iqamnMGHrg$_%Pr-+J7m3yx5^Nbz>mF=_lF{| zJTKxMa{1cw8;eas0v7^1Of+h!HmPmLB>c?Vfh<^KXaHAj3>Wt-lB!4ML6u_+*g#60 zj-W8Y5(yov>9}VJTM=KHEqw3&e_u1r%wp+Nv-}Epb(F?Xf~TB}e>$25nt9@Y24*K@ zYuD7^dv!mVr(Q>Jmksuy1caU75y1ydd)40!TT4CQoHF@vxMl?NlB}SQ%>H%z zHU)b+c5dwW>|HKp*%03NdfMMyN%Y-95jsGk@)<7VxGJTeXbJKxXB>yYEu0aB8>R7w zz(0Y%vlJ(EXs+wBbqYtjf}u%uD+K& zrm|B=(ofnYZ#9t<%`&!0$x;u$%ZzY)8uj$kH28^VEaQ!e1m6lA~ z`+;5GgEcKbMewbTmvcOD%M2eJ_0Kh{13ti7Rc0O2>0gNB`O|Jo z)6o9w$)!oc3J+Ur>!sN(!v&SPbivIh+8JYLNjqd9w%=-NHb&_`9Gv2!l4w=7`HP<8 zJuBzx)|5}NqfRnNwFS$y$e+$T`U2fg7^^9%+$juZEI7#HkyK$oK#(v#gc^_l1^}w1 zjH?)hS`^#Ru=hcn%d~y$g&e~^O5>zHI(cTOE*DL$#I4G2jXj@ zo?xiSN$zuEa`lO#>AjwZqSUe7$c#(;+3G8n@b8RZTTyGO&GV}t-WMd1)DC)_{+~l# z3SL;sSz)?IDie0b2OGZcPg?qV82T8BYH?@hn2e_pgsR~+w_c2sRM%Hc3!6r5=jCF+ zDH!J+`;OI#d#~yfT{X?6!^93T9{hpEI&}RipNPCf+LY@Zsr}q}+UKhi)brZ2Q&4Eo zM$#)|uH%wzGF)bC7w!=9U#Its|Qo zHw5)AnV|bZETEPCA%otsHB%E_F}IYm1B{f%r%ryk;;l<6#~a+wBC1BE_=fT5TC(YKfjkpQ40DNbxp!bngdChBXLf$@C!nv`_!|V=r8KQ?F6Z+PjTyx{ z7+BGhzc#kN^7(z`pA&pl@U4!oap9}!F8=^@#yMtzM#VdM0g<-?3C9B<`eM0{6!`xD z!B*ZExlI;LLR+io)noH6rri^Oer@c>1u`-hhR7U@k;6(auO~M%iDi;+-ZYPvX*VCe zp7|%Qa%$#>;6I8V5-%X|$AJ6~scK?5)V%iglDsfH*i{bdHbMwYmvROdB!H&BVx?B1 zr^u4~kK@|(;a0b_lYe>4IgkUf6!0;Y#(zrH@K1uZUx_|5(mow%R~GSKYx<)$jlT(4_Omg$~F<8Rp;;;-zpt6z9$;)jMTZd&q7dGvn}Y3cThdEt&Z z4B{ymERiy_kp~QeAx{NLF~G0Y?;Cs^_-FBZLxW54zMVd$Z4{3*QMREf1d-GN%(1Xn zU^;INjJIYv;WQuE1NLpuwHv#G;An2`Zf%+YZFxP!jEcc>!P--`@(B*1SOb81lf0nh z&R12p%`T_O-Wbo*&V?O$McH9+Rofu2@9EXhE7S@x^rrETu$}`FN0EobWP5 zdvC(eh*moFzMbJaOEM(1(F0vdWhZ2j$>jvWQJkj7$R``I*w>4G-2MUaPr-d(!!zi= z2oHulGo?Xir@^gh*ATS+AekZ(NcU1izFcyTnLv26Df3_VilJlkf7zSke~I*ujv8}# zi&D6~w$|Nr$>QxBO2{L0K+1|liyq^H@|WO~Ts0<>v7G5C#_6APR&~CLH0b4&GBJ5% zc9Uiphn3tfxEs%Y=cZ}VT*(|Q3WdXGIqT09*13^_+PqPi!tNhA2O#?&dct*_R)?P8 zo3SiRf2N)SAxALZ0X&O!OZ?xOniCw}hj}T_b&Ikk?;~%K4i+5=t zNf_j^0!caTT3#K{tu-j_VQX7(08Bf=8IxnEG?iIqlZGzxIT%@OOj!Jw5KBrCZH>s~^}b);C2}G7R$` zHm(bvNK)DAYnD~HS2LD}Z4G3iqp9=Wy>&14%*_;xoCU}QNf;T=O!HM9XDT;4k{ckF z=|%P9U*1W2(JW?0ED}8JLD&qEa0eWcea$gg?ovQFJr6@z!w}^6Jt@&v*pbXlI zuXg7@{<^=T+z2iRiq+(i#sbDNNWmu`h#!V(hSn???cjDmD#R8ymqZv~BoV>r58`Xm z=CU{^1=Q+cwYiy=HGuDB4YZ74W8bIaT9%qLFp(srmR1B1-oyIltLV)0>LzI;B$fNh zyeaMU>028|rE^MYGn=26a>bsVG?Dr50A(iuSde>j)1_+KiJ)?EfJZ#_s`_+|acrn# z%BkCyewYK$R+X8yf(HW%bNDQX_n`dC@osU%ycKC4bhqK`gYYPsvQVwG82 zJ5NebLF63Q;eS(YYLC&DBg_d33o*bQNvIo9vsT;Y=blIglJfbj8Ap@2FyQXRW;-*n zb~z;En&Gd6j1H<*9ER%dw^p+YiO$mlD>(snj2>&xuNK}p1a{YrGJ*Gudq?4uUHt1C zKA^pheC|4xrkXyRDyX9tn=@+%#w~j- zg~hg-k$t0Y?%Qz;G6s1EgN}sv1Ds~N>s>O^(7%?X?@+8C2ao=}L9FTebQ*Qcji=jy zW6Lu}qmT#$ zH8|wdE|TJFiLIZ@3n8@vGRk?+Ob#)OW7fXc2JanqK3@{=Elp@{Ao~hjqacjL8Fqc# zV?1%w9@TEj^7Ba4Ak?g8^5?geC4yDK!vYytbqBHZHOy<*Dl8Ep)oxSCk~VKNs1BSd z1dMgbW1hV|DlJFiewU@%sFKcE-5^y)h2tnl45|qZO6OtioO6yqu9r$%qn4H#$>_B{ zlK5w;YF;C?hf~&kK|Y`vmIxZ^$IEdXY~XHem3)j6a!%%8Ng!viwDD($?jxQnIj+`6 znne>MND*WoD`y9&aC4Et;PkJQeh_}sH$D>a#C~R-a@s}Gr`qh&RbsBF`=mg_?|jNQ zDp*9hJplEXd?7Za<4bQFTk6w&iqloOV`+6LkfgVQMhg}YZA`0^l5lZ>mSbO0lj1#v zn%}A?8-j3Fo|n~rN1= zj_0Y)J7WW{HHT%Y&3AnrzK7wQ+@qb@C|P=?O$ z?A~Ri<-)rpY>twU!47cVSW1FQgqy2%*zW>cwAg7Q_@gruT<`j&hLm{3w%xRk6TX)__BLB zCHn+-FkINk&lJ$HDy+MeSbV^#461UZ^uaizQ+3WR4loDZ$?5O@d9S&@XwTWF!ao%J z9P(-Q&{}JDHfAj=QMr;ru`czHtc7ySxK~lTa8EVZ4A;jW8NLg6-{5YcX{Y$k)kwd# zX{|1;;h04GWMpLqSkUhnRx6GcL?`cJzcJ5vew7(cui0+?o=5eU0QjGc%%evICcUak zHnpzTRr24_vl1Ob;2;MKI~E+&ayv-oM(R&BoBgK=K%;md9-v~aTHHe;n9@K_Gk`^Y zL73qyLZe!>chm7dtnz%$oqRl8w3U_a`n7hxPeSY$a!0i{0HdycwPeiL;g9E8f>n{4 zB^-?R6*^o>fC53l>5B3tPEg$+Lr%0Nv}KY>IVO~`BL<^MgN?*uk>zj+M9v2Qp0%75 zo7mQKid&MQJF)FkLoCSW%bk?6?If|}dLM2F>9VtfRS&JN!Pt?_mOSgjo zaCZ)bRcdr(2Lzh%p;mC8GInQdslrjSFWcTTJENQy83ZqWm1Gj!dwOEAi?QfP$ie5R ztJc>tygp;ez#Q|>74G425}Y|?aMqz1zGa}{v@usvkZ^Fm^l*BT+tk)CQlwy21? zQIY&R$2`?tQ(F5CsFEvRHdf*oeBh=-mB<~*!)JhcbBv1j^4zV;N)T6XzK6$WneH14 zMs=%7(Tcu_zrkwXlGLs7Kg3pg4}@-mM#|TDv_@D%09{+J%(xg*GtLPI2c>uyi}g7y z^itNr7)<_4?gxO%bB}uTPaMX+D~erm^`?x)6Uhttgd?om6 z@fX0pER*6t!$>t`%og_Aj-z0cq+z0ydRwuNbTTegnbu7F@qNOex9=GiR~)YlslDE> z`tm=8`1gvX#CfyCMnAicyB_T>zc=_FHtACN`dzf%S|G>vN7j=Ll*&;zzV^#%nQMG|9g1E$(8}G|Px0XajHZop6r8fDwzYAT!}X=OkAwtHx5YJE-8A z(e8Sm!TGK)ycch&&vPW6eA6)V8zc`fs2%$+bH;e%71dXge$KxZbZui)x%fo3raebW zwUXq>w=p`&33$#*2J;cOO^g-B06V^5E3WVdjJ!kQ?F0K)#99>EP1D>+ji<EvMbC+T9q=cKJUC+bjo@83U(;J)ILAJ47R!QQww$m&u;8ZBFTjnzo z0xg;C44ZO8JgnnsVk_I^)2?OL(_3v$QV|(^hUG>^4msdtDaJaF%PZnF{hV5KR`O4E z71V`|q?V5$Xz`4<$T=A*FnxHz=CZ2|F3%~>OGutkXKZen&pxeG z{HMMTYSFcd!U^6hc3&`k<=v78AEkJ>nvse$qMV+lTER28Z?icE1cgJ;)|QVxr37Xe zVz~0!A^~7_sUtZZhi}fLn!?^wxF*)vS1ZRDBl^^K4QHd@NhT&cnmFSONDNCUIAQ67 zk&Iwq^{P_vff!4O^CX{Y*vK=J^8WyIfJSqU zp!@k}i(=AjG%_vj%H2ANAu!5*b#ezfJQ4(SMsy&tT<45n z^T+G-u4lv$O$!ugR3_YRKuYHwiLax>$w{L*$+l&~Bxd1bl3XJkG4!P&c@J&kR#j7XuF1|Wq5_4Th(Q%_^htgdwWBqE08?`p#>+F{1MjMF00Gwv4>Q@t61Q9+rXD9Nimohx69!A`K zYx5<5x=rlQw^)trCB@U+%+oN&dJOax6U-3_45Wq53s6WAw9yugoDqOVIp-JysU1gA=0gur z*HK98opj-&Jj!{7p{uNM+r=o$N+wkp2L*^5#z#!?+*Ut|?ckc%`&J|y-a#7zF@n3p zXV;Ji{0FTv&sCl|5N&sm&YLzW^0~tfNX9|y?b?>&^IC_)F+yRuj#iTrT*&)K1&Qms zE7)X=WALx3!_#!ylJq?K)929U9UzVgVDnk_@~SP5>m}{JTgb?gqU> z;a&mJJ1)etaev`^Xf<4|@9zwtkaF2patIxoQPi>b#{=*3j9q6n8OwElozI`gVPK(n zuD_wv(r#Rlo}FoGIRghI5yoqobwX57UNGKE+Sj9)Eq{425bx-Jvr;2s1?)LVL^7bX#sA3al7@; z72O%T92|=GF?>UVVl8fOGb3z z>QtvyN-oW8&zgT|pV@m%@%D`trSQ8((sX@8PL6pN!p}{L5vXo4m59i@cI*iIO9sh& z5}=kJG~5w`8OaIL|@pn#}Pp!=D29s!cxI#r_V{wV15qm+ZgV))8C?9oY%m9Zu4A^&j2( zSIuUeIfl$rls(x!JihPpKW^Zk6|-&~P{U$ZwWAxg{ObDYEuOvZ^>%hiADqJeAmzM_ zXZVLxR#AhfanOv4`j6s=>~rwP#eN`tSHiaUo*x%B(yLh8#gsQp+mcX>PShKSF)q+R zP`fa9c<;vV*~7#i2Xu)%S7ClHbho|{#;j`)jYRhoAZ0P~pJmrAV^?r+;qw zt5*L24Zbbw7I11d9}E0JJ+#rRuupHI&dVY)}#j+r|k3bcg1rmw}WnU zxJ$A<#2U38l{sNeyX|Dpw5!J%b{7ol*Th09JKk~s z06X8wYH>qQ0t<$Xu<^%`K*;5Q{=cOquZS(gL2njKz;e-`IX{^8uJY^lQuw25qU+kV z^^foL@~2Oqz zAo2)25!6>?@`|_`agADTH@^CHYx-Y3nmO=%S%J81P4zC?kSoUrTbOSyeTLdP8raqUePNH`$=Rr8N4t0`J2`bC=2gfAvp zt2X81h=x($Ag{O9v%cD~f*DBw0tn~p-mhB9&u<)aM=CLLpD@QeNzc-~Y`ZC}=K0l+ zFEh{Z)TpOQNw)RtVhj1mg9P$;7^-4Y0Oas;F;~|~n^D%_(rlo4?k-tY7-B|gC2~T9 zP&$%$0CQfg@Q3zO@fV9cM+AO1(JnOoC9RrCC64AXF=7V9+lMH35Ki?N0keaEevbje z*t}HSV7AcsJ|g4nk0!&axS8&*mWjVa^>5Jg--n+I{B7|<=38F~SR~Qg$r4^oEy_la z2Q9Uj6S;@V$K?!o>C(L)!9TD!io8MNy)x^>{xQ>{gh8mUFWBFf;d`r$ahIJ`n?M{XL z)x7;&x<08St$SVC?~m0!6>EMQ(QdEiyouq{c1I{>xZK%bgKJ9|5_8F5$JacJtiA@< zF8n;Y;zxIVJdJL!#|^CHtVTEMzA?A}sGy-L2i0rTFJ{+o6lt1;jfKUX!C$lqBisQP zCxh3XoF0RvY+6Sg7STZj3mj;HQ4jzXK;r;(9kE|S2CjZjQjC_n+~GV6VRdVvS=h!T z7aLfzvpSGVGhheC+yjgb3CS7GPL{W3`n(n}-(AR3+U7gB!r*2_$QdMLjDPy-=CdV^ zm#e6Z7+Iku6;D=djQb9MN`~g@(QTn;4Y)>Bg*n0Poc=Yk=9b4ysm3u*E1P>mK?LNt-d^Wl94xOR>t5t;Uu`$EB*}_Q5geWZNPa8oTkaNZlqFmg^YiT9qsUb+? zF3TKD?|?EuRRx&)07>X8%Kk5WU+@+0fvt48E^dFd^{beo@SHa~Wy}eGa@Z;n-BBAT z&4Ih-+ydp90jN{e7|O4+*5}Q>5BQt=Pgu{W>V6*Z6jqHZ2`-xE32m}AD(wPES9;PGZRlMN3n2=k+qygxFlniEPi3<-v+fP zymzGAc&6QL?xKTLp4Q^)PQH$KH>6R@xG^&X{{UD98G{n1Q#a0`&^{MCN%GW=nK<>YRu7kB!p7EBC8_Azr--zTCe~}4i`dzshDm&cm3+q$ zs}>3g86#tUN7A?t8T?_=wW~3w=x~(-WQ}ui!y(5YFHSNPl1S@;(W}h-W8*8mKK|3e zQ(at3dj;D4vhAQq#ER>}g#_c}a0%n?_svNZ(p#T82HPsIDA*ihpXZOtxp7tGqS84b zO-Sl)Z)CK!ncm7M3=nZTLP2+6Fh9CLK7eC9=eCWkunka6adR@rN6N^%j&Y9p`gAqK z-dJ7OjhD)XQ2tqTY~@uDD8@SiIqGxIO5D(5k+hhZSC53+V4?=|%1#`Da zQb|lPl37>=03I?jGw40(x`l&ZTeY(St@5yRZLF9e&%`ykh*&ja;qqJzymxGI0WFFV^H|EttejgtDiq}v za~tBdM=IAgEFX?2Hx92dKq)=ZH1vbqzYw$XZ4wwm^?5 z9FQ}Ck4#|a)SP3#SK}+48c4Mp&1+V7mPndbfX;TS00=u5j!6dx>(e#la_ZOeK{eXK zRauKGEfL2z}OV?o=MG7)+O@oLV$A4FhJ>!f2Ag$ zs7Z3-7G2*acZ1j5({+2epyRh0{CTf)46P(^)VY$DrHJzRJ+LcA&qTP@ zF5`jaR01;3$!v4j6W=4fC8FBTa(>H|^3apGb^LShTN(qzttzkuii~mFzx1zWoOzk& z*QqLd7o(2S#|icYakTR;8z+u`PM-C3Zqnv7AnYOk0C>VapH8((SB6X#To8Kk%{m6% z6Qc8h+upmW(>%G#=)LxvFSN%rjUfnrU9pS<>OmQ;D7C9=X(KV+mCT66mpBWabB}J` z-K!E1RX=;{{mlLu%}Pz6Rx6NCOpM~URMKgfUiu$L!LRBv?S@wlK)`1tpXW{*rlk1- zd=E{dip^Is6Dr7|l}QTS_&?!JYwN^~=4D(6k(Z7+{C>Ze=kqmi@k>OHqN7u}dTWc> z*JQKg1K4BRwP)%gLSlpM8-IJdBLg5W-9EV|`D50dr(NFM$W~ChR02s}dFlD}tj%v# zklYv|Y%(zgmAZ4={P(XH6M<7rGrpD~!&3Bb63jQsqhCXPkkrvUam z5nRQ+{PwKx7Txk5WMPsy{iY_i$Lg zWvQurlFe#kfTl~RV*HJ{8^0W99{8?9SN_Zz?bMcb@k-en+XVdOLxaWv9HVj0M_x@D zr;M*;z1?cDHMsk*$bo^#BPYIadmrnXcG`px#spjULG(YVf37~7YFZP9a17Iq)8-szIV4r+}?^Ra{ z;)sSPnn^Z!jm$RjUCJOt3M6ftPCyy#d(%lLsi~*55hnQOM>~k}#&-{{Kp(GqhZ4MC z!))b=Ba*nzaqH_vI5f_Fe>IBlArRhM{&EaC$2|d zq01uNqbLzI2}P&W_HAdvakiOt<2@(h1?9x67o5IMS&Sv$<=G$1IRI@{`^dm9P8YlV zowR={-%#;w--)kpWk_OyY~@)HL?n(mcQVKW6O*(MI4I!!*;M(vOz{Vcd?#b#8+%yo zt|HZw%(gJWC!G}0A2u$8f)DQ$jxu%-a(36Ie#yTOJZs_$ne6;Wr`cQXyNon4mP?s- z#U>s#na=}rmnqILI%FTR!`G)7MoC-z&pQ)_tL$XCwEZ;y0D^rV4y6;^ebxoQP)P63 z_|qOeHd~h0+W3`@5}Ur$`>4W}+;9#v*ysC$p%u;et5Lp=!s^dUM_HnVIc1y#Dv_7N zaM{V)uf`8gTnfshvU<1uQbQIx{YL8bFR0WBeIs0AyY9oR@#FA?&*x5e+`Oq zcDeHy%3QI%^fr7k;>`-?`Zd$_YiXWz`C(ax@-e&a^#o&(M;zBcbqV)w;{bF5u{c-tz$NzdQ>3iEezX@GVb$KhUVOX63((o zyRjH2ACdg(rlaA=<&8A$Vi<2AlTLVNiewIsrLf9XxGRU-j^jL5G}*pNxMD zE&?^SxxPaG06VRmql|aTjP|Y*;vdAH5By^BeUF5+Bxt;rnj1|*^591llCv&2!xE)q z!j1`P7lDj7n|QOtRvsJHZnP_S=D429`g?nV>LX9x$W>WLEKWel1PpZfy4Mwa&W#Ux z>z8kt^|@yaV>1M!D874LtreF|{XawLm5x%emWf7x)(rIH>+6ccxcDpZlf~NC*nC0o z^G=jsT&vz)Lja0rW_`r@h*iO69FW=M=RFUcd@lIk;%^vyMbi8-ZmyQfV=tbUPj4eO z*koV;ro=ceRoc^mPA&OZsQX;jPC)2JA+6I40I!@BLLS` zJWc~J!@1jBPR-yikGQW@5*KMN|3>q1$LbM7apetrk@qv#l&!|tsHx#ZK_$= zDyS`tlEeY(NXJ^s@L$A_3wZm(_Z}wj&CK)K+T6Rht;=cm;>Gcau4&Yqe*vPSJNiC$2NfF&3 zRc|p=f(VcS+n$-KUl45dn@wj=*0j)C($`Ox2_aJC{pi>>(5<+vYbHCMoMe%da-6!H zqgEX}_t*42n*3wLm8ew1Rgz9?vQ1tocGmmruDjaDG4O}L_8$zqL8xe68MJ$}dv=!U z;_=YB4TA(=06;B_5KqkAiLXG=Cx~hWd#iP2RReI1Ktfz$yLUf_&{qZU-^3c`y{k*& zg|QIZ+}k`-hGr#!8$blc6yUCMq~ib_WY=e7ec?QpuB9D81Ym+VBAsCzP)Nv@$r#$Ig%40S9!EjR zJu{rueLqvvwNW9{uVb6ZlgpS!`7yrG+gNo|wUw}W!voNYw2(ZDxDk(f=(=j>imA#j z%@zyFq!bLJJg}=#-o&wHLUN;!s#u;q0O#pco#au6E(zp({B^8v3s_!gz9H20eP;bG zV!MtswA!p)0!wh^ShF^9=B^09>=i=OjqhYBLL9BL7vhJ+jT-MmvA^)giY(^0O=bap zM#7>MS7`t&Ibt^atMg;0Q&;r);np1}ar&;*h*D3G`;=;-N;1^IUMIXl4vZ$CNy)qWh*>^ynl+kIn9@omku zw&`?jXzELG1T({H6lPZ{1KLTKW)cD&r&M(-w!7~He$<~2{7dm)$DRuCj);wO;ax^6 zEmG^tcoO1o^o_wz(p{EFFW9#4$DSPV9;xugTOD^yu!0G$)HR@MPqeCe zEiUCdC3ehMIV#>*!5PW=SH@6HKZi9PEb5UTJWFbm!wJI!mCgx2!;{z32f6WI18VZ= z9x-Sk*6pn4wSAWm&vdEwmCEKN>KwL42dK#C4SM&EF0C}ko&n-z)q~5pT)~ZwNarl2 zfNs1Kp7_BO{j6zIvU?t6<2sYOJX6J5e1048FuIy)_{{R~EpA|uDj(!C9J zWQ8`oY*9CD+sOkY;19>3t}n*Ye`sqfv4X5{tZacX(>xvBextD;TJS1e%Ix(h=&W*g zn#Qkq<*zSgpL}H<=AFx9oDRH>Nyq;HUpZQfqF9KdWjQ%GV}tVNKdAgGV^q=Z7FD}0 zo>X!I6@Fe19RTO3@6$fDgREV{9Is}^Fwu3vt*U$ zoYP9FZcpJ<^#ajap<9ING37o-8RtJ==TKYRJA%(E5;OA_?ZtaE_OZt#+qti&Tnl@W z+mtIQRxH@Su8&E%wT{&M(T&TKl0iRSKb3M8vCO~e9%(1cRz*EHJl8{R;z$-u{oo0~ z?_P!*bI!y^nVP{eKrM{^l{S|IgtP7gs9;7%TvmOJ+s1Yl%I)A2fIrVQHk+tP4244g zy9puAa&w&iwe3-aQap;0lDV+)hC>+R=qfp_{{V_H)bs+YoqEiJ zy!L`7k#U7*&Upi%#dP~S=+1PfeGi~x)bz<*`Fe~QbU!GZWSkHNGuN7y##k0PA-L$} ze~TOj{{ZXPJ#C@fSl+`lDZ3alKH0CDUy&M}Jdt6`IN zN3Tx3x}7Gas~s}v!(kKzGJ^bcIU^h&YR0;GCb@ZK`_9FVI&)bzSGJb2I9%b71?L>| z*ZgZnJFm3HvtzHJuNN0VQjVu}8Oo%9@Nq>iT$)PxS<&{D8SKJd&Lai94I4DDubOf< zs*arck4ntcbg9zen$F$YB7Q)lBzt<+x~n^FMI@ep3X4#*x{}mv$^y!FGH`!C&+xAL z7%4_P$sAR&3ChiwacP$;HND&nfVAONRFFXga&idt_4;+Ke-^Zn=|#lohkp*p2u=yk z4;4wg$lC$gSRSa@Bk>f=<(m0?xuh<*!C5jv2DmXfbLQqdC}JLn^Ot6JF6>Jal1b#6 z&U^K>ost_ken$CQZy@K^w>8@a)AdQ=COmnkXpM&e;ef|c!5-al(z$<%^V!?@Lr03= z?LTk1k;E?(WJwst=-&;_e8nS!$YI7!c~x+3Rv3FqFo7suLh0iMF(05Kr|9j(}P=f9^;o}7<`Vhf|HT}LuH85IyH z!(rRzIT^&d|M9WmCsPlFKNSa`IX zn<$2h7Mlj<_SQb}OLOS(sdj1jb84mxrh14{VCTINi&C*e=y@2=a0^vr^jo0aO4sOKp6+O zaa{_mWGhZ9LzZtAYPVC1YgpqUr~Ten48Wh2P7l-a=RD_5=IGgpY+*%ZX#?g(&Ix8_ z`j4BBOn0r=taQyZ6|}XEAj(7eag3j@bKbIiNo#X1jUC30Exg#~SuR>=j$R?1>ZA}u z0n<4jE-}tWHA-%7=cR?ja!Sn18j#fxPNZ!FfT5J__Q)sNzH<1Frpu)G>r}FyX=HD; zw1!EQ12+EvpCln8o!R3bMf;<>@s;<)oexZuKn1n1Ddt>ROitr~P7XmpSYtRInK|cx z)o$*KwxKI|vKD5NNkcOdc_%*nEt(KW3-}aTq zk|Ep^%ZRYf2^iXPa*opVivF8*ed?30<4 z0f4K!fLm!98$kpRKp=|A)ipGuQ;@pB?dXQ21Pj{Fita$y)mCkp)B*tp=Fhu z{o-+&(dM|SF=~|By6OFBaMj`Ls~1`_#M6xVUDeg}?C*5fuly6E_^I&`J|=7S`r_!H zVKCUOyGQn)H+c^2yE|7LI2gxl_pWA&E6u5hsa~s{M|Sr;iWpoj3k@0+7c63|magA7 zc6u+uPmB7e!@XMT#IWg5-A{F;n@Hi_V~HFT*&$UQFdIJT+nvV+Yo^pcXzv(!rDd`4 z6|SC^^FcCyqggXDZ;NPE-6k=(1Gwa_;zn>5yst}Ddo(J@al-{{;QRak0F5VzHBanq zCQG#1Twzfe$la5Jj1Y5-o;@q*aQLdxqZp|l1&zSqCyJd)kyr29+ZvXi6?DBjP)qA^ zcfJdlr?z#87$Yvm0}YOh4nf=xt_}w6{{Zbp@k>b4m&7nfaWDYSHC$Uly1FAiAv)5W^o*M>9=CsM!p1 zx@aOlYc}>P1an9iEXoVE#VwKnV~*^4*W2XoRd9-&)tq!c7UMWlrJBnTN=d4k+gq-l zYR{&<^s+W)o@paxG9FhM1ND8{2NjEZSve+)9FJX?|X10;M zvP%dH%WD*ji?xxL%Wt~EzW)HX@g>%w;hA+CjY8VqU9xROQIofC123LO9goa0*tf#J z8oy>QiJm$ApnOT;?+@E7?R#x^;tLC#yMu0*p`}9b#=tN#q?4-Q*#Y60s<_XoIx>RO zQ|0j3i1R*eG&}?27QL^0O|_TA9xw4`wW{hikr8V?t*Jf6*j0;pd2&cmxyVt#EP3SD zpZGV&-aGhps!6TKkuXpNW=c=m7C^P*vryS{{RHDvXcFD z_W1KNPS-3Zx;`2NK0@sq4agvd-Im;P2*4Qmh*7J(h^vjmCCfQ}7yOSx{g`}DqiWtB zOZ_LrIy=~Ce+@h_4!13~`RDslH;9nCB#f~bj__mh_mgp!U=Rx0@rQ{lwd=35==Qe; zAsnJ&lbF2RkG;VhC>y;`BOQ;cd^z}Sp!i$C+Gm6GnW4MVS4Xt4X1%fxEyNJSRu&|X z1A95QgNy143}1y7t*=&ZT|pu{vGv08dY1#Od6n_4CmS6x!*kkKJu2t^DOc0g!^Z+5qDxJw0oW)@9N4sZ!&_ z7w%-5Kx3IDP)Ilg^TyGY>Cg|tuslWM9ZOEMkNXE&)FQWn-)i}{4sngd77_FVfyY2A z=P?+E?JUm9a7kGb`1i!OGBg$zGfNeu_TonKBT*v_=LF;Z(0IpR%an7IfaIv*bLssm zy{4isErrD52-vf3@`lwvF~f7uJ$d!1C!RZW-y!+|)YdTf0GgmilE@N#!cb2QNL75A7B;XNS zR##BVZWbvOiU6&H-vf%~^jQ|(+5XWFnxvs%V^f?4$pO3b`kJ{Grv}tuzC-N|Hvv?? z894fi^yo#!-p8L-H*Fi4;}pA{RP7{WVBqx?QqxruT*85YJIIkh9Gql*J!#Wk+pJOC z+h4P88C6wNk<@1+j-#*TUez5^Jo&?063C1cYz#{<0ENyfmBL>rG0g*f+~j1Azg$*; zQGW`sxoiS4w1P%C1DyU;=~Sx)Rz1lX>;7|Il{nnxcIL744eyIQKVlD?sH0#4L_ojl zIIL@}MK2ldb`^I+`=Bx3ZgKUlR_f|yR)##4l0qcLdjXHv)~@MSWj}o@kl5ZJyP&;S*^{*QlLz)(6rAD_d#?`Nv<$mmUIrlWn&<@eGe_*Q-G^d;E9iWoUxRV&ENd9*UcH?gf;Yev1Nndii>6A&W%`?wg$^c?e# z#;NMJ@io8M1*0U9oMF2G=yT0gjpsxcafL!xAg3759Da2P&OT5H_ciTH1ffpHn;b_p z?m$q3g1xg%Rt!!%REm?CiIW>jk-_O${wCCQJtp5U1Ya^usV+ev01rdgl16dHJ;ivn z@J=qs_9$Xh^f5emM7qlPd2cS?BlyAz_2Go?E9q{{X_POdfXMB&kS-OtW)r>6bhvHEp?Z-VwUW5GfuQAg~R*F3uRpgSpH8iba${S<-p{Ydj z7LaZ&hFr4+7#Qi0IUNRb-lU7-e~Y{u;>j)aE8G1#IP5k(&4t@TE4I~rxe_nRag1Z{ z0CSFh-@4c;@xAc zLE|B)TtMk3*)9>*NFyq%wG5wm0Z^bX3QzlBRME!ORh(m@@9Jla!okz$UvcjGZnYh( zaNDh;?ox14MJ0(KVEnnq9Y3A{t*dL#J~1FtjCsdAel^Nzq8r(x5;;iR{LDxgABo5L z@6x*o)=xCNolhJdKhHJwIc`3xr^?=oL+9&IiX^k6OBIFiOexPUn0M%K5 z5^x1siE_X@R9EeMOb=IEz`Re`FRPI>G@R~`wN$~Ft*21I6_ZezfV(F zt-%S&9Fx#uiaRE*06sV4ts7eK{;axYvu7>4m{vtc`>qKia*@Lh2*}SMj-ZPBV(QM$?KWP(k|-dB zkYodnxIbUkv3ybR)4={Lvx47V@U^YXVo43Tk#>YHAC~)A5x0%K4-6H)@`65BFvwwE z?u)a3ar*ZUaot=5;<0O_g(6Gr~4^{uudRwKFr=h zA~1|jv&nJMx^Q}bT6Z{?8syb^Wg5wIKQ(9PeV1$K`W{!OUwys@M|7_%zE1yvgonSfNe8ZgwC6lfdMTwd`LAKV-&};r6UPC23bWez!f&-8xjfNmkw^ zRU$yKu~yv0g9bl!MmC?A^_mC6O&h_@9+PLKSv0oL#Is%-QMz&pzVcfqCDcAMg&+Zp z3f7KChC)XbO>VWfd))K*{sj2Bw3r}@>e?H#ZcKt% z0TG`og}}~Fm_R3yfX4@n;%XnWSH!JG-a&h;X_DLw7~n}*2T&hBHo=3I01k(7$s2k1 z_%!+a(=@j#*<1i410DL+{TD{HyOr)P7bP5h)&RGtJ@LTwuYNgp8R&dABZ%>li<@g- zBjm;SGw~wFQ2Q;|PczJKEU*ewa5Xk~^s*k}{6WK~Wi8tDzh5BC8MzVEqwmZ)0SLw%T+m$eTo^NpgF! zIqH8ddR3?=X(S48Gt&UqRv!b0qftuj*!jF>e~YU|P>M?G&#s>{!}b3Ff&L-7{kH5r zCqd#(e^1e7(e3Uprm?vBZfAy6Pp}Z2t-AzByuY}iwi(qwh(Z+;1WhoKj0(s6t`Xq z@Xw3&J3Vh*@Z?k6X|pBPopQ{4$Q@g%vf%9{6qP4wD5Qgdj)A@($s@-#z2b{}W@8~c z$0s-dW2fs@mfUy)J#l~mACF4EEN={r41)}eLk#pHuG&ds6@snv zz=fZ5O!x%jf(bpl;<1)#%$n?R&krZD&s^U_YdL`2Y?d_+Kp3}gnmQb-QfqsNqq|wznE=k_cL(*wH&wR1)a@jSDWW1-w|wNBuNWYX zhX4+pJNGoNb(<|7IOM&$^210l21#x~JP&W_SF~MT(^;_>R&)7*PRS0!K41YoN4;{c zYjYzutY%uxf2Ui@t!9%$3ZF5HW9AKv0!KIlIQ@H8ZlkVV>JF@1%L=#)86%$Nr=MP) z-t$nimeHc~2r$OX2}7KceRG`m><1jyWqPzJ+g6MvHd;Ep+ZNrhs|;)_#ZtIYG>I6I z!?t!J$X9n6>}h0{I8ezfimE!Z906IE8nv6>KvL{4mP-i-Ae@1ZZim|y=~08eff*7_ zb9e$F1q!YX>5fSR`K+pNc%gen3KCDGH|~C08@|9R#gL6O(@~7qle7t<}!`g^v~A2 zAk<}cXDB%>4vynimeMtiu3T+9kwH9>+diJ%D#e$Gt(~Nj`&5cJ)i`NbASVpRt~x4` zeX@I3n|Qn8b45HcXqMthBMg@>aUNBOBL#N1L-Td^u4Bi(CT|y6!4(Y%Vs4Jg6DLd#bhNp6~ zi08U;k`ScHA;R)G=QY?`MzLEWARlxSv~W&3*9f6Y0L_3;Cmk!Z(~Z#6BVfVFiCG9- z_3g`K{y48Y8Ad+UG_^OSC(2rA!?HOiDA^y8AJ&#zrinl!jPt=ipsG`@r6tkWtg5UE zGN?RZhIwpv{{Zz=63eQ=8%cF4CP)Ctz;o@}wK_DN)y(Qj?BBPUUfp91q^jVNPO7nZ zYs3-TE~74`YLSS5I;#3HD~#8! z?dG21>tdAiNK+W#;NUl2bJyQBy?5f9C@-M2D{z730JGbWt_a5&8Q_)ttDNyw$+e2^ z=qnMHkcB`-bg$=C!C_ z?}};gnI~d^0QU9A*0n98@b0RRL3MWPHPkL`)y@@8?W#@>Es$_Cj-$BFCcSC>gQ>or z&L-NRhZr43dIE9y{d?Dgi-hlfhph=%!tq_SEgVca+P8M+DOP4{W<(=BH>yY zq)e#=h~2PY^VE8N6~j^UJ0sP@?{;@OCC&A=nnD_L2C7@E^kV_F4_Lp{47Z<@B$nUNmsY zZvsTonPdwhFp-&DAQ&SKTXs|f@%F9zMSOJDv}?}}-uzY8*H6?hFK%zFEpM6#XM48Y zaIBH-QyZ~n^0BZPBq2uk-FO}y#$)OGUUe0JUAKC9`SEV-IMZ+9G_4-SE*itV;?v1bSAzk{{VtS{CU&5J4=>r&NdwM$Ehe5fQW!LV0h2R@wC z@XE8t=Abw}wd-IpajR14oK@+{D^xrZry$c=L$1)LJ&+A$$mrl&y8d(&tY#=fT zXGM{U<1V?tA78CcYiDR}QZsCYRktdY7*py8YL-}%U^jN9jRa}2dIE7;Qv)4)-m@;IO8>yEwa3Y)a?hiTHCsWOrc8w&N)7{kU<24+tAeFWZ`4c!Or(cf;~N% z!F(TC21W@g2N~!1sR{)iS>z5m?^mqVni5+9i5bAi2CB;hzGehX$OK?^r3p7(BMA3ttFn+I&GQS;K|}q>-{;8Q}B- zuVGrT{{X9B_eCvoJsC5_Vk$@8k<4COt+awQVsg18`qN^Sp>W_1zLjTCws&QCVk9cy zJz$`?1gBYNr_M z&1WjSt?GHQS3;eX2 z&Ibf``c_X7WZP#n;F`6JolnEjMJj!a$%m9H3~t&Ff1vlPM^8u~+9r|k<+CGX^VY6R z>$tu+9)my1sa{;9OnkscJaBpc064EAra8g8Gf2=wbLIYhiKtejf0Q^PpF+b$|7QBS#A|%WXUL?7AF7_e(o{v_*VY_i9CO8 zuDGyGIw)a|c6jF6p@<}$k{E@^Adm^k8P96+j}v&R_f^-X8g$b=q*EBtg~!NnFjy!! zBa?&aj`io^>U&At(op4Em^!8X&Y`b8<@_c$l3-dn7dsb>0x&aykF9G%EKu2bzygS+ zkCO@H4D?ZwPq5_H9;H3y#Orl(q&F%FAm<1Abo?tb$9lc&J_>j(CSYDgTY`)M2+TqE z!8inZH>PXRr58GhE~h<7w(M5b{8auYyDtnXEnzM8X#hEJSg9vIp+Uw5GtOz2I-T~L zJa-mXB^n~eJ^>0?V4NN~AIMiZpzBEj3p? zzvEuYrlF!*9PQm2@avaTUp>X_o0{VSSvnKb8TR0D&{g3qMn5!2y8y{-@sF)@@yi^@ zB#K34JsD0xs4o8i*CGhXEDi{Xm>xTjFg>zsu8LC7t=Dwc{@Dka9`{V#Q!RSVP@_n(HeHNBgq*?xRxQ&gRpMOfB zUYsDKscJEj*!6LHX?1S5(QQ~=1F6XXDFEl@>Fdp5>b@<7qY&waSfvgNG>EvyI(PQ0 zyG!Vy(=B1R)B_{NqBvxb0gyT<^#uKB00Kw@C#kNO&7^Yju3}9`#CKQevwKI4!GcI| z;PeE2D=SjEx@h;SZ`$RvB$xn_GR2Ru&*4$ca|9RZr<;HzAmIuhm<;#mI)0T`TGcIJ zfvla0X_iRTj9?H-fV9gQWF j%_WK|sstF}a(49~XFlef6z?tS0RDBKGjp*m>VN;)f;|o6 literal 0 HcmV?d00001 diff --git a/modules/xphoto/tutorials/oil_painting_effect.markdown b/modules/xphoto/tutorials/oil_painting_effect.markdown new file mode 100644 index 000000000..f7c4f95c3 --- /dev/null +++ b/modules/xphoto/tutorials/oil_painting_effect.markdown @@ -0,0 +1,23 @@ +Oil painting effect {#tutorial_xphoto_oil_painting_effect} +=================================================== + +Introduction +------------ +Image is converted in a color space default color space COLOR_BGR2GRAY. +For every pixel in the image a program calculated a histogram (first plane of color space) of the neighbouring of size 2*size+1. +and assigned the value of the most frequently occurring value. The result looks almost like an oil painting. Parameter 4 of oilPainting is used to decrease image dynamic and hence increase oil painting effect. + +Example +-------------------- + + + @code{.cpp} + Mat img; + Mat dst; + img = imread("opencv/samples/data/baboon.jpg"); + xphoto::oilPainting(img, dst, 10, 1, COLOR_BGR2Lab); + imshow("oil painting effect", dst); + @endcode + + Original ![](images/baboon.jpg) + Oil painting effect ![](images/baboon_oil_painting_effect.jpg) From d3d380635145ede7a2b4786d1f09c236f5e6d393 Mon Sep 17 00:00:00 2001 From: LaurentBerger Date: Tue, 11 Sep 2018 22:30:08 +0200 Subject: [PATCH 20/97] solves I1767 --- .../libmv_light/libmv/correspondence/nRobustViewMatching.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/modules/sfm/src/libmv_light/libmv/correspondence/nRobustViewMatching.h b/modules/sfm/src/libmv_light/libmv/correspondence/nRobustViewMatching.h index faddbc3ed..bea27d7fc 100644 --- a/modules/sfm/src/libmv_light/libmv/correspondence/nRobustViewMatching.h +++ b/modules/sfm/src/libmv_light/libmv/correspondence/nRobustViewMatching.h @@ -127,9 +127,9 @@ private : Matches m_tracks; /// Interface to detect Keypoint. - cv::Ptr m_pDetector; + std::shared_ptr m_pDetector; /// Interface to describe Keypoint. - cv::Ptr m_pDescriber; + std::shared_ptr m_pDescriber; }; } // using namespace correspondence From 82733fe56b13401519ace101dc4d724f0a83f535 Mon Sep 17 00:00:00 2001 From: Alexander Alekhin Date: Tue, 18 Sep 2018 16:37:20 +0000 Subject: [PATCH 21/97] cuda: move CUDA modules to opencv_contrib OpenCV 4.0+ --- modules/cudaarithm/CMakeLists.txt | 27 + .../cudaarithm/include/opencv2/cudaarithm.hpp | 878 ++++++ modules/cudaarithm/perf/perf_arithm.cpp | 254 ++ modules/cudaarithm/perf/perf_core.cpp | 323 ++ .../perf/perf_element_operations.cpp | 1501 +++++++++ modules/cudaarithm/perf/perf_main.cpp | 47 + modules/cudaarithm/perf/perf_precomp.hpp | 55 + modules/cudaarithm/perf/perf_reductions.cpp | 520 +++ modules/cudaarithm/src/arithm.cpp | 582 ++++ modules/cudaarithm/src/core.cpp | 135 + modules/cudaarithm/src/cuda/absdiff_mat.cu | 188 ++ modules/cudaarithm/src/cuda/absdiff_scalar.cu | 133 + modules/cudaarithm/src/cuda/add_mat.cu | 225 ++ modules/cudaarithm/src/cuda/add_scalar.cu | 180 ++ modules/cudaarithm/src/cuda/add_weighted.cu | 596 ++++ modules/cudaarithm/src/cuda/bitwise_mat.cu | 230 ++ modules/cudaarithm/src/cuda/bitwise_scalar.cu | 171 + modules/cudaarithm/src/cuda/cmp_mat.cu | 219 ++ modules/cudaarithm/src/cuda/cmp_scalar.cu | 225 ++ .../cudaarithm/src/cuda/copy_make_border.cu | 159 + modules/cudaarithm/src/cuda/countnonzero.cu | 113 + modules/cudaarithm/src/cuda/div_mat.cu | 242 ++ modules/cudaarithm/src/cuda/div_scalar.cu | 260 ++ modules/cudaarithm/src/cuda/integral.cu | 107 + modules/cudaarithm/src/cuda/lut.cu | 210 ++ modules/cudaarithm/src/cuda/math.cu | 341 ++ modules/cudaarithm/src/cuda/minmax.cu | 189 ++ modules/cudaarithm/src/cuda/minmax_mat.cu | 243 ++ modules/cudaarithm/src/cuda/minmaxloc.cu | 159 + modules/cudaarithm/src/cuda/mul_mat.cu | 224 ++ modules/cudaarithm/src/cuda/mul_scalar.cu | 182 ++ modules/cudaarithm/src/cuda/mul_spectrums.cu | 170 + modules/cudaarithm/src/cuda/norm.cu | 189 ++ modules/cudaarithm/src/cuda/normalize.cu | 294 ++ modules/cudaarithm/src/cuda/polar_cart.cu | 217 ++ modules/cudaarithm/src/cuda/reduce.cu | 301 ++ modules/cudaarithm/src/cuda/split_merge.cu | 250 ++ modules/cudaarithm/src/cuda/sub_mat.cu | 225 ++ modules/cudaarithm/src/cuda/sub_scalar.cu | 203 ++ modules/cudaarithm/src/cuda/sum.cu | 242 ++ modules/cudaarithm/src/cuda/threshold.cu | 153 + modules/cudaarithm/src/cuda/transpose.cu | 95 + modules/cudaarithm/src/element_operations.cpp | 505 +++ modules/cudaarithm/src/precomp.hpp | 63 + modules/cudaarithm/src/reductions.cpp | 219 ++ modules/cudaarithm/test/test_arithm.cpp | 433 +++ modules/cudaarithm/test/test_buffer_pool.cpp | 120 + modules/cudaarithm/test/test_core.cpp | 421 +++ .../test/test_element_operations.cpp | 2799 +++++++++++++++++ modules/cudaarithm/test/test_gpumat.cpp | 412 +++ modules/cudaarithm/test/test_main.cpp | 45 + modules/cudaarithm/test/test_opengl.cpp | 457 +++ modules/cudaarithm/test/test_precomp.hpp | 56 + modules/cudaarithm/test/test_reductions.cpp | 1121 +++++++ modules/cudaarithm/test/test_stream.cpp | 176 ++ modules/cudabgsegm/CMakeLists.txt | 9 + .../cudabgsegm/include/opencv2/cudabgsegm.hpp | 154 + modules/cudabgsegm/perf/perf_bgsegm.cpp | 392 +++ modules/cudabgsegm/perf/perf_main.cpp | 47 + modules/cudabgsegm/perf/perf_precomp.hpp | 55 + modules/cudabgsegm/src/cuda/mog.cu | 425 +++ modules/cudabgsegm/src/cuda/mog2.cu | 439 +++ modules/cudabgsegm/src/mog.cpp | 209 ++ modules/cudabgsegm/src/mog2.cpp | 253 ++ modules/cudabgsegm/src/precomp.hpp | 54 + modules/cudabgsegm/test/test_bgsegm.cpp | 171 + modules/cudabgsegm/test/test_main.cpp | 45 + modules/cudabgsegm/test/test_precomp.hpp | 54 + modules/cudacodec/CMakeLists.txt | 29 + .../cudacodec/include/opencv2/cudacodec.hpp | 342 ++ .../misc/python/pyopencv_cudacodec.hpp | 14 + modules/cudacodec/perf/perf_main.cpp | 47 + modules/cudacodec/perf/perf_precomp.hpp | 54 + modules/cudacodec/perf/perf_video.cpp | 148 + modules/cudacodec/src/cuda/nv12_to_rgb.cu | 207 ++ modules/cudacodec/src/cuda/rgb_to_yv12.cu | 167 + modules/cudacodec/src/cuvid_video_source.cpp | 114 + modules/cudacodec/src/cuvid_video_source.hpp | 90 + modules/cudacodec/src/ffmpeg_video_source.cpp | 139 + modules/cudacodec/src/ffmpeg_video_source.hpp | 71 + modules/cudacodec/src/frame_queue.cpp | 118 + modules/cudacodec/src/frame_queue.hpp | 102 + modules/cudacodec/src/precomp.hpp | 87 + modules/cudacodec/src/thread.cpp | 170 + modules/cudacodec/src/thread.hpp | 70 + modules/cudacodec/src/video_decoder.cpp | 116 + modules/cudacodec/src/video_decoder.hpp | 116 + modules/cudacodec/src/video_parser.cpp | 162 + modules/cudacodec/src/video_parser.hpp | 99 + modules/cudacodec/src/video_reader.cpp | 223 ++ modules/cudacodec/src/video_source.cpp | 121 + modules/cudacodec/src/video_source.hpp | 99 + modules/cudacodec/src/video_writer.cpp | 916 ++++++ modules/cudacodec/test/test_main.cpp | 45 + modules/cudacodec/test/test_precomp.hpp | 52 + modules/cudacodec/test/test_video.cpp | 128 + modules/cudafeatures2d/CMakeLists.txt | 9 + .../include/opencv2/cudafeatures2d.hpp | 490 +++ .../cudafeatures2d/perf/perf_features2d.cpp | 312 ++ modules/cudafeatures2d/perf/perf_main.cpp | 47 + modules/cudafeatures2d/perf/perf_precomp.hpp | 56 + .../src/brute_force_matcher.cpp | 1078 +++++++ .../cudafeatures2d/src/cuda/bf_knnmatch.cu | 1255 ++++++++ modules/cudafeatures2d/src/cuda/bf_match.cu | 774 +++++ .../src/cuda/bf_radius_match.cu | 463 +++ modules/cudafeatures2d/src/cuda/fast.cu | 377 +++ modules/cudafeatures2d/src/cuda/orb.cu | 446 +++ modules/cudafeatures2d/src/fast.cpp | 214 ++ .../cudafeatures2d/src/feature2d_async.cpp | 85 + modules/cudafeatures2d/src/orb.cpp | 930 ++++++ modules/cudafeatures2d/src/precomp.hpp | 57 + .../cudafeatures2d/test/test_features2d.cpp | 762 +++++ modules/cudafeatures2d/test/test_main.cpp | 45 + modules/cudafeatures2d/test/test_precomp.hpp | 53 + modules/cudafilters/CMakeLists.txt | 9 + .../include/opencv2/cudafilters.hpp | 331 ++ modules/cudafilters/perf/perf_filters.cpp | 417 +++ modules/cudafilters/perf/perf_main.cpp | 47 + modules/cudafilters/perf/perf_precomp.hpp | 55 + .../src/cuda/column_filter.16sc1.cu | 52 + .../src/cuda/column_filter.16sc3.cu | 52 + .../src/cuda/column_filter.16sc4.cu | 52 + .../src/cuda/column_filter.16uc1.cu | 52 + .../src/cuda/column_filter.16uc3.cu | 52 + .../src/cuda/column_filter.16uc4.cu | 52 + .../src/cuda/column_filter.32fc1.cu | 52 + .../src/cuda/column_filter.32fc3.cu | 52 + .../src/cuda/column_filter.32fc4.cu | 52 + .../src/cuda/column_filter.32sc1.cu | 52 + .../src/cuda/column_filter.32sc3.cu | 52 + .../src/cuda/column_filter.32sc4.cu | 52 + .../src/cuda/column_filter.8uc1.cu | 52 + .../src/cuda/column_filter.8uc3.cu | 52 + .../src/cuda/column_filter.8uc4.cu | 52 + .../cudafilters/src/cuda/column_filter.hpp | 365 +++ modules/cudafilters/src/cuda/filter2d.cu | 151 + modules/cudafilters/src/cuda/median_filter.cu | 343 ++ .../cudafilters/src/cuda/row_filter.16sc1.cu | 52 + .../cudafilters/src/cuda/row_filter.16sc3.cu | 52 + .../cudafilters/src/cuda/row_filter.16sc4.cu | 52 + .../cudafilters/src/cuda/row_filter.16uc1.cu | 52 + .../cudafilters/src/cuda/row_filter.16uc3.cu | 52 + .../cudafilters/src/cuda/row_filter.16uc4.cu | 52 + .../cudafilters/src/cuda/row_filter.32fc1.cu | 52 + .../cudafilters/src/cuda/row_filter.32fc3.cu | 52 + .../cudafilters/src/cuda/row_filter.32fc4.cu | 52 + .../cudafilters/src/cuda/row_filter.32sc1.cu | 52 + .../cudafilters/src/cuda/row_filter.32sc3.cu | 52 + .../cudafilters/src/cuda/row_filter.32sc4.cu | 52 + .../cudafilters/src/cuda/row_filter.8uc1.cu | 52 + .../cudafilters/src/cuda/row_filter.8uc3.cu | 52 + .../cudafilters/src/cuda/row_filter.8uc4.cu | 52 + modules/cudafilters/src/cuda/row_filter.hpp | 364 +++ modules/cudafilters/src/filtering.cpp | 1118 +++++++ modules/cudafilters/src/precomp.hpp | 54 + modules/cudafilters/test/test_filters.cpp | 708 +++++ modules/cudafilters/test/test_main.cpp | 45 + modules/cudafilters/test/test_precomp.hpp | 52 + modules/cudaimgproc/CMakeLists.txt | 9 + .../include/opencv2/cudaimgproc.hpp | 738 +++++ .../perf/perf_bilateral_filter.cpp | 93 + modules/cudaimgproc/perf/perf_blend.cpp | 88 + modules/cudaimgproc/perf/perf_canny.cpp | 88 + modules/cudaimgproc/perf/perf_color.cpp | 253 ++ modules/cudaimgproc/perf/perf_corners.cpp | 135 + modules/cudaimgproc/perf/perf_gftt.cpp | 86 + modules/cudaimgproc/perf/perf_histogram.cpp | 219 ++ modules/cudaimgproc/perf/perf_hough.cpp | 348 ++ modules/cudaimgproc/perf/perf_main.cpp | 47 + .../cudaimgproc/perf/perf_match_template.cpp | 135 + modules/cudaimgproc/perf/perf_mean_shift.cpp | 152 + modules/cudaimgproc/perf/perf_precomp.hpp | 55 + modules/cudaimgproc/src/bilateral_filter.cpp | 99 + modules/cudaimgproc/src/blend.cpp | 109 + modules/cudaimgproc/src/canny.cpp | 245 ++ modules/cudaimgproc/src/color.cpp | 2332 ++++++++++++++ modules/cudaimgproc/src/corners.cpp | 189 ++ .../cudaimgproc/src/cuda/bilateral_filter.cu | 199 ++ modules/cudaimgproc/src/cuda/blend.cu | 121 + .../cudaimgproc/src/cuda/build_point_list.cu | 138 + modules/cudaimgproc/src/cuda/canny.cu | 670 ++++ modules/cudaimgproc/src/cuda/clahe.cu | 186 ++ modules/cudaimgproc/src/cuda/color.cu | 297 ++ modules/cudaimgproc/src/cuda/corners.cu | 280 ++ modules/cudaimgproc/src/cuda/debayer.cu | 544 ++++ .../cudaimgproc/src/cuda/generalized_hough.cu | 824 +++++ modules/cudaimgproc/src/cuda/gftt.cu | 150 + modules/cudaimgproc/src/cuda/hist.cu | 299 ++ modules/cudaimgproc/src/cuda/hough_circles.cu | 260 ++ modules/cudaimgproc/src/cuda/hough_lines.cu | 212 ++ .../cudaimgproc/src/cuda/hough_segments.cu | 249 ++ .../cudaimgproc/src/cuda/match_template.cu | 916 ++++++ modules/cudaimgproc/src/cuda/mean_shift.cu | 182 ++ modules/cudaimgproc/src/cvt_color_internal.h | 275 ++ modules/cudaimgproc/src/generalized_hough.cpp | 885 ++++++ modules/cudaimgproc/src/gftt.cpp | 215 ++ modules/cudaimgproc/src/histogram.cpp | 584 ++++ modules/cudaimgproc/src/hough_circles.cpp | 318 ++ modules/cudaimgproc/src/hough_lines.cpp | 212 ++ modules/cudaimgproc/src/hough_segments.cpp | 187 ++ modules/cudaimgproc/src/match_template.cpp | 644 ++++ modules/cudaimgproc/src/mean_shift.cpp | 128 + modules/cudaimgproc/src/mssegmentation.cpp | 394 +++ modules/cudaimgproc/src/precomp.hpp | 65 + .../test/test_bilateral_filter.cpp | 98 + modules/cudaimgproc/test/test_blend.cpp | 126 + modules/cudaimgproc/test/test_canny.cpp | 160 + modules/cudaimgproc/test/test_color.cpp | 2513 +++++++++++++++ modules/cudaimgproc/test/test_corners.cpp | 151 + modules/cudaimgproc/test/test_gftt.cpp | 133 + modules/cudaimgproc/test/test_histogram.cpp | 277 ++ modules/cudaimgproc/test/test_hough.cpp | 261 ++ modules/cudaimgproc/test/test_main.cpp | 45 + .../cudaimgproc/test/test_match_template.cpp | 341 ++ modules/cudaimgproc/test/test_mean_shift.cpp | 176 ++ modules/cudaimgproc/test/test_precomp.hpp | 52 + modules/cudalegacy/CMakeLists.txt | 10 + .../cudalegacy/include/opencv2/cudalegacy.hpp | 290 ++ .../include/opencv2/cudalegacy/NCV.hpp | 1032 ++++++ .../opencv2/cudalegacy/NCVBroxOpticalFlow.hpp | 110 + .../cudalegacy/NCVHaarObjectDetection.hpp | 463 +++ .../include/opencv2/cudalegacy/NCVPyramid.hpp | 113 + .../opencv2/cudalegacy/NPP_staging.hpp | 906 ++++++ .../include/opencv2/cudalegacy/private.hpp | 96 + modules/cudalegacy/perf/perf_bgsegm.cpp | 236 ++ modules/cudalegacy/perf/perf_calib3d.cpp | 140 + modules/cudalegacy/perf/perf_labeling.cpp | 195 ++ modules/cudalegacy/perf/perf_main.cpp | 47 + modules/cudalegacy/perf/perf_precomp.hpp | 57 + modules/cudalegacy/src/NCV.cpp | 888 ++++++ modules/cudalegacy/src/bm.cpp | 204 ++ modules/cudalegacy/src/bm_fast.cpp | 90 + modules/cudalegacy/src/calib3d.cpp | 292 ++ modules/cudalegacy/src/cuda/NCV.cu | 180 ++ modules/cudalegacy/src/cuda/NCVAlg.hpp | 155 + .../cudalegacy/src/cuda/NCVBroxOpticalFlow.cu | 1164 +++++++ .../src/cuda/NCVColorConversion.hpp | 100 + .../src/cuda/NCVHaarObjectDetection.cu | 2542 +++++++++++++++ .../src/cuda/NCVPixelOperations.hpp | 351 +++ modules/cudalegacy/src/cuda/NCVPyramid.cu | 621 ++++ .../src/cuda/NCVRuntimeTemplates.hpp | 221 ++ modules/cudalegacy/src/cuda/NPP_staging.cu | 2616 +++++++++++++++ modules/cudalegacy/src/cuda/bm.cu | 169 + modules/cudalegacy/src/cuda/bm_fast.cu | 295 ++ modules/cudalegacy/src/cuda/calib3d.cu | 193 ++ modules/cudalegacy/src/cuda/ccomponetns.cu | 534 ++++ modules/cudalegacy/src/cuda/fgd.cu | 801 +++++ modules/cudalegacy/src/cuda/fgd.hpp | 189 ++ modules/cudalegacy/src/cuda/gmg.cu | 258 ++ modules/cudalegacy/src/cuda/needle_map.cu | 220 ++ modules/cudalegacy/src/fgd.cpp | 729 +++++ modules/cudalegacy/src/gmg.cpp | 277 ++ modules/cudalegacy/src/graphcuts.cpp | 283 ++ modules/cudalegacy/src/image_pyramid.cpp | 147 + modules/cudalegacy/src/interpolate_frames.cpp | 113 + modules/cudalegacy/src/needle_map.cpp | 100 + modules/cudalegacy/src/precomp.hpp | 85 + modules/cudalegacy/test/NCVAutoTestLister.hpp | 166 + modules/cudalegacy/test/NCVTest.hpp | 247 ++ .../cudalegacy/test/NCVTestSourceProvider.hpp | 193 ++ modules/cudalegacy/test/TestCompact.cpp | 159 + modules/cudalegacy/test/TestCompact.h | 73 + modules/cudalegacy/test/TestDrawRects.cpp | 194 ++ modules/cudalegacy/test/TestDrawRects.h | 76 + .../test/TestHaarCascadeApplication.cpp | 335 ++ .../test/TestHaarCascadeApplication.h | 73 + .../cudalegacy/test/TestHaarCascadeLoader.cpp | 153 + .../cudalegacy/test/TestHaarCascadeLoader.h | 66 + .../cudalegacy/test/TestHypothesesFilter.cpp | 206 ++ .../cudalegacy/test/TestHypothesesFilter.h | 76 + .../cudalegacy/test/TestHypothesesGrow.cpp | 164 + modules/cudalegacy/test/TestHypothesesGrow.h | 78 + modules/cudalegacy/test/TestIntegralImage.cpp | 215 ++ modules/cudalegacy/test/TestIntegralImage.h | 72 + .../test/TestIntegralImageSquared.cpp | 148 + .../test/TestIntegralImageSquared.h | 71 + modules/cudalegacy/test/TestRectStdDev.cpp | 209 ++ modules/cudalegacy/test/TestRectStdDev.h | 76 + modules/cudalegacy/test/TestResize.cpp | 190 ++ modules/cudalegacy/test/TestResize.h | 74 + modules/cudalegacy/test/TestTranspose.cpp | 177 ++ modules/cudalegacy/test/TestTranspose.h | 73 + modules/cudalegacy/test/main_nvidia.cpp | 459 +++ modules/cudalegacy/test/main_test_nvidia.h | 67 + modules/cudalegacy/test/test_calib3d.cpp | 193 ++ modules/cudalegacy/test/test_labeling.cpp | 200 ++ modules/cudalegacy/test/test_main.cpp | 130 + modules/cudalegacy/test/test_nvidia.cpp | 152 + modules/cudalegacy/test/test_precomp.hpp | 90 + modules/cudaobjdetect/CMakeLists.txt | 9 + .../include/opencv2/cudaobjdetect.hpp | 288 ++ modules/cudaobjdetect/perf/perf_main.cpp | 47 + modules/cudaobjdetect/perf/perf_objdetect.cpp | 173 + modules/cudaobjdetect/perf/perf_precomp.hpp | 53 + .../cudaobjdetect/src/cascadeclassifier.cpp | 861 +++++ modules/cudaobjdetect/src/cuda/hog.cu | 890 ++++++ modules/cudaobjdetect/src/cuda/lbp.cu | 303 ++ modules/cudaobjdetect/src/cuda/lbp.hpp | 112 + modules/cudaobjdetect/src/hog.cpp | 1754 +++++++++++ modules/cudaobjdetect/src/precomp.hpp | 62 + modules/cudaobjdetect/test/test_main.cpp | 45 + modules/cudaobjdetect/test/test_objdetect.cpp | 563 ++++ modules/cudaobjdetect/test/test_precomp.hpp | 55 + modules/cudaoptflow/CMakeLists.txt | 9 + .../include/opencv2/cudaoptflow.hpp | 349 ++ modules/cudaoptflow/perf/perf_main.cpp | 47 + modules/cudaoptflow/perf/perf_optflow.cpp | 329 ++ modules/cudaoptflow/perf/perf_precomp.hpp | 57 + modules/cudaoptflow/src/brox.cpp | 194 ++ modules/cudaoptflow/src/cuda/farneback.cu | 656 ++++ modules/cudaoptflow/src/cuda/pyrlk.cu | 1162 +++++++ modules/cudaoptflow/src/cuda/tvl1flow.cu | 372 +++ modules/cudaoptflow/src/farneback.cpp | 469 +++ modules/cudaoptflow/src/precomp.hpp | 62 + modules/cudaoptflow/src/pyrlk.cpp | 404 +++ modules/cudaoptflow/src/tvl1flow.cpp | 385 +++ modules/cudaoptflow/test/test_main.cpp | 45 + modules/cudaoptflow/test/test_optflow.cpp | 406 +++ modules/cudaoptflow/test/test_precomp.hpp | 54 + modules/cudastereo/CMakeLists.txt | 9 + .../cudastereo/include/opencv2/cudastereo.hpp | 333 ++ modules/cudastereo/perf/perf_main.cpp | 47 + modules/cudastereo/perf/perf_precomp.hpp | 55 + modules/cudastereo/perf/perf_stereo.cpp | 255 ++ .../src/cuda/disparity_bilateral_filter.cu | 205 ++ .../src/cuda/disparity_bilateral_filter.hpp | 8 + modules/cudastereo/src/cuda/stereobm.cu | 540 ++++ modules/cudastereo/src/cuda/stereobp.cu | 538 ++++ modules/cudastereo/src/cuda/stereocsbp.cu | 814 +++++ modules/cudastereo/src/cuda/stereocsbp.hpp | 29 + modules/cudastereo/src/cuda/util.cu | 290 ++ .../src/disparity_bilateral_filter.cpp | 197 ++ modules/cudastereo/src/precomp.hpp | 53 + modules/cudastereo/src/stereobm.cpp | 185 ++ modules/cudastereo/src/stereobp.cpp | 380 +++ modules/cudastereo/src/stereocsbp.cpp | 357 +++ modules/cudastereo/src/util.cpp | 125 + modules/cudastereo/test/test_main.cpp | 45 + modules/cudastereo/test/test_precomp.hpp | 53 + modules/cudastereo/test/test_stereo.cpp | 214 ++ modules/cudawarping/CMakeLists.txt | 9 + .../include/opencv2/cudawarping.hpp | 216 ++ modules/cudawarping/perf/perf_main.cpp | 47 + modules/cudawarping/perf/perf_precomp.hpp | 55 + modules/cudawarping/perf/perf_warping.cpp | 436 +++ modules/cudawarping/src/cuda/pyr_down.cu | 228 ++ modules/cudawarping/src/cuda/pyr_up.cu | 196 ++ modules/cudawarping/src/cuda/remap.cu | 274 ++ modules/cudawarping/src/cuda/resize.cu | 482 +++ modules/cudawarping/src/cuda/warp.cu | 389 +++ modules/cudawarping/src/precomp.hpp | 50 + modules/cudawarping/src/pyramids.cpp | 134 + modules/cudawarping/src/remap.cpp | 104 + modules/cudawarping/src/resize.cpp | 108 + modules/cudawarping/src/warp.cpp | 534 ++++ modules/cudawarping/test/interpolation.hpp | 131 + modules/cudawarping/test/test_main.cpp | 45 + modules/cudawarping/test/test_precomp.hpp | 54 + modules/cudawarping/test/test_pyramids.cpp | 131 + modules/cudawarping/test/test_remap.cpp | 182 ++ modules/cudawarping/test/test_resize.cpp | 211 ++ modules/cudawarping/test/test_warp_affine.cpp | 282 ++ .../test/test_warp_perspective.cpp | 285 ++ modules/cudev/CMakeLists.txt | 25 + modules/cudev/include/opencv2/cudev.hpp | 119 + .../include/opencv2/cudev/block/block.hpp | 133 + .../opencv2/cudev/block/detail/reduce.hpp | 392 +++ .../cudev/block/detail/reduce_key_val.hpp | 394 +++ .../opencv2/cudev/block/dynamic_smem.hpp | 91 + .../include/opencv2/cudev/block/reduce.hpp | 133 + .../include/opencv2/cudev/block/scan.hpp | 106 + .../opencv2/cudev/block/vec_distance.hpp | 189 ++ .../cudev/include/opencv2/cudev/common.hpp | 94 + .../opencv2/cudev/expr/binary_func.hpp | 80 + .../include/opencv2/cudev/expr/binary_op.hpp | 240 ++ .../include/opencv2/cudev/expr/color.hpp | 287 ++ .../include/opencv2/cudev/expr/deriv.hpp | 126 + .../cudev/include/opencv2/cudev/expr/expr.hpp | 97 + .../opencv2/cudev/expr/per_element_func.hpp | 137 + .../include/opencv2/cudev/expr/reduction.hpp | 264 ++ .../include/opencv2/cudev/expr/unary_func.hpp | 103 + .../include/opencv2/cudev/expr/unary_op.hpp | 99 + .../include/opencv2/cudev/expr/warping.hpp | 176 ++ .../opencv2/cudev/functional/color_cvt.hpp | 479 +++ .../cudev/functional/detail/color_cvt.hpp | 1284 ++++++++ .../opencv2/cudev/functional/functional.hpp | 904 ++++++ .../cudev/functional/tuple_adapter.hpp | 103 + .../cudev/include/opencv2/cudev/grid/copy.hpp | 457 +++ .../opencv2/cudev/grid/detail/copy.hpp | 132 + .../opencv2/cudev/grid/detail/histogram.hpp | 111 + .../opencv2/cudev/grid/detail/integral.hpp | 627 ++++ .../opencv2/cudev/grid/detail/minmaxloc.hpp | 177 ++ .../opencv2/cudev/grid/detail/pyr_down.hpp | 201 ++ .../opencv2/cudev/grid/detail/pyr_up.hpp | 172 + .../opencv2/cudev/grid/detail/reduce.hpp | 466 +++ .../cudev/grid/detail/reduce_to_column.hpp | 146 + .../cudev/grid/detail/reduce_to_row.hpp | 118 + .../opencv2/cudev/grid/detail/split_merge.hpp | 282 ++ .../opencv2/cudev/grid/detail/transform.hpp | 417 +++ .../opencv2/cudev/grid/detail/transpose.hpp | 127 + .../include/opencv2/cudev/grid/histogram.hpp | 124 + .../include/opencv2/cudev/grid/integral.hpp | 74 + .../include/opencv2/cudev/grid/pyramids.hpp | 93 + .../include/opencv2/cudev/grid/reduce.hpp | 380 +++ .../opencv2/cudev/grid/reduce_to_vec.hpp | 235 ++ .../opencv2/cudev/grid/split_merge.hpp | 589 ++++ .../include/opencv2/cudev/grid/transform.hpp | 546 ++++ .../include/opencv2/cudev/grid/transpose.hpp | 108 + .../include/opencv2/cudev/ptr2d/constant.hpp | 98 + .../include/opencv2/cudev/ptr2d/deriv.hpp | 398 +++ .../opencv2/cudev/ptr2d/detail/gpumat.hpp | 361 +++ .../opencv2/cudev/ptr2d/extrapolation.hpp | 224 ++ .../include/opencv2/cudev/ptr2d/glob.hpp | 129 + .../include/opencv2/cudev/ptr2d/gpumat.hpp | 166 + .../opencv2/cudev/ptr2d/interpolation.hpp | 390 +++ .../cudev/include/opencv2/cudev/ptr2d/lut.hpp | 105 + .../include/opencv2/cudev/ptr2d/mask.hpp | 108 + .../include/opencv2/cudev/ptr2d/remap.hpp | 159 + .../include/opencv2/cudev/ptr2d/resize.hpp | 108 + .../include/opencv2/cudev/ptr2d/texture.hpp | 258 ++ .../include/opencv2/cudev/ptr2d/traits.hpp | 106 + .../include/opencv2/cudev/ptr2d/transform.hpp | 156 + .../include/opencv2/cudev/ptr2d/warping.hpp | 157 + .../cudev/include/opencv2/cudev/ptr2d/zip.hpp | 178 ++ .../include/opencv2/cudev/util/atomic.hpp | 202 ++ .../opencv2/cudev/util/detail/tuple.hpp | 175 ++ .../opencv2/cudev/util/detail/type_traits.hpp | 238 ++ .../include/opencv2/cudev/util/limits.hpp | 129 + .../opencv2/cudev/util/saturate_cast.hpp | 300 ++ .../opencv2/cudev/util/simd_functions.hpp | 918 ++++++ .../include/opencv2/cudev/util/tuple.hpp | 85 + .../opencv2/cudev/util/type_traits.hpp | 174 + .../include/opencv2/cudev/util/vec_math.hpp | 941 ++++++ .../include/opencv2/cudev/util/vec_traits.hpp | 325 ++ .../opencv2/cudev/warp/detail/reduce.hpp | 222 ++ .../cudev/warp/detail/reduce_key_val.hpp | 239 ++ .../include/opencv2/cudev/warp/reduce.hpp | 211 ++ .../cudev/include/opencv2/cudev/warp/scan.hpp | 104 + .../include/opencv2/cudev/warp/shuffle.hpp | 439 +++ .../cudev/include/opencv2/cudev/warp/warp.hpp | 127 + modules/cudev/src/stub.cpp | 11 + modules/cudev/test/CMakeLists.txt | 43 + modules/cudev/test/test_arithm_func.cu | 168 + modules/cudev/test/test_arithm_op.cu | 395 +++ modules/cudev/test/test_bitwize_op.cu | 146 + modules/cudev/test/test_cmp_op.cu | 151 + modules/cudev/test/test_color_cvt.cu | 180 ++ modules/cudev/test/test_cvt.cu | 150 + modules/cudev/test/test_deriv.cu | 109 + modules/cudev/test/test_integral.cu | 103 + modules/cudev/test/test_lut.cu | 82 + modules/cudev/test/test_main.cpp | 46 + modules/cudev/test/test_precomp.hpp | 55 + modules/cudev/test/test_pyramids.cu | 81 + modules/cudev/test/test_reduction.cu | 312 ++ modules/cudev/test/test_split_merge.cu | 180 ++ modules/cudev/test/test_warp.cu | 256 ++ modules/cudev/test/transpose.cu | 81 + 458 files changed, 120709 insertions(+) create mode 100644 modules/cudaarithm/CMakeLists.txt create mode 100644 modules/cudaarithm/include/opencv2/cudaarithm.hpp create mode 100644 modules/cudaarithm/perf/perf_arithm.cpp create mode 100644 modules/cudaarithm/perf/perf_core.cpp create mode 100644 modules/cudaarithm/perf/perf_element_operations.cpp create mode 100644 modules/cudaarithm/perf/perf_main.cpp create mode 100644 modules/cudaarithm/perf/perf_precomp.hpp create mode 100644 modules/cudaarithm/perf/perf_reductions.cpp create mode 100644 modules/cudaarithm/src/arithm.cpp create mode 100644 modules/cudaarithm/src/core.cpp create mode 100644 modules/cudaarithm/src/cuda/absdiff_mat.cu create mode 100644 modules/cudaarithm/src/cuda/absdiff_scalar.cu create mode 100644 modules/cudaarithm/src/cuda/add_mat.cu create mode 100644 modules/cudaarithm/src/cuda/add_scalar.cu create mode 100644 modules/cudaarithm/src/cuda/add_weighted.cu create mode 100644 modules/cudaarithm/src/cuda/bitwise_mat.cu create mode 100644 modules/cudaarithm/src/cuda/bitwise_scalar.cu create mode 100644 modules/cudaarithm/src/cuda/cmp_mat.cu create mode 100644 modules/cudaarithm/src/cuda/cmp_scalar.cu create mode 100644 modules/cudaarithm/src/cuda/copy_make_border.cu create mode 100644 modules/cudaarithm/src/cuda/countnonzero.cu create mode 100644 modules/cudaarithm/src/cuda/div_mat.cu create mode 100644 modules/cudaarithm/src/cuda/div_scalar.cu create mode 100644 modules/cudaarithm/src/cuda/integral.cu create mode 100644 modules/cudaarithm/src/cuda/lut.cu create mode 100644 modules/cudaarithm/src/cuda/math.cu create mode 100644 modules/cudaarithm/src/cuda/minmax.cu create mode 100644 modules/cudaarithm/src/cuda/minmax_mat.cu create mode 100644 modules/cudaarithm/src/cuda/minmaxloc.cu create mode 100644 modules/cudaarithm/src/cuda/mul_mat.cu create mode 100644 modules/cudaarithm/src/cuda/mul_scalar.cu create mode 100644 modules/cudaarithm/src/cuda/mul_spectrums.cu create mode 100644 modules/cudaarithm/src/cuda/norm.cu create mode 100644 modules/cudaarithm/src/cuda/normalize.cu create mode 100644 modules/cudaarithm/src/cuda/polar_cart.cu create mode 100644 modules/cudaarithm/src/cuda/reduce.cu create mode 100644 modules/cudaarithm/src/cuda/split_merge.cu create mode 100644 modules/cudaarithm/src/cuda/sub_mat.cu create mode 100644 modules/cudaarithm/src/cuda/sub_scalar.cu create mode 100644 modules/cudaarithm/src/cuda/sum.cu create mode 100644 modules/cudaarithm/src/cuda/threshold.cu create mode 100644 modules/cudaarithm/src/cuda/transpose.cu create mode 100644 modules/cudaarithm/src/element_operations.cpp create mode 100644 modules/cudaarithm/src/precomp.hpp create mode 100644 modules/cudaarithm/src/reductions.cpp create mode 100644 modules/cudaarithm/test/test_arithm.cpp create mode 100644 modules/cudaarithm/test/test_buffer_pool.cpp create mode 100644 modules/cudaarithm/test/test_core.cpp create mode 100644 modules/cudaarithm/test/test_element_operations.cpp create mode 100644 modules/cudaarithm/test/test_gpumat.cpp create mode 100644 modules/cudaarithm/test/test_main.cpp create mode 100644 modules/cudaarithm/test/test_opengl.cpp create mode 100644 modules/cudaarithm/test/test_precomp.hpp create mode 100644 modules/cudaarithm/test/test_reductions.cpp create mode 100644 modules/cudaarithm/test/test_stream.cpp create mode 100644 modules/cudabgsegm/CMakeLists.txt create mode 100644 modules/cudabgsegm/include/opencv2/cudabgsegm.hpp create mode 100644 modules/cudabgsegm/perf/perf_bgsegm.cpp create mode 100644 modules/cudabgsegm/perf/perf_main.cpp create mode 100644 modules/cudabgsegm/perf/perf_precomp.hpp create mode 100644 modules/cudabgsegm/src/cuda/mog.cu create mode 100644 modules/cudabgsegm/src/cuda/mog2.cu create mode 100644 modules/cudabgsegm/src/mog.cpp create mode 100644 modules/cudabgsegm/src/mog2.cpp create mode 100644 modules/cudabgsegm/src/precomp.hpp create mode 100644 modules/cudabgsegm/test/test_bgsegm.cpp create mode 100644 modules/cudabgsegm/test/test_main.cpp create mode 100644 modules/cudabgsegm/test/test_precomp.hpp create mode 100644 modules/cudacodec/CMakeLists.txt create mode 100644 modules/cudacodec/include/opencv2/cudacodec.hpp create mode 100644 modules/cudacodec/misc/python/pyopencv_cudacodec.hpp create mode 100644 modules/cudacodec/perf/perf_main.cpp create mode 100644 modules/cudacodec/perf/perf_precomp.hpp create mode 100644 modules/cudacodec/perf/perf_video.cpp create mode 100644 modules/cudacodec/src/cuda/nv12_to_rgb.cu create mode 100644 modules/cudacodec/src/cuda/rgb_to_yv12.cu create mode 100644 modules/cudacodec/src/cuvid_video_source.cpp create mode 100644 modules/cudacodec/src/cuvid_video_source.hpp create mode 100644 modules/cudacodec/src/ffmpeg_video_source.cpp create mode 100644 modules/cudacodec/src/ffmpeg_video_source.hpp create mode 100644 modules/cudacodec/src/frame_queue.cpp create mode 100644 modules/cudacodec/src/frame_queue.hpp create mode 100644 modules/cudacodec/src/precomp.hpp create mode 100644 modules/cudacodec/src/thread.cpp create mode 100644 modules/cudacodec/src/thread.hpp create mode 100644 modules/cudacodec/src/video_decoder.cpp create mode 100644 modules/cudacodec/src/video_decoder.hpp create mode 100644 modules/cudacodec/src/video_parser.cpp create mode 100644 modules/cudacodec/src/video_parser.hpp create mode 100644 modules/cudacodec/src/video_reader.cpp create mode 100644 modules/cudacodec/src/video_source.cpp create mode 100644 modules/cudacodec/src/video_source.hpp create mode 100644 modules/cudacodec/src/video_writer.cpp create mode 100644 modules/cudacodec/test/test_main.cpp create mode 100644 modules/cudacodec/test/test_precomp.hpp create mode 100644 modules/cudacodec/test/test_video.cpp create mode 100644 modules/cudafeatures2d/CMakeLists.txt create mode 100644 modules/cudafeatures2d/include/opencv2/cudafeatures2d.hpp create mode 100644 modules/cudafeatures2d/perf/perf_features2d.cpp create mode 100644 modules/cudafeatures2d/perf/perf_main.cpp create mode 100644 modules/cudafeatures2d/perf/perf_precomp.hpp create mode 100644 modules/cudafeatures2d/src/brute_force_matcher.cpp create mode 100644 modules/cudafeatures2d/src/cuda/bf_knnmatch.cu create mode 100644 modules/cudafeatures2d/src/cuda/bf_match.cu create mode 100644 modules/cudafeatures2d/src/cuda/bf_radius_match.cu create mode 100644 modules/cudafeatures2d/src/cuda/fast.cu create mode 100644 modules/cudafeatures2d/src/cuda/orb.cu create mode 100644 modules/cudafeatures2d/src/fast.cpp create mode 100644 modules/cudafeatures2d/src/feature2d_async.cpp create mode 100644 modules/cudafeatures2d/src/orb.cpp create mode 100644 modules/cudafeatures2d/src/precomp.hpp create mode 100644 modules/cudafeatures2d/test/test_features2d.cpp create mode 100644 modules/cudafeatures2d/test/test_main.cpp create mode 100644 modules/cudafeatures2d/test/test_precomp.hpp create mode 100644 modules/cudafilters/CMakeLists.txt create mode 100644 modules/cudafilters/include/opencv2/cudafilters.hpp create mode 100644 modules/cudafilters/perf/perf_filters.cpp create mode 100644 modules/cudafilters/perf/perf_main.cpp create mode 100644 modules/cudafilters/perf/perf_precomp.hpp create mode 100644 modules/cudafilters/src/cuda/column_filter.16sc1.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.16sc3.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.16sc4.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.16uc1.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.16uc3.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.16uc4.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.32fc1.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.32fc3.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.32fc4.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.32sc1.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.32sc3.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.32sc4.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.8uc1.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.8uc3.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.8uc4.cu create mode 100644 modules/cudafilters/src/cuda/column_filter.hpp create mode 100644 modules/cudafilters/src/cuda/filter2d.cu create mode 100644 modules/cudafilters/src/cuda/median_filter.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.16sc1.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.16sc3.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.16sc4.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.16uc1.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.16uc3.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.16uc4.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.32fc1.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.32fc3.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.32fc4.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.32sc1.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.32sc3.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.32sc4.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.8uc1.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.8uc3.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.8uc4.cu create mode 100644 modules/cudafilters/src/cuda/row_filter.hpp create mode 100644 modules/cudafilters/src/filtering.cpp create mode 100644 modules/cudafilters/src/precomp.hpp create mode 100644 modules/cudafilters/test/test_filters.cpp create mode 100644 modules/cudafilters/test/test_main.cpp create mode 100644 modules/cudafilters/test/test_precomp.hpp create mode 100644 modules/cudaimgproc/CMakeLists.txt create mode 100644 modules/cudaimgproc/include/opencv2/cudaimgproc.hpp create mode 100644 modules/cudaimgproc/perf/perf_bilateral_filter.cpp create mode 100644 modules/cudaimgproc/perf/perf_blend.cpp create mode 100644 modules/cudaimgproc/perf/perf_canny.cpp create mode 100644 modules/cudaimgproc/perf/perf_color.cpp create mode 100644 modules/cudaimgproc/perf/perf_corners.cpp create mode 100644 modules/cudaimgproc/perf/perf_gftt.cpp create mode 100644 modules/cudaimgproc/perf/perf_histogram.cpp create mode 100644 modules/cudaimgproc/perf/perf_hough.cpp create mode 100644 modules/cudaimgproc/perf/perf_main.cpp create mode 100644 modules/cudaimgproc/perf/perf_match_template.cpp create mode 100644 modules/cudaimgproc/perf/perf_mean_shift.cpp create mode 100644 modules/cudaimgproc/perf/perf_precomp.hpp create mode 100644 modules/cudaimgproc/src/bilateral_filter.cpp create mode 100644 modules/cudaimgproc/src/blend.cpp create mode 100644 modules/cudaimgproc/src/canny.cpp create mode 100644 modules/cudaimgproc/src/color.cpp create mode 100644 modules/cudaimgproc/src/corners.cpp create mode 100644 modules/cudaimgproc/src/cuda/bilateral_filter.cu create mode 100644 modules/cudaimgproc/src/cuda/blend.cu create mode 100644 modules/cudaimgproc/src/cuda/build_point_list.cu create mode 100644 modules/cudaimgproc/src/cuda/canny.cu create mode 100644 modules/cudaimgproc/src/cuda/clahe.cu create mode 100644 modules/cudaimgproc/src/cuda/color.cu create mode 100644 modules/cudaimgproc/src/cuda/corners.cu create mode 100644 modules/cudaimgproc/src/cuda/debayer.cu create mode 100644 modules/cudaimgproc/src/cuda/generalized_hough.cu create mode 100644 modules/cudaimgproc/src/cuda/gftt.cu create mode 100644 modules/cudaimgproc/src/cuda/hist.cu create mode 100644 modules/cudaimgproc/src/cuda/hough_circles.cu create mode 100644 modules/cudaimgproc/src/cuda/hough_lines.cu create mode 100644 modules/cudaimgproc/src/cuda/hough_segments.cu create mode 100644 modules/cudaimgproc/src/cuda/match_template.cu create mode 100644 modules/cudaimgproc/src/cuda/mean_shift.cu create mode 100644 modules/cudaimgproc/src/cvt_color_internal.h create mode 100644 modules/cudaimgproc/src/generalized_hough.cpp create mode 100644 modules/cudaimgproc/src/gftt.cpp create mode 100644 modules/cudaimgproc/src/histogram.cpp create mode 100644 modules/cudaimgproc/src/hough_circles.cpp create mode 100644 modules/cudaimgproc/src/hough_lines.cpp create mode 100644 modules/cudaimgproc/src/hough_segments.cpp create mode 100644 modules/cudaimgproc/src/match_template.cpp create mode 100644 modules/cudaimgproc/src/mean_shift.cpp create mode 100644 modules/cudaimgproc/src/mssegmentation.cpp create mode 100644 modules/cudaimgproc/src/precomp.hpp create mode 100644 modules/cudaimgproc/test/test_bilateral_filter.cpp create mode 100644 modules/cudaimgproc/test/test_blend.cpp create mode 100644 modules/cudaimgproc/test/test_canny.cpp create mode 100644 modules/cudaimgproc/test/test_color.cpp create mode 100644 modules/cudaimgproc/test/test_corners.cpp create mode 100644 modules/cudaimgproc/test/test_gftt.cpp create mode 100644 modules/cudaimgproc/test/test_histogram.cpp create mode 100644 modules/cudaimgproc/test/test_hough.cpp create mode 100644 modules/cudaimgproc/test/test_main.cpp create mode 100644 modules/cudaimgproc/test/test_match_template.cpp create mode 100644 modules/cudaimgproc/test/test_mean_shift.cpp create mode 100644 modules/cudaimgproc/test/test_precomp.hpp create mode 100644 modules/cudalegacy/CMakeLists.txt create mode 100644 modules/cudalegacy/include/opencv2/cudalegacy.hpp create mode 100644 modules/cudalegacy/include/opencv2/cudalegacy/NCV.hpp create mode 100644 modules/cudalegacy/include/opencv2/cudalegacy/NCVBroxOpticalFlow.hpp create mode 100644 modules/cudalegacy/include/opencv2/cudalegacy/NCVHaarObjectDetection.hpp create mode 100644 modules/cudalegacy/include/opencv2/cudalegacy/NCVPyramid.hpp create mode 100644 modules/cudalegacy/include/opencv2/cudalegacy/NPP_staging.hpp create mode 100644 modules/cudalegacy/include/opencv2/cudalegacy/private.hpp create mode 100644 modules/cudalegacy/perf/perf_bgsegm.cpp create mode 100644 modules/cudalegacy/perf/perf_calib3d.cpp create mode 100644 modules/cudalegacy/perf/perf_labeling.cpp create mode 100644 modules/cudalegacy/perf/perf_main.cpp create mode 100644 modules/cudalegacy/perf/perf_precomp.hpp create mode 100644 modules/cudalegacy/src/NCV.cpp create mode 100644 modules/cudalegacy/src/bm.cpp create mode 100644 modules/cudalegacy/src/bm_fast.cpp create mode 100644 modules/cudalegacy/src/calib3d.cpp create mode 100644 modules/cudalegacy/src/cuda/NCV.cu create mode 100644 modules/cudalegacy/src/cuda/NCVAlg.hpp create mode 100644 modules/cudalegacy/src/cuda/NCVBroxOpticalFlow.cu create mode 100644 modules/cudalegacy/src/cuda/NCVColorConversion.hpp create mode 100644 modules/cudalegacy/src/cuda/NCVHaarObjectDetection.cu create mode 100644 modules/cudalegacy/src/cuda/NCVPixelOperations.hpp create mode 100644 modules/cudalegacy/src/cuda/NCVPyramid.cu create mode 100644 modules/cudalegacy/src/cuda/NCVRuntimeTemplates.hpp create mode 100644 modules/cudalegacy/src/cuda/NPP_staging.cu create mode 100644 modules/cudalegacy/src/cuda/bm.cu create mode 100644 modules/cudalegacy/src/cuda/bm_fast.cu create mode 100644 modules/cudalegacy/src/cuda/calib3d.cu create mode 100644 modules/cudalegacy/src/cuda/ccomponetns.cu create mode 100644 modules/cudalegacy/src/cuda/fgd.cu create mode 100644 modules/cudalegacy/src/cuda/fgd.hpp create mode 100644 modules/cudalegacy/src/cuda/gmg.cu create mode 100644 modules/cudalegacy/src/cuda/needle_map.cu create mode 100644 modules/cudalegacy/src/fgd.cpp create mode 100644 modules/cudalegacy/src/gmg.cpp create mode 100644 modules/cudalegacy/src/graphcuts.cpp create mode 100644 modules/cudalegacy/src/image_pyramid.cpp create mode 100644 modules/cudalegacy/src/interpolate_frames.cpp create mode 100644 modules/cudalegacy/src/needle_map.cpp create mode 100644 modules/cudalegacy/src/precomp.hpp create mode 100644 modules/cudalegacy/test/NCVAutoTestLister.hpp create mode 100644 modules/cudalegacy/test/NCVTest.hpp create mode 100644 modules/cudalegacy/test/NCVTestSourceProvider.hpp create mode 100644 modules/cudalegacy/test/TestCompact.cpp create mode 100644 modules/cudalegacy/test/TestCompact.h create mode 100644 modules/cudalegacy/test/TestDrawRects.cpp create mode 100644 modules/cudalegacy/test/TestDrawRects.h create mode 100644 modules/cudalegacy/test/TestHaarCascadeApplication.cpp create mode 100644 modules/cudalegacy/test/TestHaarCascadeApplication.h create mode 100644 modules/cudalegacy/test/TestHaarCascadeLoader.cpp create mode 100644 modules/cudalegacy/test/TestHaarCascadeLoader.h create mode 100644 modules/cudalegacy/test/TestHypothesesFilter.cpp create mode 100644 modules/cudalegacy/test/TestHypothesesFilter.h create mode 100644 modules/cudalegacy/test/TestHypothesesGrow.cpp create mode 100644 modules/cudalegacy/test/TestHypothesesGrow.h create mode 100644 modules/cudalegacy/test/TestIntegralImage.cpp create mode 100644 modules/cudalegacy/test/TestIntegralImage.h create mode 100644 modules/cudalegacy/test/TestIntegralImageSquared.cpp create mode 100644 modules/cudalegacy/test/TestIntegralImageSquared.h create mode 100644 modules/cudalegacy/test/TestRectStdDev.cpp create mode 100644 modules/cudalegacy/test/TestRectStdDev.h create mode 100644 modules/cudalegacy/test/TestResize.cpp create mode 100644 modules/cudalegacy/test/TestResize.h create mode 100644 modules/cudalegacy/test/TestTranspose.cpp create mode 100644 modules/cudalegacy/test/TestTranspose.h create mode 100644 modules/cudalegacy/test/main_nvidia.cpp create mode 100644 modules/cudalegacy/test/main_test_nvidia.h create mode 100644 modules/cudalegacy/test/test_calib3d.cpp create mode 100644 modules/cudalegacy/test/test_labeling.cpp create mode 100644 modules/cudalegacy/test/test_main.cpp create mode 100644 modules/cudalegacy/test/test_nvidia.cpp create mode 100644 modules/cudalegacy/test/test_precomp.hpp create mode 100644 modules/cudaobjdetect/CMakeLists.txt create mode 100644 modules/cudaobjdetect/include/opencv2/cudaobjdetect.hpp create mode 100644 modules/cudaobjdetect/perf/perf_main.cpp create mode 100644 modules/cudaobjdetect/perf/perf_objdetect.cpp create mode 100644 modules/cudaobjdetect/perf/perf_precomp.hpp create mode 100644 modules/cudaobjdetect/src/cascadeclassifier.cpp create mode 100644 modules/cudaobjdetect/src/cuda/hog.cu create mode 100644 modules/cudaobjdetect/src/cuda/lbp.cu create mode 100644 modules/cudaobjdetect/src/cuda/lbp.hpp create mode 100644 modules/cudaobjdetect/src/hog.cpp create mode 100644 modules/cudaobjdetect/src/precomp.hpp create mode 100644 modules/cudaobjdetect/test/test_main.cpp create mode 100644 modules/cudaobjdetect/test/test_objdetect.cpp create mode 100644 modules/cudaobjdetect/test/test_precomp.hpp create mode 100644 modules/cudaoptflow/CMakeLists.txt create mode 100644 modules/cudaoptflow/include/opencv2/cudaoptflow.hpp create mode 100644 modules/cudaoptflow/perf/perf_main.cpp create mode 100644 modules/cudaoptflow/perf/perf_optflow.cpp create mode 100644 modules/cudaoptflow/perf/perf_precomp.hpp create mode 100644 modules/cudaoptflow/src/brox.cpp create mode 100644 modules/cudaoptflow/src/cuda/farneback.cu create mode 100644 modules/cudaoptflow/src/cuda/pyrlk.cu create mode 100644 modules/cudaoptflow/src/cuda/tvl1flow.cu create mode 100644 modules/cudaoptflow/src/farneback.cpp create mode 100644 modules/cudaoptflow/src/precomp.hpp create mode 100644 modules/cudaoptflow/src/pyrlk.cpp create mode 100644 modules/cudaoptflow/src/tvl1flow.cpp create mode 100644 modules/cudaoptflow/test/test_main.cpp create mode 100644 modules/cudaoptflow/test/test_optflow.cpp create mode 100644 modules/cudaoptflow/test/test_precomp.hpp create mode 100644 modules/cudastereo/CMakeLists.txt create mode 100644 modules/cudastereo/include/opencv2/cudastereo.hpp create mode 100644 modules/cudastereo/perf/perf_main.cpp create mode 100644 modules/cudastereo/perf/perf_precomp.hpp create mode 100644 modules/cudastereo/perf/perf_stereo.cpp create mode 100644 modules/cudastereo/src/cuda/disparity_bilateral_filter.cu create mode 100644 modules/cudastereo/src/cuda/disparity_bilateral_filter.hpp create mode 100644 modules/cudastereo/src/cuda/stereobm.cu create mode 100644 modules/cudastereo/src/cuda/stereobp.cu create mode 100644 modules/cudastereo/src/cuda/stereocsbp.cu create mode 100644 modules/cudastereo/src/cuda/stereocsbp.hpp create mode 100644 modules/cudastereo/src/cuda/util.cu create mode 100644 modules/cudastereo/src/disparity_bilateral_filter.cpp create mode 100644 modules/cudastereo/src/precomp.hpp create mode 100644 modules/cudastereo/src/stereobm.cpp create mode 100644 modules/cudastereo/src/stereobp.cpp create mode 100644 modules/cudastereo/src/stereocsbp.cpp create mode 100644 modules/cudastereo/src/util.cpp create mode 100644 modules/cudastereo/test/test_main.cpp create mode 100644 modules/cudastereo/test/test_precomp.hpp create mode 100644 modules/cudastereo/test/test_stereo.cpp create mode 100644 modules/cudawarping/CMakeLists.txt create mode 100644 modules/cudawarping/include/opencv2/cudawarping.hpp create mode 100644 modules/cudawarping/perf/perf_main.cpp create mode 100644 modules/cudawarping/perf/perf_precomp.hpp create mode 100644 modules/cudawarping/perf/perf_warping.cpp create mode 100644 modules/cudawarping/src/cuda/pyr_down.cu create mode 100644 modules/cudawarping/src/cuda/pyr_up.cu create mode 100644 modules/cudawarping/src/cuda/remap.cu create mode 100644 modules/cudawarping/src/cuda/resize.cu create mode 100644 modules/cudawarping/src/cuda/warp.cu create mode 100644 modules/cudawarping/src/precomp.hpp create mode 100644 modules/cudawarping/src/pyramids.cpp create mode 100644 modules/cudawarping/src/remap.cpp create mode 100644 modules/cudawarping/src/resize.cpp create mode 100644 modules/cudawarping/src/warp.cpp create mode 100644 modules/cudawarping/test/interpolation.hpp create mode 100644 modules/cudawarping/test/test_main.cpp create mode 100644 modules/cudawarping/test/test_precomp.hpp create mode 100644 modules/cudawarping/test/test_pyramids.cpp create mode 100644 modules/cudawarping/test/test_remap.cpp create mode 100644 modules/cudawarping/test/test_resize.cpp create mode 100644 modules/cudawarping/test/test_warp_affine.cpp create mode 100644 modules/cudawarping/test/test_warp_perspective.cpp create mode 100644 modules/cudev/CMakeLists.txt create mode 100644 modules/cudev/include/opencv2/cudev.hpp create mode 100644 modules/cudev/include/opencv2/cudev/block/block.hpp create mode 100644 modules/cudev/include/opencv2/cudev/block/detail/reduce.hpp create mode 100644 modules/cudev/include/opencv2/cudev/block/detail/reduce_key_val.hpp create mode 100644 modules/cudev/include/opencv2/cudev/block/dynamic_smem.hpp create mode 100644 modules/cudev/include/opencv2/cudev/block/reduce.hpp create mode 100644 modules/cudev/include/opencv2/cudev/block/scan.hpp create mode 100644 modules/cudev/include/opencv2/cudev/block/vec_distance.hpp create mode 100644 modules/cudev/include/opencv2/cudev/common.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/binary_func.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/binary_op.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/color.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/deriv.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/expr.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/per_element_func.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/reduction.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/unary_func.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/unary_op.hpp create mode 100644 modules/cudev/include/opencv2/cudev/expr/warping.hpp create mode 100644 modules/cudev/include/opencv2/cudev/functional/color_cvt.hpp create mode 100644 modules/cudev/include/opencv2/cudev/functional/detail/color_cvt.hpp create mode 100644 modules/cudev/include/opencv2/cudev/functional/functional.hpp create mode 100644 modules/cudev/include/opencv2/cudev/functional/tuple_adapter.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/copy.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/copy.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/histogram.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/integral.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/minmaxloc.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/pyr_down.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/pyr_up.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/reduce.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/reduce_to_column.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/reduce_to_row.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/split_merge.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/transform.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/detail/transpose.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/histogram.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/integral.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/pyramids.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/reduce.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/reduce_to_vec.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/split_merge.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/transform.hpp create mode 100644 modules/cudev/include/opencv2/cudev/grid/transpose.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/constant.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/deriv.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/detail/gpumat.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/extrapolation.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/glob.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/gpumat.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/interpolation.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/lut.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/mask.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/remap.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/resize.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/texture.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/traits.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/transform.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/warping.hpp create mode 100644 modules/cudev/include/opencv2/cudev/ptr2d/zip.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/atomic.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/detail/tuple.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/detail/type_traits.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/limits.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/saturate_cast.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/simd_functions.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/tuple.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/type_traits.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/vec_math.hpp create mode 100644 modules/cudev/include/opencv2/cudev/util/vec_traits.hpp create mode 100644 modules/cudev/include/opencv2/cudev/warp/detail/reduce.hpp create mode 100644 modules/cudev/include/opencv2/cudev/warp/detail/reduce_key_val.hpp create mode 100644 modules/cudev/include/opencv2/cudev/warp/reduce.hpp create mode 100644 modules/cudev/include/opencv2/cudev/warp/scan.hpp create mode 100644 modules/cudev/include/opencv2/cudev/warp/shuffle.hpp create mode 100644 modules/cudev/include/opencv2/cudev/warp/warp.hpp create mode 100644 modules/cudev/src/stub.cpp create mode 100644 modules/cudev/test/CMakeLists.txt create mode 100644 modules/cudev/test/test_arithm_func.cu create mode 100644 modules/cudev/test/test_arithm_op.cu create mode 100644 modules/cudev/test/test_bitwize_op.cu create mode 100644 modules/cudev/test/test_cmp_op.cu create mode 100644 modules/cudev/test/test_color_cvt.cu create mode 100644 modules/cudev/test/test_cvt.cu create mode 100644 modules/cudev/test/test_deriv.cu create mode 100644 modules/cudev/test/test_integral.cu create mode 100644 modules/cudev/test/test_lut.cu create mode 100644 modules/cudev/test/test_main.cpp create mode 100644 modules/cudev/test/test_precomp.hpp create mode 100644 modules/cudev/test/test_pyramids.cu create mode 100644 modules/cudev/test/test_reduction.cu create mode 100644 modules/cudev/test/test_split_merge.cu create mode 100644 modules/cudev/test/test_warp.cu create mode 100644 modules/cudev/test/transpose.cu diff --git a/modules/cudaarithm/CMakeLists.txt b/modules/cudaarithm/CMakeLists.txt new file mode 100644 index 000000000..d552bb4eb --- /dev/null +++ b/modules/cudaarithm/CMakeLists.txt @@ -0,0 +1,27 @@ +if(IOS OR WINRT OR (NOT HAVE_CUDA AND NOT BUILD_CUDA_STUBS)) + ocv_module_disable(cudaarithm) +endif() + +set(the_description "CUDA-accelerated Operations on Matrices") + +ocv_warnings_disable(CMAKE_CXX_FLAGS /wd4127 /wd4324 /wd4512 -Wundef -Wmissing-declarations -Wshadow) + +ocv_add_module(cudaarithm opencv_core OPTIONAL opencv_cudev WRAP python) + +ocv_module_include_directories() +ocv_glob_module_sources() + +set(extra_libs "") + +if(HAVE_CUBLAS) + list(APPEND extra_libs ${CUDA_cublas_LIBRARY}) +endif() + +if(HAVE_CUFFT) + list(APPEND extra_libs ${CUDA_cufft_LIBRARY}) +endif() + +ocv_create_module(${extra_libs}) + +ocv_add_accuracy_tests(DEPENDS_ON opencv_imgproc) +ocv_add_perf_tests(DEPENDS_ON opencv_imgproc) diff --git a/modules/cudaarithm/include/opencv2/cudaarithm.hpp b/modules/cudaarithm/include/opencv2/cudaarithm.hpp new file mode 100644 index 000000000..c357f77b4 --- /dev/null +++ b/modules/cudaarithm/include/opencv2/cudaarithm.hpp @@ -0,0 +1,878 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#ifndef OPENCV_CUDAARITHM_HPP +#define OPENCV_CUDAARITHM_HPP + +#ifndef __cplusplus +# error cudaarithm.hpp header must be compiled as C++ +#endif + +#include "opencv2/core/cuda.hpp" + +/** + @addtogroup cuda + @{ + @defgroup cudaarithm Operations on Matrices + @{ + @defgroup cudaarithm_core Core Operations on Matrices + @defgroup cudaarithm_elem Per-element Operations + @defgroup cudaarithm_reduce Matrix Reductions + @defgroup cudaarithm_arithm Arithm Operations on Matrices + @} + @} + */ + +namespace cv { namespace cuda { + +//! @addtogroup cudaarithm +//! @{ + +//! @addtogroup cudaarithm_elem +//! @{ + +/** @brief Computes a matrix-matrix or matrix-scalar sum. + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. Matrix should have the same size and type as src1 . +@param dst Destination matrix that has the same size and number of channels as the input array(s). +The depth is defined by dtype or src1 depth. +@param mask Optional operation mask, 8-bit single channel array, that specifies elements of the +destination array to be changed. The mask can be used only with single channel images. +@param dtype Optional depth of the output array. +@param stream Stream for the asynchronous version. + +@sa add + */ +CV_EXPORTS_W void add(InputArray src1, InputArray src2, OutputArray dst, InputArray mask = noArray(), int dtype = -1, Stream& stream = Stream::Null()); + +/** @brief Computes a matrix-matrix or matrix-scalar difference. + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. Matrix should have the same size and type as src1 . +@param dst Destination matrix that has the same size and number of channels as the input array(s). +The depth is defined by dtype or src1 depth. +@param mask Optional operation mask, 8-bit single channel array, that specifies elements of the +destination array to be changed. The mask can be used only with single channel images. +@param dtype Optional depth of the output array. +@param stream Stream for the asynchronous version. + +@sa subtract + */ +CV_EXPORTS_W void subtract(InputArray src1, InputArray src2, OutputArray dst, InputArray mask = noArray(), int dtype = -1, Stream& stream = Stream::Null()); + +/** @brief Computes a matrix-matrix or matrix-scalar per-element product. + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and number of channels as the input array(s). +The depth is defined by dtype or src1 depth. +@param scale Optional scale factor. +@param dtype Optional depth of the output array. +@param stream Stream for the asynchronous version. + +@sa multiply + */ +CV_EXPORTS_W void multiply(InputArray src1, InputArray src2, OutputArray dst, double scale = 1, int dtype = -1, Stream& stream = Stream::Null()); + +/** @brief Computes a matrix-matrix or matrix-scalar division. + +@param src1 First source matrix or a scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and number of channels as the input array(s). +The depth is defined by dtype or src1 depth. +@param scale Optional scale factor. +@param dtype Optional depth of the output array. +@param stream Stream for the asynchronous version. + +This function, in contrast to divide, uses a round-down rounding mode. + +@sa divide + */ +CV_EXPORTS_W void divide(InputArray src1, InputArray src2, OutputArray dst, double scale = 1, int dtype = -1, Stream& stream = Stream::Null()); + +/** @brief Computes per-element absolute difference of two matrices (or of a matrix and scalar). + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and type as the input array(s). +@param stream Stream for the asynchronous version. + +@sa absdiff + */ +CV_EXPORTS_W void absdiff(InputArray src1, InputArray src2, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes an absolute value of each matrix element. + +@param src Source matrix. +@param dst Destination matrix with the same size and type as src . +@param stream Stream for the asynchronous version. + +@sa abs + */ +CV_EXPORTS_W void abs(InputArray src, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes a square value of each matrix element. + +@param src Source matrix. +@param dst Destination matrix with the same size and type as src . +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void sqr(InputArray src, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes a square root of each matrix element. + +@param src Source matrix. +@param dst Destination matrix with the same size and type as src . +@param stream Stream for the asynchronous version. + +@sa sqrt + */ +CV_EXPORTS_W void sqrt(InputArray src, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes an exponent of each matrix element. + +@param src Source matrix. +@param dst Destination matrix with the same size and type as src . +@param stream Stream for the asynchronous version. + +@sa exp + */ +CV_EXPORTS_W void exp(InputArray src, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes a natural logarithm of absolute value of each matrix element. + +@param src Source matrix. +@param dst Destination matrix with the same size and type as src . +@param stream Stream for the asynchronous version. + +@sa log + */ +CV_EXPORTS_W void log(InputArray src, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Raises every matrix element to a power. + +@param src Source matrix. +@param power Exponent of power. +@param dst Destination matrix with the same size and type as src . +@param stream Stream for the asynchronous version. + +The function pow raises every element of the input matrix to power : + +\f[\texttt{dst} (I) = \fork{\texttt{src}(I)^power}{if \texttt{power} is integer}{|\texttt{src}(I)|^power}{otherwise}\f] + +@sa pow + */ +CV_EXPORTS_W void pow(InputArray src, double power, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Compares elements of two matrices (or of a matrix and scalar). + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and type as the input array(s). +@param cmpop Flag specifying the relation between the elements to be checked: +- **CMP_EQ:** a(.) == b(.) +- **CMP_GT:** a(.) \> b(.) +- **CMP_GE:** a(.) \>= b(.) +- **CMP_LT:** a(.) \< b(.) +- **CMP_LE:** a(.) \<= b(.) +- **CMP_NE:** a(.) != b(.) +@param stream Stream for the asynchronous version. + +@sa compare + */ +CV_EXPORTS_W void compare(InputArray src1, InputArray src2, OutputArray dst, int cmpop, Stream& stream = Stream::Null()); + +/** @brief Performs a per-element bitwise inversion. + +@param src Source matrix. +@param dst Destination matrix with the same size and type as src . +@param mask Optional operation mask, 8-bit single channel array, that specifies elements of the +destination array to be changed. The mask can be used only with single channel images. +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void bitwise_not(InputArray src, OutputArray dst, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Performs a per-element bitwise disjunction of two matrices (or of matrix and scalar). + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and type as the input array(s). +@param mask Optional operation mask, 8-bit single channel array, that specifies elements of the +destination array to be changed. The mask can be used only with single channel images. +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void bitwise_or(InputArray src1, InputArray src2, OutputArray dst, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Performs a per-element bitwise conjunction of two matrices (or of matrix and scalar). + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and type as the input array(s). +@param mask Optional operation mask, 8-bit single channel array, that specifies elements of the +destination array to be changed. The mask can be used only with single channel images. +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void bitwise_and(InputArray src1, InputArray src2, OutputArray dst, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Performs a per-element bitwise exclusive or operation of two matrices (or of matrix and scalar). + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and type as the input array(s). +@param mask Optional operation mask, 8-bit single channel array, that specifies elements of the +destination array to be changed. The mask can be used only with single channel images. +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void bitwise_xor(InputArray src1, InputArray src2, OutputArray dst, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Performs pixel by pixel right shift of an image by a constant value. + +@param src Source matrix. Supports 1, 3 and 4 channels images with integers elements. +@param val Constant values, one per channel. +@param dst Destination matrix with the same size and type as src . +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS void rshift(InputArray src, Scalar_ val, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Performs pixel by pixel right left of an image by a constant value. + +@param src Source matrix. Supports 1, 3 and 4 channels images with CV_8U , CV_16U or CV_32S +depth. +@param val Constant values, one per channel. +@param dst Destination matrix with the same size and type as src . +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS void lshift(InputArray src, Scalar_ val, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes the per-element minimum of two matrices (or a matrix and a scalar). + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and type as the input array(s). +@param stream Stream for the asynchronous version. + +@sa min + */ +CV_EXPORTS_W void min(InputArray src1, InputArray src2, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes the per-element maximum of two matrices (or a matrix and a scalar). + +@param src1 First source matrix or scalar. +@param src2 Second source matrix or scalar. +@param dst Destination matrix that has the same size and type as the input array(s). +@param stream Stream for the asynchronous version. + +@sa max + */ +CV_EXPORTS_W void max(InputArray src1, InputArray src2, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes the weighted sum of two arrays. + +@param src1 First source array. +@param alpha Weight for the first array elements. +@param src2 Second source array of the same size and channel number as src1 . +@param beta Weight for the second array elements. +@param dst Destination array that has the same size and number of channels as the input arrays. +@param gamma Scalar added to each sum. +@param dtype Optional depth of the destination array. When both input arrays have the same depth, +dtype can be set to -1, which will be equivalent to src1.depth(). +@param stream Stream for the asynchronous version. + +The function addWeighted calculates the weighted sum of two arrays as follows: + +\f[\texttt{dst} (I)= \texttt{saturate} ( \texttt{src1} (I)* \texttt{alpha} + \texttt{src2} (I)* \texttt{beta} + \texttt{gamma} )\f] + +where I is a multi-dimensional index of array elements. In case of multi-channel arrays, each +channel is processed independently. + +@sa addWeighted + */ +CV_EXPORTS_W void addWeighted(InputArray src1, double alpha, InputArray src2, double beta, double gamma, OutputArray dst, + int dtype = -1, Stream& stream = Stream::Null()); + +//! adds scaled array to another one (dst = alpha*src1 + src2) +static inline void scaleAdd(InputArray src1, double alpha, InputArray src2, OutputArray dst, Stream& stream = Stream::Null()) +{ + addWeighted(src1, alpha, src2, 1.0, 0.0, dst, -1, stream); +} + +/** @brief Applies a fixed-level threshold to each array element. + +@param src Source array (single-channel). +@param dst Destination array with the same size and type as src . +@param thresh Threshold value. +@param maxval Maximum value to use with THRESH_BINARY and THRESH_BINARY_INV threshold types. +@param type Threshold type. For details, see threshold . The THRESH_OTSU and THRESH_TRIANGLE +threshold types are not supported. +@param stream Stream for the asynchronous version. + +@sa threshold + */ +CV_EXPORTS_W double threshold(InputArray src, OutputArray dst, double thresh, double maxval, int type, Stream& stream = Stream::Null()); + +/** @brief Computes magnitudes of complex matrix elements. + +@param xy Source complex matrix in the interleaved format ( CV_32FC2 ). +@param magnitude Destination matrix of float magnitudes ( CV_32FC1 ). +@param stream Stream for the asynchronous version. + +@sa magnitude + */ +CV_EXPORTS_W void magnitude(InputArray xy, OutputArray magnitude, Stream& stream = Stream::Null()); + +/** @brief Computes squared magnitudes of complex matrix elements. + +@param xy Source complex matrix in the interleaved format ( CV_32FC2 ). +@param magnitude Destination matrix of float magnitude squares ( CV_32FC1 ). +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void magnitudeSqr(InputArray xy, OutputArray magnitude, Stream& stream = Stream::Null()); + +/** @overload + computes magnitude of each (x(i), y(i)) vector + supports only floating-point source +@param x Source matrix containing real components ( CV_32FC1 ). +@param y Source matrix containing imaginary components ( CV_32FC1 ). +@param magnitude Destination matrix of float magnitudes ( CV_32FC1 ). +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void magnitude(InputArray x, InputArray y, OutputArray magnitude, Stream& stream = Stream::Null()); + +/** @overload + computes squared magnitude of each (x(i), y(i)) vector + supports only floating-point source +@param x Source matrix containing real components ( CV_32FC1 ). +@param y Source matrix containing imaginary components ( CV_32FC1 ). +@param magnitude Destination matrix of float magnitude squares ( CV_32FC1 ). +@param stream Stream for the asynchronous version. +*/ +CV_EXPORTS_W void magnitudeSqr(InputArray x, InputArray y, OutputArray magnitude, Stream& stream = Stream::Null()); + +/** @brief Computes polar angles of complex matrix elements. + +@param x Source matrix containing real components ( CV_32FC1 ). +@param y Source matrix containing imaginary components ( CV_32FC1 ). +@param angle Destination matrix of angles ( CV_32FC1 ). +@param angleInDegrees Flag for angles that must be evaluated in degrees. +@param stream Stream for the asynchronous version. + +@sa phase + */ +CV_EXPORTS_W void phase(InputArray x, InputArray y, OutputArray angle, bool angleInDegrees = false, Stream& stream = Stream::Null()); + +/** @brief Converts Cartesian coordinates into polar. + +@param x Source matrix containing real components ( CV_32FC1 ). +@param y Source matrix containing imaginary components ( CV_32FC1 ). +@param magnitude Destination matrix of float magnitudes ( CV_32FC1 ). +@param angle Destination matrix of angles ( CV_32FC1 ). +@param angleInDegrees Flag for angles that must be evaluated in degrees. +@param stream Stream for the asynchronous version. + +@sa cartToPolar + */ +CV_EXPORTS_W void cartToPolar(InputArray x, InputArray y, OutputArray magnitude, OutputArray angle, bool angleInDegrees = false, Stream& stream = Stream::Null()); + +/** @brief Converts polar coordinates into Cartesian. + +@param magnitude Source matrix containing magnitudes ( CV_32FC1 ). +@param angle Source matrix containing angles ( CV_32FC1 ). +@param x Destination matrix of real components ( CV_32FC1 ). +@param y Destination matrix of imaginary components ( CV_32FC1 ). +@param angleInDegrees Flag that indicates angles in degrees. +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void polarToCart(InputArray magnitude, InputArray angle, OutputArray x, OutputArray y, bool angleInDegrees = false, Stream& stream = Stream::Null()); + +//! @} cudaarithm_elem + +//! @addtogroup cudaarithm_core +//! @{ + +/** @brief Makes a multi-channel matrix out of several single-channel matrices. + +@param src Array/vector of source matrices. +@param n Number of source matrices. +@param dst Destination matrix. +@param stream Stream for the asynchronous version. + +@sa merge + */ +CV_EXPORTS_W void merge(const GpuMat* src, size_t n, OutputArray dst, Stream& stream = Stream::Null()); +/** @overload */ +CV_EXPORTS_W void merge(const std::vector& src, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Copies each plane of a multi-channel matrix into an array. + +@param src Source matrix. +@param dst Destination array/vector of single-channel matrices. +@param stream Stream for the asynchronous version. + +@sa split + */ +CV_EXPORTS_W void split(InputArray src, GpuMat* dst, Stream& stream = Stream::Null()); +/** @overload */ +CV_EXPORTS_W void split(InputArray src, std::vector& dst, Stream& stream = Stream::Null()); + +/** @brief Transposes a matrix. + +@param src1 Source matrix. 1-, 4-, 8-byte element sizes are supported for now. +@param dst Destination matrix. +@param stream Stream for the asynchronous version. + +@sa transpose + */ +CV_EXPORTS_W void transpose(InputArray src1, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Flips a 2D matrix around vertical, horizontal, or both axes. + +@param src Source matrix. Supports 1, 3 and 4 channels images with CV_8U, CV_16U, CV_32S or +CV_32F depth. +@param dst Destination matrix. +@param flipCode Flip mode for the source: +- 0 Flips around x-axis. +- \> 0 Flips around y-axis. +- \< 0 Flips around both axes. +@param stream Stream for the asynchronous version. + +@sa flip + */ +CV_EXPORTS_W void flip(InputArray src, OutputArray dst, int flipCode, Stream& stream = Stream::Null()); + +/** @brief Base class for transform using lookup table. + */ +class CV_EXPORTS_W LookUpTable : public Algorithm +{ +public: + /** @brief Transforms the source matrix into the destination matrix using the given look-up table: + dst(I) = lut(src(I)) . + + @param src Source matrix. CV_8UC1 and CV_8UC3 matrices are supported for now. + @param dst Destination matrix. + @param stream Stream for the asynchronous version. + */ + CV_WRAP virtual void transform(InputArray src, OutputArray dst, Stream& stream = Stream::Null()) = 0; +}; + +/** @brief Creates implementation for cuda::LookUpTable . + +@param lut Look-up table of 256 elements. It is a continuous CV_8U matrix. + */ +CV_EXPORTS_W Ptr createLookUpTable(InputArray lut); + +/** @brief Forms a border around an image. + +@param src Source image. CV_8UC1 , CV_8UC4 , CV_32SC1 , and CV_32FC1 types are supported. +@param dst Destination image with the same type as src. The size is +Size(src.cols+left+right, src.rows+top+bottom) . +@param top +@param bottom +@param left +@param right Number of pixels in each direction from the source image rectangle to extrapolate. +For example: top=1, bottom=1, left=1, right=1 mean that 1 pixel-wide border needs to be built. +@param borderType Border type. See borderInterpolate for details. BORDER_REFLECT101 , +BORDER_REPLICATE , BORDER_CONSTANT , BORDER_REFLECT and BORDER_WRAP are supported for now. +@param value Border value. +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void copyMakeBorder(InputArray src, OutputArray dst, int top, int bottom, int left, int right, int borderType, + Scalar value = Scalar(), Stream& stream = Stream::Null()); + +//! @} cudaarithm_core + +//! @addtogroup cudaarithm_reduce +//! @{ + +/** @brief Returns the norm of a matrix (or difference of two matrices). + +@param src1 Source matrix. Any matrices except 64F are supported. +@param normType Norm type. NORM_L1 , NORM_L2 , and NORM_INF are supported for now. +@param mask optional operation mask; it must have the same size as src1 and CV_8UC1 type. + +@sa norm + */ +CV_EXPORTS_W double norm(InputArray src1, int normType, InputArray mask = noArray()); +/** @overload */ +CV_EXPORTS_W void calcNorm(InputArray src, OutputArray dst, int normType, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Returns the difference of two matrices. + +@param src1 Source matrix. Any matrices except 64F are supported. +@param src2 Second source matrix (if any) with the same size and type as src1. +@param normType Norm type. NORM_L1 , NORM_L2 , and NORM_INF are supported for now. + +@sa norm + */ +CV_EXPORTS_W double norm(InputArray src1, InputArray src2, int normType=NORM_L2); +/** @overload */ +CV_EXPORTS_W void calcNormDiff(InputArray src1, InputArray src2, OutputArray dst, int normType=NORM_L2, Stream& stream = Stream::Null()); + +/** @brief Returns the sum of matrix elements. + +@param src Source image of any depth except for CV_64F . +@param mask optional operation mask; it must have the same size as src1 and CV_8UC1 type. + +@sa sum + */ +CV_EXPORTS_W Scalar sum(InputArray src, InputArray mask = noArray()); +/** @overload */ +CV_EXPORTS_W void calcSum(InputArray src, OutputArray dst, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Returns the sum of absolute values for matrix elements. + +@param src Source image of any depth except for CV_64F . +@param mask optional operation mask; it must have the same size as src1 and CV_8UC1 type. + */ +CV_EXPORTS_W Scalar absSum(InputArray src, InputArray mask = noArray()); +/** @overload */ +CV_EXPORTS_W void calcAbsSum(InputArray src, OutputArray dst, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Returns the squared sum of matrix elements. + +@param src Source image of any depth except for CV_64F . +@param mask optional operation mask; it must have the same size as src1 and CV_8UC1 type. + */ +CV_EXPORTS_W Scalar sqrSum(InputArray src, InputArray mask = noArray()); +/** @overload */ +CV_EXPORTS_W void calcSqrSum(InputArray src, OutputArray dst, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Finds global minimum and maximum matrix elements and returns their values. + +@param src Single-channel source image. +@param minVal Pointer to the returned minimum value. Use NULL if not required. +@param maxVal Pointer to the returned maximum value. Use NULL if not required. +@param mask Optional mask to select a sub-matrix. + +The function does not work with CV_64F images on GPUs with the compute capability \< 1.3. + +@sa minMaxLoc + */ +CV_EXPORTS_W void minMax(InputArray src, double* minVal, double* maxVal, InputArray mask = noArray()); +/** @overload */ +CV_EXPORTS_W void findMinMax(InputArray src, OutputArray dst, InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Finds global minimum and maximum matrix elements and returns their values with locations. + +@param src Single-channel source image. +@param minVal Pointer to the returned minimum value. Use NULL if not required. +@param maxVal Pointer to the returned maximum value. Use NULL if not required. +@param minLoc Pointer to the returned minimum location. Use NULL if not required. +@param maxLoc Pointer to the returned maximum location. Use NULL if not required. +@param mask Optional mask to select a sub-matrix. + +The function does not work with CV_64F images on GPU with the compute capability \< 1.3. + +@sa minMaxLoc + */ +CV_EXPORTS_W void minMaxLoc(InputArray src, double* minVal, double* maxVal, Point* minLoc, Point* maxLoc, + InputArray mask = noArray()); +/** @overload */ +CV_EXPORTS_W void findMinMaxLoc(InputArray src, OutputArray minMaxVals, OutputArray loc, + InputArray mask = noArray(), Stream& stream = Stream::Null()); + +/** @brief Counts non-zero matrix elements. + +@param src Single-channel source image. + +The function does not work with CV_64F images on GPUs with the compute capability \< 1.3. + +@sa countNonZero + */ +CV_EXPORTS_W int countNonZero(InputArray src); +/** @overload */ +CV_EXPORTS_W void countNonZero(InputArray src, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Reduces a matrix to a vector. + +@param mtx Source 2D matrix. +@param vec Destination vector. Its size and type is defined by dim and dtype parameters. +@param dim Dimension index along which the matrix is reduced. 0 means that the matrix is reduced +to a single row. 1 means that the matrix is reduced to a single column. +@param reduceOp Reduction operation that could be one of the following: +- **CV_REDUCE_SUM** The output is the sum of all rows/columns of the matrix. +- **CV_REDUCE_AVG** The output is the mean vector of all rows/columns of the matrix. +- **CV_REDUCE_MAX** The output is the maximum (column/row-wise) of all rows/columns of the +matrix. +- **CV_REDUCE_MIN** The output is the minimum (column/row-wise) of all rows/columns of the +matrix. +@param dtype When it is negative, the destination vector will have the same type as the source +matrix. Otherwise, its type will be CV_MAKE_TYPE(CV_MAT_DEPTH(dtype), mtx.channels()) . +@param stream Stream for the asynchronous version. + +The function reduce reduces the matrix to a vector by treating the matrix rows/columns as a set of +1D vectors and performing the specified operation on the vectors until a single row/column is +obtained. For example, the function can be used to compute horizontal and vertical projections of a +raster image. In case of CV_REDUCE_SUM and CV_REDUCE_AVG , the output may have a larger element +bit-depth to preserve accuracy. And multi-channel arrays are also supported in these two reduction +modes. + +@sa reduce + */ +CV_EXPORTS_W void reduce(InputArray mtx, OutputArray vec, int dim, int reduceOp, int dtype = -1, Stream& stream = Stream::Null()); + +/** @brief Computes a mean value and a standard deviation of matrix elements. + +@param mtx Source matrix. CV_8UC1 matrices are supported for now. +@param mean Mean value. +@param stddev Standard deviation value. + +@sa meanStdDev + */ +CV_EXPORTS_W void meanStdDev(InputArray mtx, Scalar& mean, Scalar& stddev); +/** @overload */ +CV_EXPORTS_W void meanStdDev(InputArray mtx, OutputArray dst, Stream& stream = Stream::Null()); + +/** @brief Computes a standard deviation of integral images. + +@param src Source image. Only the CV_32SC1 type is supported. +@param sqr Squared source image. Only the CV_32FC1 type is supported. +@param dst Destination image with the same type and size as src . +@param rect Rectangular window. +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void rectStdDev(InputArray src, InputArray sqr, OutputArray dst, Rect rect, Stream& stream = Stream::Null()); + +/** @brief Normalizes the norm or value range of an array. + +@param src Input array. +@param dst Output array of the same size as src . +@param alpha Norm value to normalize to or the lower range boundary in case of the range +normalization. +@param beta Upper range boundary in case of the range normalization; it is not used for the norm +normalization. +@param norm_type Normalization type ( NORM_MINMAX , NORM_L2 , NORM_L1 or NORM_INF ). +@param dtype When negative, the output array has the same type as src; otherwise, it has the same +number of channels as src and the depth =CV_MAT_DEPTH(dtype). +@param mask Optional operation mask. +@param stream Stream for the asynchronous version. + +@sa normalize + */ +CV_EXPORTS_W void normalize(InputArray src, OutputArray dst, double alpha, double beta, + int norm_type, int dtype, InputArray mask = noArray(), + Stream& stream = Stream::Null()); + +/** @brief Computes an integral image. + +@param src Source image. Only CV_8UC1 images are supported for now. +@param sum Integral image containing 32-bit unsigned integer values packed into CV_32SC1 . +@param stream Stream for the asynchronous version. + +@sa integral + */ +CV_EXPORTS_W void integral(InputArray src, OutputArray sum, Stream& stream = Stream::Null()); + +/** @brief Computes a squared integral image. + +@param src Source image. Only CV_8UC1 images are supported for now. +@param sqsum Squared integral image containing 64-bit unsigned integer values packed into +CV_64FC1 . +@param stream Stream for the asynchronous version. + */ +CV_EXPORTS_W void sqrIntegral(InputArray src, OutputArray sqsum, Stream& stream = Stream::Null()); + +//! @} cudaarithm_reduce + +//! @addtogroup cudaarithm_arithm +//! @{ + +/** @brief Performs generalized matrix multiplication. + +@param src1 First multiplied input matrix that should have CV_32FC1 , CV_64FC1 , CV_32FC2 , or +CV_64FC2 type. +@param src2 Second multiplied input matrix of the same type as src1 . +@param alpha Weight of the matrix product. +@param src3 Third optional delta matrix added to the matrix product. It should have the same type +as src1 and src2 . +@param beta Weight of src3 . +@param dst Destination matrix. It has the proper size and the same type as input matrices. +@param flags Operation flags: +- **GEMM_1_T** transpose src1 +- **GEMM_2_T** transpose src2 +- **GEMM_3_T** transpose src3 +@param stream Stream for the asynchronous version. + +The function performs generalized matrix multiplication similar to the gemm functions in BLAS level +3. For example, gemm(src1, src2, alpha, src3, beta, dst, GEMM_1_T + GEMM_3_T) corresponds to + +\f[\texttt{dst} = \texttt{alpha} \cdot \texttt{src1} ^T \cdot \texttt{src2} + \texttt{beta} \cdot \texttt{src3} ^T\f] + +@note Transposition operation doesn't support CV_64FC2 input type. + +@sa gemm + */ +CV_EXPORTS_W void gemm(InputArray src1, InputArray src2, double alpha, + InputArray src3, double beta, OutputArray dst, int flags = 0, Stream& stream = Stream::Null()); + +/** @brief Performs a per-element multiplication of two Fourier spectrums. + +@param src1 First spectrum. +@param src2 Second spectrum with the same size and type as a . +@param dst Destination spectrum. +@param flags Mock parameter used for CPU/CUDA interfaces similarity. +@param conjB Optional flag to specify if the second spectrum needs to be conjugated before the +multiplication. +@param stream Stream for the asynchronous version. + +Only full (not packed) CV_32FC2 complex spectrums in the interleaved format are supported for now. + +@sa mulSpectrums + */ +CV_EXPORTS_W void mulSpectrums(InputArray src1, InputArray src2, OutputArray dst, int flags, bool conjB=false, Stream& stream = Stream::Null()); + +/** @brief Performs a per-element multiplication of two Fourier spectrums and scales the result. + +@param src1 First spectrum. +@param src2 Second spectrum with the same size and type as a . +@param dst Destination spectrum. +@param flags Mock parameter used for CPU/CUDA interfaces similarity, simply add a `0` value. +@param scale Scale constant. +@param conjB Optional flag to specify if the second spectrum needs to be conjugated before the +multiplication. +@param stream Stream for the asynchronous version. + +Only full (not packed) CV_32FC2 complex spectrums in the interleaved format are supported for now. + +@sa mulSpectrums + */ +CV_EXPORTS_W void mulAndScaleSpectrums(InputArray src1, InputArray src2, OutputArray dst, int flags, float scale, bool conjB=false, Stream& stream = Stream::Null()); + +/** @brief Performs a forward or inverse discrete Fourier transform (1D or 2D) of the floating point matrix. + +@param src Source matrix (real or complex). +@param dst Destination matrix (real or complex). +@param dft_size Size of a discrete Fourier transform. +@param flags Optional flags: +- **DFT_ROWS** transforms each individual row of the source matrix. +- **DFT_SCALE** scales the result: divide it by the number of elements in the transform +(obtained from dft_size ). +- **DFT_INVERSE** inverts DFT. Use for complex-complex cases (real-complex and complex-real +cases are always forward and inverse, respectively). +- **DFT_COMPLEX_INPUT** Specifies that input is complex input with 2 channels. +- **DFT_REAL_OUTPUT** specifies the output as real. The source matrix is the result of +real-complex transform, so the destination matrix must be real. +@param stream Stream for the asynchronous version. + +Use to handle real matrices ( CV32FC1 ) and complex matrices in the interleaved format ( CV32FC2 ). + +The source matrix should be continuous, otherwise reallocation and data copying is performed. The +function chooses an operation mode depending on the flags, size, and channel count of the source +matrix: + +- If the source matrix is complex and the output is not specified as real, the destination +matrix is complex and has the dft_size size and CV_32FC2 type. The destination matrix +contains a full result of the DFT (forward or inverse). +- If the source matrix is complex and the output is specified as real, the function assumes that +its input is the result of the forward transform (see the next item). The destination matrix +has the dft_size size and CV_32FC1 type. It contains the result of the inverse DFT. +- If the source matrix is real (its type is CV_32FC1 ), forward DFT is performed. The result of +the DFT is packed into complex ( CV_32FC2 ) matrix. So, the width of the destination matrix +is dft_size.width / 2 + 1 . But if the source is a single column, the height is reduced +instead of the width. + +@sa dft + */ +CV_EXPORTS_W void dft(InputArray src, OutputArray dst, Size dft_size, int flags=0, Stream& stream = Stream::Null()); + +/** @brief Base class for DFT operator as a cv::Algorithm. : + */ +class CV_EXPORTS_W DFT : public Algorithm +{ +public: + /** @brief Computes an FFT of a given image. + + @param image Source image. Only CV_32FC1 images are supported for now. + @param result Result image. + @param stream Stream for the asynchronous version. + */ + CV_WRAP virtual void compute(InputArray image, OutputArray result, Stream& stream = Stream::Null()) = 0; +}; + +/** @brief Creates implementation for cuda::DFT. + +@param dft_size The image size. +@param flags Optional flags: +- **DFT_ROWS** transforms each individual row of the source matrix. +- **DFT_SCALE** scales the result: divide it by the number of elements in the transform +(obtained from dft_size ). +- **DFT_INVERSE** inverts DFT. Use for complex-complex cases (real-complex and complex-real +cases are always forward and inverse, respectively). +- **DFT_COMPLEX_INPUT** Specifies that inputs will be complex with 2 channels. +- **DFT_REAL_OUTPUT** specifies the output as real. The source matrix is the result of +real-complex transform, so the destination matrix must be real. + */ +CV_EXPORTS_W Ptr createDFT(Size dft_size, int flags); + +/** @brief Base class for convolution (or cross-correlation) operator. : + */ +class CV_EXPORTS_W Convolution : public Algorithm +{ +public: + /** @brief Computes a convolution (or cross-correlation) of two images. + + @param image Source image. Only CV_32FC1 images are supported for now. + @param templ Template image. The size is not greater than the image size. The type is the same as + image . + @param result Result image. If image is *W x H* and templ is *w x h*, then result must be *W-w+1 x + H-h+1*. + @param ccorr Flags to evaluate cross-correlation instead of convolution. + @param stream Stream for the asynchronous version. + */ + virtual void convolve(InputArray image, InputArray templ, OutputArray result, bool ccorr = false, Stream& stream = Stream::Null()) = 0; +}; + +/** @brief Creates implementation for cuda::Convolution . + +@param user_block_size Block size. If you leave default value Size(0,0) then automatic +estimation of block size will be used (which is optimized for speed). By varying user_block_size +you can reduce memory requirements at the cost of speed. + */ +CV_EXPORTS_W Ptr createConvolution(Size user_block_size = Size()); + +//! @} cudaarithm_arithm + +//! @} cudaarithm + +}} // namespace cv { namespace cuda { + +#endif /* OPENCV_CUDAARITHM_HPP */ diff --git a/modules/cudaarithm/perf/perf_arithm.cpp b/modules/cudaarithm/perf/perf_arithm.cpp new file mode 100644 index 000000000..ca23e19dc --- /dev/null +++ b/modules/cudaarithm/perf/perf_arithm.cpp @@ -0,0 +1,254 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "perf_precomp.hpp" + +namespace opencv_test { namespace { + +////////////////////////////////////////////////////////////////////// +// GEMM + +#ifdef HAVE_CUBLAS + +CV_FLAGS(GemmFlags, 0, cv::GEMM_1_T, cv::GEMM_2_T, cv::GEMM_3_T) +#define ALL_GEMM_FLAGS Values(GemmFlags(0), GemmFlags(cv::GEMM_1_T), GemmFlags(cv::GEMM_2_T), GemmFlags(cv::GEMM_3_T), \ + GemmFlags(cv::GEMM_1_T | cv::GEMM_2_T), GemmFlags(cv::GEMM_1_T | cv::GEMM_3_T), GemmFlags(cv::GEMM_1_T | cv::GEMM_2_T | cv::GEMM_3_T)) + +DEF_PARAM_TEST(Sz_Type_Flags, cv::Size, MatType, GemmFlags); + +PERF_TEST_P(Sz_Type_Flags, GEMM, + Combine(Values(cv::Size(512, 512), cv::Size(1024, 1024)), + Values(CV_32FC1, CV_32FC2, CV_64FC1), + ALL_GEMM_FLAGS)) +{ + const cv::Size size = GET_PARAM(0); + const int type = GET_PARAM(1); + const int flags = GET_PARAM(2); + + cv::Mat src1(size, type); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, type); + declare.in(src2, WARMUP_RNG); + + cv::Mat src3(size, type); + declare.in(src3, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + declare.time(5.0); + + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + const cv::cuda::GpuMat d_src3(src3); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::gemm(d_src1, d_src2, 1.0, d_src3, 1.0, dst, flags); + + CUDA_SANITY_CHECK(dst, 1e-6, ERROR_RELATIVE); + } + else + { + declare.time(50.0); + + cv::Mat dst; + + TEST_CYCLE() cv::gemm(src1, src2, 1.0, src3, 1.0, dst, flags); + + CPU_SANITY_CHECK(dst); + } +} + +#endif + +////////////////////////////////////////////////////////////////////// +// MulSpectrums + +CV_FLAGS(DftFlags, 0, cv::DFT_INVERSE, cv::DFT_SCALE, cv::DFT_ROWS, cv::DFT_COMPLEX_OUTPUT, cv::DFT_REAL_OUTPUT) + +DEF_PARAM_TEST(Sz_Flags, cv::Size, DftFlags); + +PERF_TEST_P(Sz_Flags, MulSpectrums, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(0, DftFlags(cv::DFT_ROWS)))) +{ + const cv::Size size = GET_PARAM(0); + const int flag = GET_PARAM(1); + + cv::Mat a(size, CV_32FC2); + cv::Mat b(size, CV_32FC2); + declare.in(a, b, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_a(a); + const cv::cuda::GpuMat d_b(b); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::mulSpectrums(d_a, d_b, dst, flag); + + CUDA_SANITY_CHECK(dst, 1e-6, ERROR_RELATIVE); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::mulSpectrums(a, b, dst, flag); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MulAndScaleSpectrums + +PERF_TEST_P(Sz, MulAndScaleSpectrums, + CUDA_TYPICAL_MAT_SIZES) +{ + const cv::Size size = GetParam(); + + const float scale = 1.f / size.area(); + + cv::Mat src1(size, CV_32FC2); + cv::Mat src2(size, CV_32FC2); + declare.in(src1,src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::mulAndScaleSpectrums(d_src1, d_src2, dst, cv::DFT_ROWS, scale, false); + + CUDA_SANITY_CHECK(dst, 1e-6, ERROR_RELATIVE); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// Dft + +PERF_TEST_P(Sz_Flags, Dft, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(0, DftFlags(cv::DFT_ROWS), DftFlags(cv::DFT_INVERSE)))) +{ + declare.time(10.0); + + const cv::Size size = GET_PARAM(0); + const int flag = GET_PARAM(1); + + cv::Mat src(size, CV_32FC2); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::dft(d_src, dst, size, flag); + + CUDA_SANITY_CHECK(dst, 1e-6, ERROR_RELATIVE); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::dft(src, dst, flag); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Convolve + +DEF_PARAM_TEST(Sz_KernelSz_Ccorr, cv::Size, int, bool); + +PERF_TEST_P(Sz_KernelSz_Ccorr, Convolve, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(17, 27, 32, 64), + Bool())) +{ + declare.time(10.0); + + const cv::Size size = GET_PARAM(0); + const int templ_size = GET_PARAM(1); + const bool ccorr = GET_PARAM(2); + + const cv::Mat image(size, CV_32FC1); + const cv::Mat templ(templ_size, templ_size, CV_32FC1); + declare.in(image, templ, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + cv::cuda::GpuMat d_image = cv::cuda::createContinuous(size, CV_32FC1); + d_image.upload(image); + + cv::cuda::GpuMat d_templ = cv::cuda::createContinuous(templ_size, templ_size, CV_32FC1); + d_templ.upload(templ); + + cv::Ptr convolution = cv::cuda::createConvolution(); + + cv::cuda::GpuMat dst; + + TEST_CYCLE() convolution->convolve(d_image, d_templ, dst, ccorr); + + CUDA_SANITY_CHECK(dst, 1e-6, ERROR_RELATIVE); + } + else + { + if (ccorr) + FAIL_NO_CPU(); + + cv::Mat dst; + + TEST_CYCLE() cv::filter2D(image, dst, image.depth(), templ); + + CPU_SANITY_CHECK(dst); + } +} + +}} // namespace diff --git a/modules/cudaarithm/perf/perf_core.cpp b/modules/cudaarithm/perf/perf_core.cpp new file mode 100644 index 000000000..bc9f0e2f7 --- /dev/null +++ b/modules/cudaarithm/perf/perf_core.cpp @@ -0,0 +1,323 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "perf_precomp.hpp" + +namespace opencv_test { namespace { + +#define ARITHM_MAT_DEPTH Values(CV_8U, CV_16U, CV_32F, CV_64F) + +////////////////////////////////////////////////////////////////////// +// Merge + +DEF_PARAM_TEST(Sz_Depth_Cn, cv::Size, MatDepth, MatCn); + +PERF_TEST_P(Sz_Depth_Cn, Merge, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH, + Values(2, 3, 4))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + std::vector src(channels); + for (int i = 0; i < channels; ++i) + { + src[i].create(size, depth); + declare.in(src[i], WARMUP_RNG); + } + + if (PERF_RUN_CUDA()) + { + std::vector d_src(channels); + for (int i = 0; i < channels; ++i) + d_src[i].upload(src[i]); + + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::merge(d_src, dst); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::merge(src, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Split + +PERF_TEST_P(Sz_Depth_Cn, Split, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH, + Values(2, 3, 4))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + cv::Mat src(size, CV_MAKE_TYPE(depth, channels)); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + std::vector dst; + + TEST_CYCLE() cv::cuda::split(d_src, dst); + + const cv::cuda::GpuMat& dst0 = dst[0]; + const cv::cuda::GpuMat& dst1 = dst[1]; + + CUDA_SANITY_CHECK(dst0, 1e-10); + CUDA_SANITY_CHECK(dst1, 1e-10); + } + else + { + std::vector dst; + + TEST_CYCLE() cv::split(src, dst); + + const cv::Mat& dst0 = dst[0]; + const cv::Mat& dst1 = dst[1]; + + CPU_SANITY_CHECK(dst0); + CPU_SANITY_CHECK(dst1); + } +} + +////////////////////////////////////////////////////////////////////// +// Transpose + +PERF_TEST_P(Sz_Type, Transpose, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8UC1, CV_8UC4, CV_16UC2, CV_16SC2, CV_32SC1, CV_32SC2, CV_64FC1))) +{ + const cv::Size size = GET_PARAM(0); + const int type = GET_PARAM(1); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::transpose(d_src, dst); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::transpose(src, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Flip + +enum {FLIP_BOTH = 0, FLIP_X = 1, FLIP_Y = -1}; +CV_ENUM(FlipCode, FLIP_BOTH, FLIP_X, FLIP_Y) + +DEF_PARAM_TEST(Sz_Depth_Cn_Code, cv::Size, MatDepth, MatCn, FlipCode); + +PERF_TEST_P(Sz_Depth_Cn_Code, Flip, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F), + CUDA_CHANNELS_1_3_4, + FlipCode::all())) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + const int flipCode = GET_PARAM(3); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::flip(d_src, dst, flipCode); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::flip(src, dst, flipCode); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// LutOneChannel + +PERF_TEST_P(Sz_Type, LutOneChannel, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8UC1, CV_8UC3))) +{ + const cv::Size size = GET_PARAM(0); + const int type = GET_PARAM(1); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + cv::Mat lut(1, 256, CV_8UC1); + declare.in(lut, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + cv::Ptr lutAlg = cv::cuda::createLookUpTable(lut); + + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() lutAlg->transform(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::LUT(src, lut, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// LutMultiChannel + +PERF_TEST_P(Sz_Type, LutMultiChannel, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8UC3))) +{ + const cv::Size size = GET_PARAM(0); + const int type = GET_PARAM(1); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + cv::Mat lut(1, 256, CV_MAKE_TYPE(CV_8U, src.channels())); + declare.in(lut, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + cv::Ptr lutAlg = cv::cuda::createLookUpTable(lut); + + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() lutAlg->transform(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::LUT(src, lut, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// CopyMakeBorder + +DEF_PARAM_TEST(Sz_Depth_Cn_Border, cv::Size, MatDepth, MatCn, BorderMode); + +PERF_TEST_P(Sz_Depth_Cn_Border, CopyMakeBorder, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F), + CUDA_CHANNELS_1_3_4, + ALL_BORDER_MODES)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + const int borderMode = GET_PARAM(3); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::copyMakeBorder(d_src, dst, 5, 5, 5, 5, borderMode); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::copyMakeBorder(src, dst, 5, 5, 5, 5, borderMode); + + CPU_SANITY_CHECK(dst); + } +} + +}} // namespace diff --git a/modules/cudaarithm/perf/perf_element_operations.cpp b/modules/cudaarithm/perf/perf_element_operations.cpp new file mode 100644 index 000000000..02f412d99 --- /dev/null +++ b/modules/cudaarithm/perf/perf_element_operations.cpp @@ -0,0 +1,1501 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "perf_precomp.hpp" + +namespace opencv_test { namespace { + +#define ARITHM_MAT_DEPTH Values(CV_8U, CV_16U, CV_32F, CV_64F) + +////////////////////////////////////////////////////////////////////// +// AddMat + +DEF_PARAM_TEST(Sz_Depth, cv::Size, MatDepth); + +PERF_TEST_P(Sz_Depth, AddMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::add(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::add(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// AddScalar + +PERF_TEST_P(Sz_Depth, AddScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::add(d_src, s, dst); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::add(src, s, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// SubtractMat + +PERF_TEST_P(Sz_Depth, SubtractMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::subtract(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::subtract(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// SubtractScalar + +PERF_TEST_P(Sz_Depth, SubtractScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::subtract(d_src, s, dst); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::subtract(src, s, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MultiplyMat + +PERF_TEST_P(Sz_Depth, MultiplyMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::multiply(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst, 1e-6); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::multiply(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MultiplyScalar + +PERF_TEST_P(Sz_Depth, MultiplyScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::multiply(d_src, s, dst); + + CUDA_SANITY_CHECK(dst, 1e-6); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::multiply(src, s, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// DivideMat + +PERF_TEST_P(Sz_Depth, DivideMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::divide(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst, 1e-6); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::divide(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// DivideScalar + +PERF_TEST_P(Sz_Depth, DivideScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::divide(d_src, s, dst); + + CUDA_SANITY_CHECK(dst, 1e-6); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::divide(src, s, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// DivideScalarInv + +PERF_TEST_P(Sz_Depth, DivideScalarInv, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::divide(s[0], d_src, dst); + + CUDA_SANITY_CHECK(dst, 1e-6); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::divide(s, src, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// AbsDiffMat + +PERF_TEST_P(Sz_Depth, AbsDiffMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::absdiff(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::absdiff(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// AbsDiffScalar + +PERF_TEST_P(Sz_Depth, AbsDiffScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::absdiff(d_src, s, dst); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::absdiff(src, s, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Abs + +PERF_TEST_P(Sz_Depth, Abs, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_16S, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::abs(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// Sqr + +PERF_TEST_P(Sz_Depth, Sqr, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16S, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::sqr(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// Sqrt + +PERF_TEST_P(Sz_Depth, Sqrt, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16S, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + cv::randu(src, 0, 100000); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::sqrt(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::sqrt(src, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Log + +PERF_TEST_P(Sz_Depth, Log, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16S, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + cv::randu(src, 0, 100000); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::log(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::log(src, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Exp + +PERF_TEST_P(Sz_Depth, Exp, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16S, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + cv::randu(src, 0, 10); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::exp(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::exp(src, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Pow + +DEF_PARAM_TEST(Sz_Depth_Power, cv::Size, MatDepth, double); + +PERF_TEST_P(Sz_Depth_Power, Pow, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16S, CV_32F), + Values(0.3, 2.0, 2.4))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const double power = GET_PARAM(2); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::pow(d_src, power, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::pow(src, power, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// CompareMat + +CV_ENUM(CmpCode, cv::CMP_EQ, cv::CMP_GT, cv::CMP_GE, cv::CMP_LT, cv::CMP_LE, cv::CMP_NE) + +DEF_PARAM_TEST(Sz_Depth_Code, cv::Size, MatDepth, CmpCode); + +PERF_TEST_P(Sz_Depth_Code, CompareMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH, + CmpCode::all())) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int cmp_code = GET_PARAM(2); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::compare(d_src1, d_src2, dst, cmp_code); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::compare(src1, src2, dst, cmp_code); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// CompareScalar + +PERF_TEST_P(Sz_Depth_Code, CompareScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + ARITHM_MAT_DEPTH, + CmpCode::all())) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int cmp_code = GET_PARAM(2); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::compare(d_src, s, dst, cmp_code); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::compare(src, s, dst, cmp_code); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// BitwiseNot + +PERF_TEST_P(Sz_Depth, BitwiseNot, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::bitwise_not(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::bitwise_not(src, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// BitwiseAndMat + +PERF_TEST_P(Sz_Depth, BitwiseAndMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::bitwise_and(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::bitwise_and(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// BitwiseAndScalar + +DEF_PARAM_TEST(Sz_Depth_Cn, cv::Size, MatDepth, MatCn); + +PERF_TEST_P(Sz_Depth_Cn, BitwiseAndScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S), + CUDA_CHANNELS_1_3_4)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + cv::Scalar_ is = s; + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::bitwise_and(d_src, is, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::bitwise_and(src, is, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// BitwiseOrMat + +PERF_TEST_P(Sz_Depth, BitwiseOrMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::bitwise_or(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::bitwise_or(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// BitwiseOrScalar + +PERF_TEST_P(Sz_Depth_Cn, BitwiseOrScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S), + CUDA_CHANNELS_1_3_4)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + cv::Scalar_ is = s; + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::bitwise_or(d_src, is, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::bitwise_or(src, is, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// BitwiseXorMat + +PERF_TEST_P(Sz_Depth, BitwiseXorMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::bitwise_xor(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::bitwise_xor(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// BitwiseXorScalar + +PERF_TEST_P(Sz_Depth_Cn, BitwiseXorScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S), + CUDA_CHANNELS_1_3_4)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + cv::Scalar s; + declare.in(s, WARMUP_RNG); + cv::Scalar_ is = s; + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::bitwise_xor(d_src, is, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::bitwise_xor(src, is, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// RShift + +PERF_TEST_P(Sz_Depth_Cn, RShift, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S), + CUDA_CHANNELS_1_3_4)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + const cv::Scalar_ val = cv::Scalar_::all(4); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::rshift(d_src, val, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// LShift + +PERF_TEST_P(Sz_Depth_Cn, LShift, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S), + CUDA_CHANNELS_1_3_4)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + const cv::Scalar_ val = cv::Scalar_::all(4); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::lshift(d_src, val, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// MinMat + +PERF_TEST_P(Sz_Depth, MinMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::min(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::min(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MinScalar + +PERF_TEST_P(Sz_Depth, MinScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar val; + declare.in(val, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::min(d_src, val[0], dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::min(src, val[0], dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MaxMat + +PERF_TEST_P(Sz_Depth, MaxMat, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src1(size, depth); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::max(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::max(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MaxScalar + +PERF_TEST_P(Sz_Depth, MaxScalar, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + cv::Scalar val; + declare.in(val, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::max(d_src, val[0], dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::max(src, val[0], dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// AddWeighted + +DEF_PARAM_TEST(Sz_3Depth, cv::Size, MatDepth, MatDepth, MatDepth); + +PERF_TEST_P(Sz_3Depth, AddWeighted, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F, CV_64F), + Values(CV_8U, CV_16U, CV_32F, CV_64F), + Values(CV_8U, CV_16U, CV_32F, CV_64F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth1 = GET_PARAM(1); + const int depth2 = GET_PARAM(2); + const int dst_depth = GET_PARAM(3); + + cv::Mat src1(size, depth1); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, depth2); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::addWeighted(d_src1, 0.5, d_src2, 0.5, 10.0, dst, dst_depth); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::addWeighted(src1, 0.5, src2, 0.5, 10.0, dst, dst_depth); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MagnitudeComplex + +PERF_TEST_P(Sz, MagnitudeComplex, + CUDA_TYPICAL_MAT_SIZES) +{ + const cv::Size size = GetParam(); + + cv::Mat src(size, CV_32FC2); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::magnitude(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat xy[2]; + cv::split(src, xy); + + cv::Mat dst; + + TEST_CYCLE() cv::magnitude(xy[0], xy[1], dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MagnitudeSqrComplex + +PERF_TEST_P(Sz, MagnitudeSqrComplex, + CUDA_TYPICAL_MAT_SIZES) +{ + const cv::Size size = GetParam(); + + cv::Mat src(size, CV_32FC2); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::magnitudeSqr(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// Magnitude + +PERF_TEST_P(Sz, Magnitude, + CUDA_TYPICAL_MAT_SIZES) +{ + const cv::Size size = GetParam(); + + cv::Mat src1(size, CV_32FC1); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, CV_32FC1); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::magnitude(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::magnitude(src1, src2, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MagnitudeSqr + +PERF_TEST_P(Sz, MagnitudeSqr, + CUDA_TYPICAL_MAT_SIZES) +{ + const cv::Size size = GetParam(); + + cv::Mat src1(size, CV_32FC1); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, CV_32FC1); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::magnitudeSqr(d_src1, d_src2, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// Phase + +DEF_PARAM_TEST(Sz_AngleInDegrees, cv::Size, bool); + +PERF_TEST_P(Sz_AngleInDegrees, Phase, + Combine(CUDA_TYPICAL_MAT_SIZES, + Bool())) +{ + const cv::Size size = GET_PARAM(0); + const bool angleInDegrees = GET_PARAM(1); + + cv::Mat src1(size, CV_32FC1); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, CV_32FC1); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::phase(d_src1, d_src2, dst, angleInDegrees); + + CUDA_SANITY_CHECK(dst, 1e-6, ERROR_RELATIVE); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::phase(src1, src2, dst, angleInDegrees); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// CartToPolar + +PERF_TEST_P(Sz_AngleInDegrees, CartToPolar, + Combine(CUDA_TYPICAL_MAT_SIZES, + Bool())) +{ + const cv::Size size = GET_PARAM(0); + const bool angleInDegrees = GET_PARAM(1); + + cv::Mat src1(size, CV_32FC1); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, CV_32FC1); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + cv::cuda::GpuMat magnitude; + cv::cuda::GpuMat angle; + + TEST_CYCLE() cv::cuda::cartToPolar(d_src1, d_src2, magnitude, angle, angleInDegrees); + + CUDA_SANITY_CHECK(magnitude); + CUDA_SANITY_CHECK(angle, 1e-6, ERROR_RELATIVE); + } + else + { + cv::Mat magnitude; + cv::Mat angle; + + TEST_CYCLE() cv::cartToPolar(src1, src2, magnitude, angle, angleInDegrees); + + CPU_SANITY_CHECK(magnitude); + CPU_SANITY_CHECK(angle); + } +} + +////////////////////////////////////////////////////////////////////// +// PolarToCart + +PERF_TEST_P(Sz_AngleInDegrees, PolarToCart, + Combine(CUDA_TYPICAL_MAT_SIZES, + Bool())) +{ + const cv::Size size = GET_PARAM(0); + const bool angleInDegrees = GET_PARAM(1); + + cv::Mat magnitude(size, CV_32FC1); + declare.in(magnitude, WARMUP_RNG); + + cv::Mat angle(size, CV_32FC1); + declare.in(angle, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_magnitude(magnitude); + const cv::cuda::GpuMat d_angle(angle); + cv::cuda::GpuMat x; + cv::cuda::GpuMat y; + + TEST_CYCLE() cv::cuda::polarToCart(d_magnitude, d_angle, x, y, angleInDegrees); + + CUDA_SANITY_CHECK(x); + CUDA_SANITY_CHECK(y); + } + else + { + cv::Mat x; + cv::Mat y; + + TEST_CYCLE() cv::polarToCart(magnitude, angle, x, y, angleInDegrees); + + CPU_SANITY_CHECK(x); + CPU_SANITY_CHECK(y); + } +} + +////////////////////////////////////////////////////////////////////// +// Threshold + +CV_ENUM(ThreshOp, cv::THRESH_BINARY, cv::THRESH_BINARY_INV, cv::THRESH_TRUNC, cv::THRESH_TOZERO, cv::THRESH_TOZERO_INV) + +DEF_PARAM_TEST(Sz_Depth_Op, cv::Size, MatDepth, ThreshOp); + +PERF_TEST_P(Sz_Depth_Op, Threshold, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F, CV_64F), + ThreshOp::all())) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int threshOp = GET_PARAM(2); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::threshold(d_src, dst, 100.0, 255.0, threshOp); + + CUDA_SANITY_CHECK(dst, 1e-10); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::threshold(src, dst, 100.0, 255.0, threshOp); + + CPU_SANITY_CHECK(dst); + } +} + +}} // namespace diff --git a/modules/cudaarithm/perf/perf_main.cpp b/modules/cudaarithm/perf/perf_main.cpp new file mode 100644 index 000000000..118d7596a --- /dev/null +++ b/modules/cudaarithm/perf/perf_main.cpp @@ -0,0 +1,47 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "perf_precomp.hpp" + +using namespace perf; + +CV_PERF_TEST_CUDA_MAIN(cudaarithm) diff --git a/modules/cudaarithm/perf/perf_precomp.hpp b/modules/cudaarithm/perf/perf_precomp.hpp new file mode 100644 index 000000000..071ac9465 --- /dev/null +++ b/modules/cudaarithm/perf/perf_precomp.hpp @@ -0,0 +1,55 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ +#ifndef __OPENCV_PERF_PRECOMP_HPP__ +#define __OPENCV_PERF_PRECOMP_HPP__ + +#include "opencv2/ts.hpp" +#include "opencv2/ts/cuda_perf.hpp" + +#include "opencv2/cudaarithm.hpp" + +namespace opencv_test { +using namespace perf; +using namespace testing; +} + +#endif diff --git a/modules/cudaarithm/perf/perf_reductions.cpp b/modules/cudaarithm/perf/perf_reductions.cpp new file mode 100644 index 000000000..71bb5524a --- /dev/null +++ b/modules/cudaarithm/perf/perf_reductions.cpp @@ -0,0 +1,520 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "perf_precomp.hpp" + +namespace opencv_test { namespace { + +////////////////////////////////////////////////////////////////////// +// Norm + +DEF_PARAM_TEST(Sz_Depth_Norm, cv::Size, MatDepth, NormType); + +PERF_TEST_P(Sz_Depth_Norm, Norm, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32S, CV_32F), + Values(NormType(cv::NORM_INF), NormType(cv::NORM_L1), NormType(cv::NORM_L2)))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int normType = GET_PARAM(2); + + cv::Mat src(size, depth); + if (depth == CV_8U) + cv::randu(src, 0, 254); + else + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat d_buf; + double gpu_dst; + + TEST_CYCLE() gpu_dst = cv::cuda::norm(d_src, normType, d_buf); + + SANITY_CHECK(gpu_dst, 1e-6, ERROR_RELATIVE); + } + else + { + double cpu_dst; + + TEST_CYCLE() cpu_dst = cv::norm(src, normType); + + SANITY_CHECK(cpu_dst, 1e-6, ERROR_RELATIVE); + } +} + +////////////////////////////////////////////////////////////////////// +// NormDiff + +DEF_PARAM_TEST(Sz_Norm, cv::Size, NormType); + +PERF_TEST_P(Sz_Norm, NormDiff, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(NormType(cv::NORM_INF), NormType(cv::NORM_L1), NormType(cv::NORM_L2)))) +{ + const cv::Size size = GET_PARAM(0); + const int normType = GET_PARAM(1); + + cv::Mat src1(size, CV_8UC1); + declare.in(src1, WARMUP_RNG); + + cv::Mat src2(size, CV_8UC1); + declare.in(src2, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src1(src1); + const cv::cuda::GpuMat d_src2(src2); + double gpu_dst; + + TEST_CYCLE() gpu_dst = cv::cuda::norm(d_src1, d_src2, normType); + + SANITY_CHECK(gpu_dst); + + } + else + { + double cpu_dst; + + TEST_CYCLE() cpu_dst = cv::norm(src1, src2, normType); + + SANITY_CHECK(cpu_dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Sum + +DEF_PARAM_TEST(Sz_Depth_Cn, cv::Size, MatDepth, MatCn); + +PERF_TEST_P(Sz_Depth_Cn, Sum, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F), + CUDA_CHANNELS_1_3_4)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::Scalar gpu_dst; + + TEST_CYCLE() gpu_dst = cv::cuda::sum(d_src); + + SANITY_CHECK(gpu_dst, 1e-5, ERROR_RELATIVE); + } + else + { + cv::Scalar cpu_dst; + + TEST_CYCLE() cpu_dst = cv::sum(src); + + SANITY_CHECK(cpu_dst, 1e-6, ERROR_RELATIVE); + } +} + +////////////////////////////////////////////////////////////////////// +// SumAbs + +PERF_TEST_P(Sz_Depth_Cn, SumAbs, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F), + CUDA_CHANNELS_1_3_4)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::Scalar gpu_dst; + + TEST_CYCLE() gpu_dst = cv::cuda::absSum(d_src); + + SANITY_CHECK(gpu_dst, 1e-6, ERROR_RELATIVE); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// SumSqr + +PERF_TEST_P(Sz_Depth_Cn, SumSqr, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F), + CUDA_CHANNELS_1_3_4)) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::Scalar gpu_dst; + + TEST_CYCLE() gpu_dst = cv::cuda::sqrSum(d_src); + + SANITY_CHECK(gpu_dst, 1e-6, ERROR_RELATIVE); + } + else + { + FAIL_NO_CPU(); + } +} + +////////////////////////////////////////////////////////////////////// +// MinMax + +DEF_PARAM_TEST(Sz_Depth, cv::Size, MatDepth); + +PERF_TEST_P(Sz_Depth, MinMax, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F, CV_64F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + if (depth == CV_8U) + cv::randu(src, 0, 254); + else + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + double gpu_minVal, gpu_maxVal; + + TEST_CYCLE() cv::cuda::minMax(d_src, &gpu_minVal, &gpu_maxVal, cv::cuda::GpuMat()); + + SANITY_CHECK(gpu_minVal, 1e-10); + SANITY_CHECK(gpu_maxVal, 1e-10); + } + else + { + double cpu_minVal, cpu_maxVal; + + TEST_CYCLE() cv::minMaxLoc(src, &cpu_minVal, &cpu_maxVal); + + SANITY_CHECK(cpu_minVal); + SANITY_CHECK(cpu_maxVal); + } +} + +////////////////////////////////////////////////////////////////////// +// MinMaxLoc + +PERF_TEST_P(Sz_Depth, MinMaxLoc, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F, CV_64F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + if (depth == CV_8U) + cv::randu(src, 0, 254); + else + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + double gpu_minVal, gpu_maxVal; + cv::Point gpu_minLoc, gpu_maxLoc; + + TEST_CYCLE() cv::cuda::minMaxLoc(d_src, &gpu_minVal, &gpu_maxVal, &gpu_minLoc, &gpu_maxLoc); + + SANITY_CHECK(gpu_minVal, 1e-10); + SANITY_CHECK(gpu_maxVal, 1e-10); + } + else + { + double cpu_minVal, cpu_maxVal; + cv::Point cpu_minLoc, cpu_maxLoc; + + TEST_CYCLE() cv::minMaxLoc(src, &cpu_minVal, &cpu_maxVal, &cpu_minLoc, &cpu_maxLoc); + + SANITY_CHECK(cpu_minVal); + SANITY_CHECK(cpu_maxVal); + } +} + +////////////////////////////////////////////////////////////////////// +// CountNonZero + +PERF_TEST_P(Sz_Depth, CountNonZero, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F, CV_64F))) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + + cv::Mat src(size, depth); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + int gpu_dst = 0; + + TEST_CYCLE() gpu_dst = cv::cuda::countNonZero(d_src); + + SANITY_CHECK(gpu_dst); + } + else + { + int cpu_dst = 0; + + TEST_CYCLE() cpu_dst = cv::countNonZero(src); + + SANITY_CHECK(cpu_dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Reduce + +CV_ENUM(ReduceCode, REDUCE_SUM, REDUCE_AVG, REDUCE_MAX, REDUCE_MIN) + +enum {Rows = 0, Cols = 1}; +CV_ENUM(ReduceDim, Rows, Cols) + +DEF_PARAM_TEST(Sz_Depth_Cn_Code_Dim, cv::Size, MatDepth, MatCn, ReduceCode, ReduceDim); + +PERF_TEST_P(Sz_Depth_Cn_Code_Dim, Reduce, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_16S, CV_32F), + Values(1, 2, 3, 4), + ReduceCode::all(), + ReduceDim::all())) +{ + const cv::Size size = GET_PARAM(0); + const int depth = GET_PARAM(1); + const int channels = GET_PARAM(2); + const int reduceOp = GET_PARAM(3); + const int dim = GET_PARAM(4); + + const int type = CV_MAKE_TYPE(depth, channels); + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::reduce(d_src, dst, dim, reduceOp, CV_32F); + + dst = dst.reshape(dst.channels(), 1); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::reduce(src, dst, dim, reduceOp, CV_32F); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// Normalize + +DEF_PARAM_TEST(Sz_Depth_NormType, cv::Size, MatDepth, NormType); + +PERF_TEST_P(Sz_Depth_NormType, Normalize, + Combine(CUDA_TYPICAL_MAT_SIZES, + Values(CV_8U, CV_16U, CV_32F, CV_64F), + Values(NormType(cv::NORM_INF), + NormType(cv::NORM_L1), + NormType(cv::NORM_L2), + NormType(cv::NORM_MINMAX)))) +{ + const cv::Size size = GET_PARAM(0); + const int type = GET_PARAM(1); + const int norm_type = GET_PARAM(2); + + const double alpha = 1; + const double beta = 0; + + cv::Mat src(size, type); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::normalize(d_src, dst, alpha, beta, norm_type, type, cv::cuda::GpuMat()); + + CUDA_SANITY_CHECK(dst, 1e-6); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::normalize(src, dst, alpha, beta, norm_type, type); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// MeanStdDev + +PERF_TEST_P(Sz, MeanStdDev, + CUDA_TYPICAL_MAT_SIZES) +{ + const cv::Size size = GetParam(); + + cv::Mat src(size, CV_8UC1); + declare.in(src, WARMUP_RNG); + + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::Scalar gpu_mean; + cv::Scalar gpu_stddev; + + TEST_CYCLE() cv::cuda::meanStdDev(d_src, gpu_mean, gpu_stddev); + + SANITY_CHECK(gpu_mean); + SANITY_CHECK(gpu_stddev); + } + else + { + cv::Scalar cpu_mean; + cv::Scalar cpu_stddev; + + TEST_CYCLE() cv::meanStdDev(src, cpu_mean, cpu_stddev); + + SANITY_CHECK(cpu_mean); + SANITY_CHECK(cpu_stddev); + } +} + +////////////////////////////////////////////////////////////////////// +// Integral + +PERF_TEST_P(Sz, Integral, + CUDA_TYPICAL_MAT_SIZES) +{ + const cv::Size size = GetParam(); + + cv::Mat src(size, CV_8UC1); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::integral(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + cv::Mat dst; + + TEST_CYCLE() cv::integral(src, dst); + + CPU_SANITY_CHECK(dst); + } +} + +////////////////////////////////////////////////////////////////////// +// IntegralSqr + +PERF_TEST_P(Sz, IntegralSqr, + CUDA_TYPICAL_MAT_SIZES) +{ + const cv::Size size = GetParam(); + + cv::Mat src(size, CV_8UC1); + declare.in(src, WARMUP_RNG); + + if (PERF_RUN_CUDA()) + { + const cv::cuda::GpuMat d_src(src); + cv::cuda::GpuMat dst; + + TEST_CYCLE() cv::cuda::sqrIntegral(d_src, dst); + + CUDA_SANITY_CHECK(dst); + } + else + { + FAIL_NO_CPU(); + } +} + +}} // namespace diff --git a/modules/cudaarithm/src/arithm.cpp b/modules/cudaarithm/src/arithm.cpp new file mode 100644 index 000000000..381580cff --- /dev/null +++ b/modules/cudaarithm/src/arithm.cpp @@ -0,0 +1,582 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "precomp.hpp" + +using namespace cv; +using namespace cv::cuda; + +#if !defined (HAVE_CUDA) || defined (CUDA_DISABLER) + +void cv::cuda::gemm(InputArray, InputArray, double, InputArray, double, OutputArray, int, Stream&) { throw_no_cuda(); } + +void cv::cuda::mulSpectrums(InputArray, InputArray, OutputArray, int, bool, Stream&) { throw_no_cuda(); } +void cv::cuda::mulAndScaleSpectrums(InputArray, InputArray, OutputArray, int, float, bool, Stream&) { throw_no_cuda(); } + +void cv::cuda::dft(InputArray, OutputArray, Size, int, Stream&) { throw_no_cuda(); } + +Ptr cv::cuda::createConvolution(Size) { throw_no_cuda(); return Ptr(); } + +#else /* !defined (HAVE_CUDA) */ + +namespace +{ + #define error_entry(entry) { entry, #entry } + + struct ErrorEntry + { + int code; + const char* str; + }; + + struct ErrorEntryComparer + { + int code; + ErrorEntryComparer(int code_) : code(code_) {} + bool operator()(const ErrorEntry& e) const { return e.code == code; } + }; + + String getErrorString(int code, const ErrorEntry* errors, size_t n) + { + size_t idx = std::find_if(errors, errors + n, ErrorEntryComparer(code)) - errors; + + const char* msg = (idx != n) ? errors[idx].str : "Unknown error code"; + String str = cv::format("%s [Code = %d]", msg, code); + + return str; + } +} + +#ifdef HAVE_CUBLAS + namespace + { + const ErrorEntry cublas_errors[] = + { + error_entry( CUBLAS_STATUS_SUCCESS ), + error_entry( CUBLAS_STATUS_NOT_INITIALIZED ), + error_entry( CUBLAS_STATUS_ALLOC_FAILED ), + error_entry( CUBLAS_STATUS_INVALID_VALUE ), + error_entry( CUBLAS_STATUS_ARCH_MISMATCH ), + error_entry( CUBLAS_STATUS_MAPPING_ERROR ), + error_entry( CUBLAS_STATUS_EXECUTION_FAILED ), + error_entry( CUBLAS_STATUS_INTERNAL_ERROR ) + }; + + const size_t cublas_error_num = sizeof(cublas_errors) / sizeof(cublas_errors[0]); + + static inline void ___cublasSafeCall(cublasStatus_t err, const char* file, const int line, const char* func) + { + if (CUBLAS_STATUS_SUCCESS != err) + { + String msg = getErrorString(err, cublas_errors, cublas_error_num); + cv::error(cv::Error::GpuApiCallError, msg, func, file, line); + } + } + } + + #define cublasSafeCall(expr) ___cublasSafeCall(expr, __FILE__, __LINE__, CV_Func) +#endif // HAVE_CUBLAS + +#ifdef HAVE_CUFFT + namespace + { + ////////////////////////////////////////////////////////////////////////// + // CUFFT errors + + const ErrorEntry cufft_errors[] = + { + error_entry( CUFFT_INVALID_PLAN ), + error_entry( CUFFT_ALLOC_FAILED ), + error_entry( CUFFT_INVALID_TYPE ), + error_entry( CUFFT_INVALID_VALUE ), + error_entry( CUFFT_INTERNAL_ERROR ), + error_entry( CUFFT_EXEC_FAILED ), + error_entry( CUFFT_SETUP_FAILED ), + error_entry( CUFFT_INVALID_SIZE ), + error_entry( CUFFT_UNALIGNED_DATA ) + }; + + const int cufft_error_num = sizeof(cufft_errors) / sizeof(cufft_errors[0]); + + void ___cufftSafeCall(int err, const char* file, const int line, const char* func) + { + if (CUFFT_SUCCESS != err) + { + String msg = getErrorString(err, cufft_errors, cufft_error_num); + cv::error(cv::Error::GpuApiCallError, msg, func, file, line); + } + } + } + + #define cufftSafeCall(expr) ___cufftSafeCall(expr, __FILE__, __LINE__, CV_Func) + +#endif + +//////////////////////////////////////////////////////////////////////// +// gemm + +void cv::cuda::gemm(InputArray _src1, InputArray _src2, double alpha, InputArray _src3, double beta, OutputArray _dst, int flags, Stream& stream) +{ +#ifndef HAVE_CUBLAS + CV_UNUSED(_src1); + CV_UNUSED(_src2); + CV_UNUSED(alpha); + CV_UNUSED(_src3); + CV_UNUSED(beta); + CV_UNUSED(_dst); + CV_UNUSED(flags); + CV_UNUSED(stream); + CV_Error(Error::StsNotImplemented, "The library was build without CUBLAS"); +#else + // CUBLAS works with column-major matrices + + GpuMat src1 = getInputMat(_src1, stream); + GpuMat src2 = getInputMat(_src2, stream); + GpuMat src3 = getInputMat(_src3, stream); + + CV_Assert( src1.type() == CV_32FC1 || src1.type() == CV_32FC2 || src1.type() == CV_64FC1 || src1.type() == CV_64FC2 ); + CV_Assert( src2.type() == src1.type() && (src3.empty() || src3.type() == src1.type()) ); + + if (src1.depth() == CV_64F) + { + if (!deviceSupports(NATIVE_DOUBLE)) + CV_Error(cv::Error::StsUnsupportedFormat, "The device doesn't support double"); + } + + bool tr1 = (flags & GEMM_1_T) != 0; + bool tr2 = (flags & GEMM_2_T) != 0; + bool tr3 = (flags & GEMM_3_T) != 0; + + if (src1.type() == CV_64FC2) + { + if (tr1 || tr2 || tr3) + CV_Error(cv::Error::StsNotImplemented, "transpose operation doesn't implemented for CV_64FC2 type"); + } + + Size src1Size = tr1 ? Size(src1.rows, src1.cols) : src1.size(); + Size src2Size = tr2 ? Size(src2.rows, src2.cols) : src2.size(); + Size src3Size = tr3 ? Size(src3.rows, src3.cols) : src3.size(); + Size dstSize(src2Size.width, src1Size.height); + + CV_Assert( src1Size.width == src2Size.height ); + CV_Assert( src3.empty() || src3Size == dstSize ); + + GpuMat dst = getOutputMat(_dst, dstSize, src1.type(), stream); + + if (beta != 0) + { + if (src3.empty()) + { + dst.setTo(Scalar::all(0), stream); + } + else + { + if (tr3) + { + cuda::transpose(src3, dst, stream); + } + else + { + src3.copyTo(dst, stream); + } + } + } + + cublasHandle_t handle; + cublasSafeCall( cublasCreate_v2(&handle) ); + + cublasSafeCall( cublasSetStream_v2(handle, StreamAccessor::getStream(stream)) ); + + cublasSafeCall( cublasSetPointerMode_v2(handle, CUBLAS_POINTER_MODE_HOST) ); + + const float alphaf = static_cast(alpha); + const float betaf = static_cast(beta); + + const cuComplex alphacf = make_cuComplex(alphaf, 0); + const cuComplex betacf = make_cuComplex(betaf, 0); + + const cuDoubleComplex alphac = make_cuDoubleComplex(alpha, 0); + const cuDoubleComplex betac = make_cuDoubleComplex(beta, 0); + + cublasOperation_t transa = tr2 ? CUBLAS_OP_T : CUBLAS_OP_N; + cublasOperation_t transb = tr1 ? CUBLAS_OP_T : CUBLAS_OP_N; + + switch (src1.type()) + { + case CV_32FC1: + cublasSafeCall( cublasSgemm_v2(handle, transa, transb, tr2 ? src2.rows : src2.cols, tr1 ? src1.cols : src1.rows, tr2 ? src2.cols : src2.rows, + &alphaf, + src2.ptr(), static_cast(src2.step / sizeof(float)), + src1.ptr(), static_cast(src1.step / sizeof(float)), + &betaf, + dst.ptr(), static_cast(dst.step / sizeof(float))) ); + break; + + case CV_64FC1: + cublasSafeCall( cublasDgemm_v2(handle, transa, transb, tr2 ? src2.rows : src2.cols, tr1 ? src1.cols : src1.rows, tr2 ? src2.cols : src2.rows, + &alpha, + src2.ptr(), static_cast(src2.step / sizeof(double)), + src1.ptr(), static_cast(src1.step / sizeof(double)), + &beta, + dst.ptr(), static_cast(dst.step / sizeof(double))) ); + break; + + case CV_32FC2: + cublasSafeCall( cublasCgemm_v2(handle, transa, transb, tr2 ? src2.rows : src2.cols, tr1 ? src1.cols : src1.rows, tr2 ? src2.cols : src2.rows, + &alphacf, + src2.ptr(), static_cast(src2.step / sizeof(cuComplex)), + src1.ptr(), static_cast(src1.step / sizeof(cuComplex)), + &betacf, + dst.ptr(), static_cast(dst.step / sizeof(cuComplex))) ); + break; + + case CV_64FC2: + cublasSafeCall( cublasZgemm_v2(handle, transa, transb, tr2 ? src2.rows : src2.cols, tr1 ? src1.cols : src1.rows, tr2 ? src2.cols : src2.rows, + &alphac, + src2.ptr(), static_cast(src2.step / sizeof(cuDoubleComplex)), + src1.ptr(), static_cast(src1.step / sizeof(cuDoubleComplex)), + &betac, + dst.ptr(), static_cast(dst.step / sizeof(cuDoubleComplex))) ); + break; + } + + cublasSafeCall( cublasDestroy_v2(handle) ); + + syncOutput(dst, _dst, stream); +#endif +} + +////////////////////////////////////////////////////////////////////////////// +// DFT function + +void cv::cuda::dft(InputArray _src, OutputArray _dst, Size dft_size, int flags, Stream& stream) +{ + if (getInputMat(_src, stream).channels() == 2) + flags |= DFT_COMPLEX_INPUT; + + Ptr dft = createDFT(dft_size, flags); + dft->compute(_src, _dst, stream); +} + +////////////////////////////////////////////////////////////////////////////// +// DFT algorithm + +#ifdef HAVE_CUFFT + +namespace +{ + + class DFTImpl : public DFT + { + Size dft_size, dft_size_opt; + bool is_1d_input, is_row_dft, is_scaled_dft, is_inverse, is_complex_input, is_complex_output; + + cufftType dft_type; + cufftHandle plan; + + public: + DFTImpl(Size dft_size, int flags) + : dft_size(dft_size), + dft_size_opt(dft_size), + is_1d_input((dft_size.height == 1) || (dft_size.width == 1)), + is_row_dft((flags & DFT_ROWS) != 0), + is_scaled_dft((flags & DFT_SCALE) != 0), + is_inverse((flags & DFT_INVERSE) != 0), + is_complex_input((flags & DFT_COMPLEX_INPUT) != 0), + is_complex_output(!(flags & DFT_REAL_OUTPUT)), + dft_type(!is_complex_input ? CUFFT_R2C : (is_complex_output ? CUFFT_C2C : CUFFT_C2R)) + { + // We don't support unpacked output (in the case of real input) + CV_Assert( !(flags & DFT_COMPLEX_OUTPUT) ); + + // We don't support real-to-real transform + CV_Assert( is_complex_input || is_complex_output ); + + if (is_1d_input && !is_row_dft) + { + // If the source matrix is single column handle it as single row + dft_size_opt.width = std::max(dft_size.width, dft_size.height); + dft_size_opt.height = std::min(dft_size.width, dft_size.height); + } + + CV_Assert( dft_size_opt.width > 1 ); + + if (is_1d_input || is_row_dft) + cufftSafeCall( cufftPlan1d(&plan, dft_size_opt.width, dft_type, dft_size_opt.height) ); + else + cufftSafeCall( cufftPlan2d(&plan, dft_size_opt.height, dft_size_opt.width, dft_type) ); + } + + ~DFTImpl() + { + cufftSafeCall( cufftDestroy(plan) ); + } + + void compute(InputArray _src, OutputArray _dst, Stream& stream) + { + GpuMat src = getInputMat(_src, stream); + + CV_Assert( src.type() == CV_32FC1 || src.type() == CV_32FC2 ); + CV_Assert( is_complex_input == (src.channels() == 2) ); + + // Make sure here we work with the continuous input, + // as CUFFT can't handle gaps + GpuMat src_cont; + if (src.isContinuous()) + { + src_cont = src; + } + else + { + BufferPool pool(stream); + src_cont.allocator = pool.getAllocator(); + createContinuous(src.rows, src.cols, src.type(), src_cont); + src.copyTo(src_cont, stream); + } + + cufftSafeCall( cufftSetStream(plan, StreamAccessor::getStream(stream)) ); + + if (is_complex_input) + { + if (is_complex_output) + { + createContinuous(dft_size, CV_32FC2, _dst); + GpuMat dst = _dst.getGpuMat(); + + cufftSafeCall(cufftExecC2C( + plan, src_cont.ptr(), dst.ptr(), + is_inverse ? CUFFT_INVERSE : CUFFT_FORWARD)); + } + else + { + createContinuous(dft_size, CV_32F, _dst); + GpuMat dst = _dst.getGpuMat(); + + cufftSafeCall(cufftExecC2R( + plan, src_cont.ptr(), dst.ptr())); + } + } + else + { + // We could swap dft_size for efficiency. Here we must reflect it + if (dft_size == dft_size_opt) + createContinuous(Size(dft_size.width / 2 + 1, dft_size.height), CV_32FC2, _dst); + else + createContinuous(Size(dft_size.width, dft_size.height / 2 + 1), CV_32FC2, _dst); + + GpuMat dst = _dst.getGpuMat(); + + cufftSafeCall(cufftExecR2C( + plan, src_cont.ptr(), dst.ptr())); + } + + if (is_scaled_dft) + cuda::multiply(_dst, Scalar::all(1. / dft_size.area()), _dst, 1, -1, stream); + } + }; +} + +#endif + +Ptr cv::cuda::createDFT(Size dft_size, int flags) +{ +#ifndef HAVE_CUFFT + CV_UNUSED(dft_size); + CV_UNUSED(flags); + CV_Error(Error::StsNotImplemented, "The library was build without CUFFT"); + return Ptr(); +#else + return makePtr(dft_size, flags); +#endif +} + +////////////////////////////////////////////////////////////////////////////// +// Convolution + +#ifdef HAVE_CUFFT + +namespace +{ + class ConvolutionImpl : public Convolution + { + public: + explicit ConvolutionImpl(Size user_block_size_) : user_block_size(user_block_size_) {} + + void convolve(InputArray image, InputArray templ, OutputArray result, bool ccorr = false, Stream& stream = Stream::Null()); + + private: + void create(Size image_size, Size templ_size); + static Size estimateBlockSize(Size result_size); + + Size result_size; + Size block_size; + Size user_block_size; + Size dft_size; + + GpuMat image_spect, templ_spect, result_spect; + GpuMat image_block, templ_block, result_data; + }; + + void ConvolutionImpl::create(Size image_size, Size templ_size) + { + result_size = Size(image_size.width - templ_size.width + 1, + image_size.height - templ_size.height + 1); + + block_size = user_block_size; + if (user_block_size.width == 0 || user_block_size.height == 0) + block_size = estimateBlockSize(result_size); + + dft_size.width = 1 << int(ceil(std::log(block_size.width + templ_size.width - 1.) / std::log(2.))); + dft_size.height = 1 << int(ceil(std::log(block_size.height + templ_size.height - 1.) / std::log(2.))); + + // CUFFT has hard-coded kernels for power-of-2 sizes (up to 8192), + // see CUDA Toolkit 4.1 CUFFT Library Programming Guide + if (dft_size.width > 8192) + dft_size.width = getOptimalDFTSize(block_size.width + templ_size.width - 1); + if (dft_size.height > 8192) + dft_size.height = getOptimalDFTSize(block_size.height + templ_size.height - 1); + + // To avoid wasting time doing small DFTs + dft_size.width = std::max(dft_size.width, 512); + dft_size.height = std::max(dft_size.height, 512); + + createContinuous(dft_size, CV_32F, image_block); + createContinuous(dft_size, CV_32F, templ_block); + createContinuous(dft_size, CV_32F, result_data); + + int spect_len = dft_size.height * (dft_size.width / 2 + 1); + createContinuous(1, spect_len, CV_32FC2, image_spect); + createContinuous(1, spect_len, CV_32FC2, templ_spect); + createContinuous(1, spect_len, CV_32FC2, result_spect); + + // Use maximum result matrix block size for the estimated DFT block size + block_size.width = std::min(dft_size.width - templ_size.width + 1, result_size.width); + block_size.height = std::min(dft_size.height - templ_size.height + 1, result_size.height); + } + + Size ConvolutionImpl::estimateBlockSize(Size result_size) + { + int width = (result_size.width + 2) / 3; + int height = (result_size.height + 2) / 3; + width = std::min(width, result_size.width); + height = std::min(height, result_size.height); + return Size(width, height); + } + + void ConvolutionImpl::convolve(InputArray _image, InputArray _templ, OutputArray _result, bool ccorr, Stream& _stream) + { + GpuMat image = getInputMat(_image, _stream); + GpuMat templ = getInputMat(_templ, _stream); + + CV_Assert( image.type() == CV_32FC1 ); + CV_Assert( templ.type() == CV_32FC1 ); + + create(image.size(), templ.size()); + + GpuMat result = getOutputMat(_result, result_size, CV_32FC1, _stream); + + cudaStream_t stream = StreamAccessor::getStream(_stream); + + cufftHandle planR2C, planC2R; + cufftSafeCall( cufftPlan2d(&planC2R, dft_size.height, dft_size.width, CUFFT_C2R) ); + cufftSafeCall( cufftPlan2d(&planR2C, dft_size.height, dft_size.width, CUFFT_R2C) ); + + cufftSafeCall( cufftSetStream(planR2C, stream) ); + cufftSafeCall( cufftSetStream(planC2R, stream) ); + + GpuMat templ_roi(templ.size(), CV_32FC1, templ.data, templ.step); + cuda::copyMakeBorder(templ_roi, templ_block, 0, templ_block.rows - templ_roi.rows, 0, + templ_block.cols - templ_roi.cols, 0, Scalar(), _stream); + + cufftSafeCall( cufftExecR2C(planR2C, templ_block.ptr(), templ_spect.ptr()) ); + + // Process all blocks of the result matrix + for (int y = 0; y < result.rows; y += block_size.height) + { + for (int x = 0; x < result.cols; x += block_size.width) + { + Size image_roi_size(std::min(x + dft_size.width, image.cols) - x, + std::min(y + dft_size.height, image.rows) - y); + GpuMat image_roi(image_roi_size, CV_32F, (void*)(image.ptr(y) + x), + image.step); + cuda::copyMakeBorder(image_roi, image_block, 0, image_block.rows - image_roi.rows, + 0, image_block.cols - image_roi.cols, 0, Scalar(), _stream); + + cufftSafeCall(cufftExecR2C(planR2C, image_block.ptr(), + image_spect.ptr())); + cuda::mulAndScaleSpectrums(image_spect, templ_spect, result_spect, 0, + 1.f / dft_size.area(), ccorr, _stream); + cufftSafeCall(cufftExecC2R(planC2R, result_spect.ptr(), + result_data.ptr())); + + Size result_roi_size(std::min(x + block_size.width, result.cols) - x, + std::min(y + block_size.height, result.rows) - y); + GpuMat result_roi(result_roi_size, result.type(), + (void*)(result.ptr(y) + x), result.step); + GpuMat result_block(result_roi_size, result_data.type(), + result_data.ptr(), result_data.step); + + result_block.copyTo(result_roi, _stream); + } + } + + cufftSafeCall( cufftDestroy(planR2C) ); + cufftSafeCall( cufftDestroy(planC2R) ); + + syncOutput(result, _result, _stream); + } +} + +#endif + +Ptr cv::cuda::createConvolution(Size user_block_size) +{ +#ifndef HAVE_CUFFT + CV_UNUSED(user_block_size); + CV_Error(Error::StsNotImplemented, "The library was build without CUFFT"); + return Ptr(); +#else + return makePtr(user_block_size); +#endif +} + +#endif /* !defined (HAVE_CUDA) */ diff --git a/modules/cudaarithm/src/core.cpp b/modules/cudaarithm/src/core.cpp new file mode 100644 index 000000000..7dd51f978 --- /dev/null +++ b/modules/cudaarithm/src/core.cpp @@ -0,0 +1,135 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "precomp.hpp" + +using namespace cv; +using namespace cv::cuda; + +#if !defined (HAVE_CUDA) || defined (CUDA_DISABLER) + +void cv::cuda::merge(const GpuMat*, size_t, OutputArray, Stream&) { throw_no_cuda(); } +void cv::cuda::merge(const std::vector&, OutputArray, Stream&) { throw_no_cuda(); } + +void cv::cuda::split(InputArray, GpuMat*, Stream&) { throw_no_cuda(); } +void cv::cuda::split(InputArray, std::vector&, Stream&) { throw_no_cuda(); } + +void cv::cuda::transpose(InputArray, OutputArray, Stream&) { throw_no_cuda(); } + +void cv::cuda::flip(InputArray, OutputArray, int, Stream&) { throw_no_cuda(); } + +Ptr cv::cuda::createLookUpTable(InputArray) { throw_no_cuda(); return Ptr(); } + +void cv::cuda::copyMakeBorder(InputArray, OutputArray, int, int, int, int, int, Scalar, Stream&) { throw_no_cuda(); } + +#else /* !defined (HAVE_CUDA) */ + +//////////////////////////////////////////////////////////////////////// +// flip + +namespace +{ + template struct NppTypeTraits; + template<> struct NppTypeTraits { typedef Npp8u npp_t; }; + template<> struct NppTypeTraits { typedef Npp8s npp_t; }; + template<> struct NppTypeTraits { typedef Npp16u npp_t; }; + template<> struct NppTypeTraits { typedef Npp16s npp_t; }; + template<> struct NppTypeTraits { typedef Npp32s npp_t; }; + template<> struct NppTypeTraits { typedef Npp32f npp_t; }; + template<> struct NppTypeTraits { typedef Npp64f npp_t; }; + + template struct NppMirrorFunc + { + typedef typename NppTypeTraits::npp_t npp_t; + + typedef NppStatus (*func_t)(const npp_t* pSrc, int nSrcStep, npp_t* pDst, int nDstStep, NppiSize oROI, NppiAxis flip); + }; + + template ::func_t func> struct NppMirror + { + typedef typename NppMirrorFunc::npp_t npp_t; + + static void call(const GpuMat& src, GpuMat& dst, int flipCode, cudaStream_t stream) + { + NppStreamHandler h(stream); + + NppiSize sz; + sz.width = src.cols; + sz.height = src.rows; + + nppSafeCall( func(src.ptr(), static_cast(src.step), + dst.ptr(), static_cast(dst.step), sz, + (flipCode == 0 ? NPP_HORIZONTAL_AXIS : (flipCode > 0 ? NPP_VERTICAL_AXIS : NPP_BOTH_AXIS))) ); + + if (stream == 0) + cudaSafeCall( cudaDeviceSynchronize() ); + } + }; +} + +void cv::cuda::flip(InputArray _src, OutputArray _dst, int flipCode, Stream& stream) +{ + typedef void (*func_t)(const GpuMat& src, GpuMat& dst, int flipCode, cudaStream_t stream); + static const func_t funcs[6][4] = + { + {NppMirror::call, 0, NppMirror::call, NppMirror::call}, + {0,0,0,0}, + {NppMirror::call, 0, NppMirror::call, NppMirror::call}, + {0,0,0,0}, + {NppMirror::call, 0, NppMirror::call, NppMirror::call}, + {NppMirror::call, 0, NppMirror::call, NppMirror::call} + }; + + GpuMat src = getInputMat(_src, stream); + + CV_Assert(src.depth() == CV_8U || src.depth() == CV_16U || src.depth() == CV_32S || src.depth() == CV_32F); + CV_Assert(src.channels() == 1 || src.channels() == 3 || src.channels() == 4); + + _dst.create(src.size(), src.type()); + GpuMat dst = getOutputMat(_dst, src.size(), src.type(), stream); + + funcs[src.depth()][src.channels() - 1](src, dst, flipCode, StreamAccessor::getStream(stream)); + + syncOutput(dst, _dst, stream); +} + +#endif /* !defined (HAVE_CUDA) */ diff --git a/modules/cudaarithm/src/cuda/absdiff_mat.cu b/modules/cudaarithm/src/cuda/absdiff_mat.cu new file mode 100644 index 000000000..ec04f1228 --- /dev/null +++ b/modules/cudaarithm/src/cuda/absdiff_mat.cu @@ -0,0 +1,188 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "opencv2/opencv_modules.hpp" + +#ifndef HAVE_OPENCV_CUDEV + +#error "opencv_cudev is required" + +#else + +#include "opencv2/cudev.hpp" + +using namespace cv::cudev; + +void absDiffMat(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat&, double, Stream& stream, int); + +namespace +{ + __device__ __forceinline__ int _abs(int a) + { + return ::abs(a); + } + __device__ __forceinline__ float _abs(float a) + { + return ::fabsf(a); + } + __device__ __forceinline__ double _abs(double a) + { + return ::fabs(a); + } + + template struct AbsDiffOp1 : binary_function + { + __device__ __forceinline__ T operator ()(T a, T b) const + { + return saturate_cast(_abs(a - b)); + } + }; + + template struct TransformPolicy : DefaultTransformPolicy + { + }; + template <> struct TransformPolicy : DefaultTransformPolicy + { + enum { + shift = 1 + }; + }; + + template + void absDiffMat_v1(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, Stream& stream) + { + gridTransformBinary_< TransformPolicy >(globPtr(src1), globPtr(src2), globPtr(dst), AbsDiffOp1(), stream); + } + + struct AbsDiffOp2 : binary_function + { + __device__ __forceinline__ uint operator ()(uint a, uint b) const + { + return vabsdiff2(a, b); + } + }; + + void absDiffMat_v2(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, Stream& stream) + { + const int vcols = src1.cols >> 1; + + GlobPtrSz src1_ = globPtr((uint*) src1.data, src1.step, src1.rows, vcols); + GlobPtrSz src2_ = globPtr((uint*) src2.data, src2.step, src1.rows, vcols); + GlobPtrSz dst_ = globPtr((uint*) dst.data, dst.step, src1.rows, vcols); + + gridTransformBinary(src1_, src2_, dst_, AbsDiffOp2(), stream); + } + + struct AbsDiffOp4 : binary_function + { + __device__ __forceinline__ uint operator ()(uint a, uint b) const + { + return vabsdiff4(a, b); + } + }; + + void absDiffMat_v4(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, Stream& stream) + { + const int vcols = src1.cols >> 2; + + GlobPtrSz src1_ = globPtr((uint*) src1.data, src1.step, src1.rows, vcols); + GlobPtrSz src2_ = globPtr((uint*) src2.data, src2.step, src1.rows, vcols); + GlobPtrSz dst_ = globPtr((uint*) dst.data, dst.step, src1.rows, vcols); + + gridTransformBinary(src1_, src2_, dst_, AbsDiffOp4(), stream); + } +} + +void absDiffMat(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat&, double, Stream& stream, int) +{ + typedef void (*func_t)(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, Stream& stream); + static const func_t funcs[] = + { + absDiffMat_v1, + absDiffMat_v1, + absDiffMat_v1, + absDiffMat_v1, + absDiffMat_v1, + absDiffMat_v1, + absDiffMat_v1 + }; + + const int depth = src1.depth(); + + CV_DbgAssert( depth <= CV_64F ); + + GpuMat src1_ = src1.reshape(1); + GpuMat src2_ = src2.reshape(1); + GpuMat dst_ = dst.reshape(1); + + if (depth == CV_8U || depth == CV_16U) + { + const intptr_t src1ptr = reinterpret_cast(src1_.data); + const intptr_t src2ptr = reinterpret_cast(src2_.data); + const intptr_t dstptr = reinterpret_cast(dst_.data); + + const bool isAllAligned = (src1ptr & 31) == 0 && (src2ptr & 31) == 0 && (dstptr & 31) == 0; + + if (isAllAligned) + { + if (depth == CV_8U && (src1_.cols & 3) == 0) + { + absDiffMat_v4(src1_, src2_, dst_, stream); + return; + } + else if (depth == CV_16U && (src1_.cols & 1) == 0) + { + absDiffMat_v2(src1_, src2_, dst_, stream); + return; + } + } + } + + const func_t func = funcs[depth]; + + if (!func) + CV_Error(cv::Error::StsUnsupportedFormat, "Unsupported combination of source and destination types"); + + func(src1_, src2_, dst_, stream); +} + +#endif diff --git a/modules/cudaarithm/src/cuda/absdiff_scalar.cu b/modules/cudaarithm/src/cuda/absdiff_scalar.cu new file mode 100644 index 000000000..0955e40c8 --- /dev/null +++ b/modules/cudaarithm/src/cuda/absdiff_scalar.cu @@ -0,0 +1,133 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "opencv2/opencv_modules.hpp" + +#ifndef HAVE_OPENCV_CUDEV + +#error "opencv_cudev is required" + +#else + +#include "opencv2/cudev.hpp" + +using namespace cv::cudev; + +void absDiffScalar(const GpuMat& src, cv::Scalar val, bool, GpuMat& dst, const GpuMat&, double, Stream& stream, int); + +namespace +{ + template struct AbsDiffScalarOp : unary_function + { + ScalarType val; + + __device__ __forceinline__ DstType operator ()(SrcType a) const + { + abs_func f; + return saturate_cast(f(saturate_cast(a) - val)); + } + }; + + template struct TransformPolicy : DefaultTransformPolicy + { + }; + template <> struct TransformPolicy : DefaultTransformPolicy + { + enum { + shift = 1 + }; + }; + + template + void absDiffScalarImpl(const GpuMat& src, cv::Scalar value, GpuMat& dst, Stream& stream) + { + typedef typename MakeVec::cn>::type ScalarType; + + cv::Scalar_ value_ = value; + + AbsDiffScalarOp op; + op.val = VecTraits::make(value_.val); + gridTransformUnary_< TransformPolicy >(globPtr(src), globPtr(dst), op, stream); + } +} + +void absDiffScalar(const GpuMat& src, cv::Scalar val, bool, GpuMat& dst, const GpuMat&, double, Stream& stream, int) +{ + typedef void (*func_t)(const GpuMat& src, cv::Scalar val, GpuMat& dst, Stream& stream); + static const func_t funcs[7][4] = + { + { + absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl + }, + { + absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl + }, + { + absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl + }, + { + absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl + }, + { + absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl + }, + { + absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl + }, + { + absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl, absDiffScalarImpl + } + }; + + const int sdepth = src.depth(); + const int cn = src.channels(); + + CV_DbgAssert( sdepth <= CV_64F && cn <= 4 && src.type() == dst.type()); + + const func_t func = funcs[sdepth][cn - 1]; + if (!func) + CV_Error(cv::Error::StsUnsupportedFormat, "Unsupported combination of source and destination types"); + + func(src, val, dst, stream); +} + +#endif diff --git a/modules/cudaarithm/src/cuda/add_mat.cu b/modules/cudaarithm/src/cuda/add_mat.cu new file mode 100644 index 000000000..4166cc104 --- /dev/null +++ b/modules/cudaarithm/src/cuda/add_mat.cu @@ -0,0 +1,225 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "opencv2/opencv_modules.hpp" + +#ifndef HAVE_OPENCV_CUDEV + +#error "opencv_cudev is required" + +#else + +#include "opencv2/cudev.hpp" + +using namespace cv::cudev; + +void addMat(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask, double, Stream& _stream, int); + +namespace +{ + template struct AddOp1 : binary_function + { + __device__ __forceinline__ D operator ()(T a, T b) const + { + return saturate_cast(a + b); + } + }; + + template + void addMat_v1(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask, Stream& stream) + { + if (mask.data) + gridTransformBinary(globPtr(src1), globPtr(src2), globPtr(dst), AddOp1(), globPtr(mask), stream); + else + gridTransformBinary(globPtr(src1), globPtr(src2), globPtr(dst), AddOp1(), stream); + } + + struct AddOp2 : binary_function + { + __device__ __forceinline__ uint operator ()(uint a, uint b) const + { + return vadd2(a, b); + } + }; + + void addMat_v2(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, Stream& stream) + { + const int vcols = src1.cols >> 1; + + GlobPtrSz src1_ = globPtr((uint*) src1.data, src1.step, src1.rows, vcols); + GlobPtrSz src2_ = globPtr((uint*) src2.data, src2.step, src1.rows, vcols); + GlobPtrSz dst_ = globPtr((uint*) dst.data, dst.step, src1.rows, vcols); + + gridTransformBinary(src1_, src2_, dst_, AddOp2(), stream); + } + + struct AddOp4 : binary_function + { + __device__ __forceinline__ uint operator ()(uint a, uint b) const + { + return vadd4(a, b); + } + }; + + void addMat_v4(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, Stream& stream) + { + const int vcols = src1.cols >> 2; + + GlobPtrSz src1_ = globPtr((uint*) src1.data, src1.step, src1.rows, vcols); + GlobPtrSz src2_ = globPtr((uint*) src2.data, src2.step, src1.rows, vcols); + GlobPtrSz dst_ = globPtr((uint*) dst.data, dst.step, src1.rows, vcols); + + gridTransformBinary(src1_, src2_, dst_, AddOp4(), stream); + } +} + +void addMat(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask, double, Stream& stream, int) +{ + typedef void (*func_t)(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask, Stream& stream); + static const func_t funcs[7][7] = + { + { + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1 + }, + { + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1 + }, + { + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1 + }, + { + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1, + addMat_v1 + }, + { + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + addMat_v1, + addMat_v1, + addMat_v1 + }, + { + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + addMat_v1, + addMat_v1 + }, + { + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + 0 /*addMat_v1*/, + addMat_v1 + } + }; + + const int sdepth = src1.depth(); + const int ddepth = dst.depth(); + + CV_DbgAssert( sdepth <= CV_64F && ddepth <= CV_64F ); + + GpuMat src1_ = src1.reshape(1); + GpuMat src2_ = src2.reshape(1); + GpuMat dst_ = dst.reshape(1); + + if (mask.empty() && (sdepth == CV_8U || sdepth == CV_16U) && ddepth == sdepth) + { + const intptr_t src1ptr = reinterpret_cast(src1_.data); + const intptr_t src2ptr = reinterpret_cast(src2_.data); + const intptr_t dstptr = reinterpret_cast(dst_.data); + + const bool isAllAligned = (src1ptr & 31) == 0 && (src2ptr & 31) == 0 && (dstptr & 31) == 0; + + if (isAllAligned) + { + if (sdepth == CV_8U && (src1_.cols & 3) == 0) + { + addMat_v4(src1_, src2_, dst_, stream); + return; + } + else if (sdepth == CV_16U && (src1_.cols & 1) == 0) + { + addMat_v2(src1_, src2_, dst_, stream); + return; + } + } + } + + const func_t func = funcs[sdepth][ddepth]; + + if (!func) + CV_Error(cv::Error::StsUnsupportedFormat, "Unsupported combination of source and destination types"); + + func(src1_, src2_, dst_, mask, stream); +} + +#endif diff --git a/modules/cudaarithm/src/cuda/add_scalar.cu b/modules/cudaarithm/src/cuda/add_scalar.cu new file mode 100644 index 000000000..92838a2a5 --- /dev/null +++ b/modules/cudaarithm/src/cuda/add_scalar.cu @@ -0,0 +1,180 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "opencv2/opencv_modules.hpp" + +#ifndef HAVE_OPENCV_CUDEV + +#error "opencv_cudev is required" + +#else + +#include "opencv2/cudev.hpp" + +using namespace cv::cudev; + +void addScalar(const GpuMat& src, cv::Scalar val, bool, GpuMat& dst, const GpuMat& mask, double, Stream& stream, int); + +namespace +{ + template struct AddScalarOp : unary_function + { + ScalarType val; + + __device__ __forceinline__ DstType operator ()(SrcType a) const + { + return saturate_cast(saturate_cast(a) + val); + } + }; + + template struct TransformPolicy : DefaultTransformPolicy + { + }; + template <> struct TransformPolicy : DefaultTransformPolicy + { + enum { + shift = 1 + }; + }; + + template + void addScalarImpl(const GpuMat& src, cv::Scalar value, GpuMat& dst, const GpuMat& mask, Stream& stream) + { + typedef typename MakeVec::cn>::type ScalarType; + + cv::Scalar_ value_ = value; + + AddScalarOp op; + op.val = VecTraits::make(value_.val); + + if (mask.data) + gridTransformUnary_< TransformPolicy >(globPtr(src), globPtr(dst), op, globPtr(mask), stream); + else + gridTransformUnary_< TransformPolicy >(globPtr(src), globPtr(dst), op, stream); + } +} + +void addScalar(const GpuMat& src, cv::Scalar val, bool, GpuMat& dst, const GpuMat& mask, double, Stream& stream, int) +{ + typedef void (*func_t)(const GpuMat& src, cv::Scalar val, GpuMat& dst, const GpuMat& mask, Stream& stream); + static const func_t funcs[7][7][4] = + { + { + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl} + }, + { + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl} + }, + { + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl} + }, + { + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl} + }, + { + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl} + }, + { + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl} + }, + { + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/, 0 /*addScalarImpl*/}, + {addScalarImpl, addScalarImpl, addScalarImpl, addScalarImpl} + } + }; + + const int sdepth = src.depth(); + const int ddepth = dst.depth(); + const int cn = src.channels(); + + CV_DbgAssert( sdepth <= CV_64F && ddepth <= CV_64F && cn <= 4 ); + + const func_t func = funcs[sdepth][ddepth][cn - 1]; + + if (!func) + CV_Error(cv::Error::StsUnsupportedFormat, "Unsupported combination of source and destination types"); + + func(src, val, dst, mask, stream); +} + +#endif diff --git a/modules/cudaarithm/src/cuda/add_weighted.cu b/modules/cudaarithm/src/cuda/add_weighted.cu new file mode 100644 index 000000000..929301076 --- /dev/null +++ b/modules/cudaarithm/src/cuda/add_weighted.cu @@ -0,0 +1,596 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "opencv2/opencv_modules.hpp" + +#ifndef HAVE_OPENCV_CUDEV + +#error "opencv_cudev is required" + +#else + +#include "opencv2/cudaarithm.hpp" +#include "opencv2/cudev.hpp" +#include "opencv2/core/private.cuda.hpp" + +using namespace cv; +using namespace cv::cuda; +using namespace cv::cudev; + +namespace +{ + template struct AddWeightedOp : binary_function + { + S alpha; + S beta; + S gamma; + + __device__ __forceinline__ D operator ()(T1 a, T2 b) const + { + return cudev::saturate_cast(a * alpha + b * beta + gamma); + } + }; + + template struct TransformPolicy : DefaultTransformPolicy + { + }; + template <> struct TransformPolicy : DefaultTransformPolicy + { + enum { + shift = 1 + }; + }; + + template + void addWeightedImpl(const GpuMat& src1, double alpha, const GpuMat& src2, double beta, double gamma, GpuMat& dst, Stream& stream) + { + typedef typename LargerType::type larger_type1; + typedef typename LargerType::type larger_type2; + typedef typename LargerType::type scalar_type; + + AddWeightedOp op; + op.alpha = static_cast(alpha); + op.beta = static_cast(beta); + op.gamma = static_cast(gamma); + + gridTransformBinary_< TransformPolicy >(globPtr(src1), globPtr(src2), globPtr(dst), op, stream); + } +} + +void cv::cuda::addWeighted(InputArray _src1, double alpha, InputArray _src2, double beta, double gamma, OutputArray _dst, int ddepth, Stream& stream) +{ + typedef void (*func_t)(const GpuMat& src1, double alpha, const GpuMat& src2, double beta, double gamma, GpuMat& dst, Stream& stream); + static const func_t funcs[7][7][7] = + { + { + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + } + }, + { + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + } + }, + { + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + } + }, + { + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + } + }, + { + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + } + }, + { + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + } + }, + { + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/, + 0/*addWeightedImpl*/ + }, + { + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl, + addWeightedImpl + } + } + }; + + GpuMat src1 = getInputMat(_src1, stream); + GpuMat src2 = getInputMat(_src2, stream); + + int sdepth1 = src1.depth(); + int sdepth2 = src2.depth(); + + ddepth = ddepth >= 0 ? CV_MAT_DEPTH(ddepth) : std::max(sdepth1, sdepth2); + const int cn = src1.channels(); + + CV_Assert( src2.size() == src1.size() && src2.channels() == cn ); + CV_Assert( sdepth1 <= CV_64F && sdepth2 <= CV_64F && ddepth <= CV_64F ); + + GpuMat dst = getOutputMat(_dst, src1.size(), CV_MAKE_TYPE(ddepth, cn), stream); + + GpuMat src1_single = src1.reshape(1); + GpuMat src2_single = src2.reshape(1); + GpuMat dst_single = dst.reshape(1); + + if (sdepth1 > sdepth2) + { + src1_single.swap(src2_single); + std::swap(alpha, beta); + std::swap(sdepth1, sdepth2); + } + + const func_t func = funcs[sdepth1][sdepth2][ddepth]; + + if (!func) + CV_Error(cv::Error::StsUnsupportedFormat, "Unsupported combination of source and destination types"); + + func(src1_single, alpha, src2_single, beta, gamma, dst_single, stream); + + syncOutput(dst, _dst, stream); +} + +#endif diff --git a/modules/cudaarithm/src/cuda/bitwise_mat.cu b/modules/cudaarithm/src/cuda/bitwise_mat.cu new file mode 100644 index 000000000..f151c1a48 --- /dev/null +++ b/modules/cudaarithm/src/cuda/bitwise_mat.cu @@ -0,0 +1,230 @@ +/*M/////////////////////////////////////////////////////////////////////////////////////// +// +// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING. +// +// By downloading, copying, installing or using the software you agree to this license. +// If you do not agree to this license, do not download, install, +// copy or use the software. +// +// +// License Agreement +// For Open Source Computer Vision Library +// +// Copyright (C) 2000-2008, Intel Corporation, all rights reserved. +// Copyright (C) 2009, Willow Garage Inc., all rights reserved. +// Third party copyrights are property of their respective owners. +// +// Redistribution and use in source and binary forms, with or without modification, +// are permitted provided that the following conditions are met: +// +// * Redistribution's of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// +// * Redistribution's in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// * The name of the copyright holders may not be used to endorse or promote products +// derived from this software without specific prior written permission. +// +// This software is provided by the copyright holders and contributors "as is" and +// any express or implied warranties, including, but not limited to, the implied +// warranties of merchantability and fitness for a particular purpose are disclaimed. +// In no event shall the Intel Corporation or contributors be liable for any direct, +// indirect, incidental, special, exemplary, or consequential damages +// (including, but not limited to, procurement of substitute goods or services; +// loss of use, data, or profits; or business interruption) however caused +// and on any theory of liability, whether in contract, strict liability, +// or tort (including negligence or otherwise) arising in any way out of +// the use of this software, even if advised of the possibility of such damage. +// +//M*/ + +#include "opencv2/opencv_modules.hpp" + +#ifndef HAVE_OPENCV_CUDEV + +#error "opencv_cudev is required" + +#else + +#include "opencv2/cudaarithm.hpp" +#include "opencv2/cudev.hpp" +#include "opencv2/core/private.cuda.hpp" + +using namespace cv; +using namespace cv::cuda; +using namespace cv::cudev; + +void bitMat(const GpuMat& src1, const GpuMat& src2, GpuMat& dst, const GpuMat& mask, double, Stream& stream, int op); + +////////////////////////////////////////////////////////////////////////////// +/// bitwise_not + +void cv::cuda::bitwise_not(InputArray _src, OutputArray _dst, InputArray _mask, Stream& stream) +{ + GpuMat src = getInputMat(_src, stream); + GpuMat mask = getInputMat(_mask, stream); + + const int depth = src.depth(); + + CV_DbgAssert( depth <= CV_32F ); + CV_DbgAssert( mask.empty() || (mask.type() == CV_8UC1 && mask.size() == src.size()) ); + + GpuMat dst = getOutputMat(_dst, src.size(), src.type(), stream); + + if (mask.empty()) + { + const int bcols = (int) (src.cols * src.elemSize()); + + if ((bcols & 3) == 0) + { + const int vcols = bcols >> 2; + + GlobPtrSz vsrc = globPtr((uint*) src.data, src.step, src.rows, vcols); + GlobPtrSz vdst = globPtr((uint*) dst.data, dst.step, src.rows, vcols); + + gridTransformUnary(vsrc, vdst, bit_not(), stream); + } + else if ((bcols & 1) == 0) + { + const int vcols = bcols >> 1; + + GlobPtrSz vsrc = globPtr((ushort*) src.data, src.step, src.rows, vcols); + GlobPtrSz vdst = globPtr((ushort*) dst.data, dst.step, src.rows, vcols); + + gridTransformUnary(vsrc, vdst, bit_not(), stream); + } + else + { + GlobPtrSz vsrc = globPtr((uchar*) src.data, src.step, src.rows, bcols); + GlobPtrSz vdst = globPtr((uchar*) dst.data, dst.step, src.rows, bcols); + + gridTransformUnary(vsrc, vdst, bit_not(), stream); + } + } + else + { + if (depth == CV_32F || depth == CV_32S) + { + GlobPtrSz vsrc = globPtr((uint*) src.data, src.step, src.rows, src.cols * src.channels()); + GlobPtrSz vdst = globPtr((uint*) dst.data, dst.step, src.rows, src.cols * src.channels()); + + gridTransformUnary(vsrc, vdst, bit_not(), singleMaskChannels(globPtr(mask), src.channels()), stream); + } + else if (depth == CV_16S || depth == CV_16U) + { + GlobPtrSz vsrc = globPtr((ushort*) src.data, src.step, src.rows, src.cols * src.channels()); + GlobPtrSz vdst = globPtr((ushort*) dst.data, dst.step, src.rows, src.cols * src.channels()); + + gridTransformUnary(vsrc, vdst, bit_not(), singleMaskChannels(globPtr(mask), src.channels()), stream); + } + else + { + GlobPtrSz vsrc = globPtr((uchar*) src.data, src.step, src.rows, src.cols * src.channels()); + GlobPtrSz vdst = globPtr((uchar*) dst.data, dst.step, src.rows, src.cols * src.channels()); + + gridTransformUnary(vsrc, vdst, bit_not(), singleMaskChannels(globPtr(mask), src.channels()), stream); + } + } + + syncOutput(dst, _dst, stream); +} + +////////////////////////////////////////////////////////////////////////////// +/// Binary bitwise logical operations + +namespace +{ + template