From 2f4ec4f8c9faaf5ca0a8c4ae113d414f15cc334c Mon Sep 17 00:00:00 2001 From: Lunkhound Date: Sat, 12 Nov 2016 12:41:55 -0800 Subject: [PATCH 01/39] collisionObject: renamed uniqueId to worldArrayIndex; removed linear search in removeCollisionObject --- .../CollisionDispatch/btCollisionObject.cpp | 1 + .../CollisionDispatch/btCollisionObject.h | 11 ++++---- .../CollisionDispatch/btCollisionWorld.cpp | 25 ++++++++++++++++--- .../btSequentialImpulseConstraintSolver.cpp | 2 +- .../Dynamics/btDiscreteDynamicsWorldMt.cpp | 6 ----- .../Dynamics/btDiscreteDynamicsWorldMt.h | 2 -- 6 files changed, 30 insertions(+), 17 deletions(-) diff --git a/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp b/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp index 25cefb11f..fdecac162 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionObject.cpp @@ -28,6 +28,7 @@ btCollisionObject::btCollisionObject() m_collisionFlags(btCollisionObject::CF_STATIC_OBJECT), m_islandTag1(-1), m_companionId(-1), + m_worldArrayIndex(-1), m_activationState1(1), m_deactivationTime(btScalar(0.)), m_friction(btScalar(0.5)), diff --git a/src/BulletCollision/CollisionDispatch/btCollisionObject.h b/src/BulletCollision/CollisionDispatch/btCollisionObject.h index 11491e41f..c285a83fb 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionObject.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionObject.h @@ -79,7 +79,7 @@ protected: int m_islandTag1; int m_companionId; - int m_uniqueId; + int m_worldArrayIndex; // index of object in world's collisionObjects array mutable int m_activationState1; mutable btScalar m_deactivationTime; @@ -456,14 +456,15 @@ public: m_companionId = id; } - SIMD_FORCE_INLINE int getUniqueId() const + SIMD_FORCE_INLINE int getWorldArrayIndex() const { - return m_uniqueId; + return m_worldArrayIndex; } - void setUniqueId( int id ) + // only should be called by CollisionWorld + void setWorldArrayIndex(int ix) { - m_uniqueId = id; + m_worldArrayIndex = ix; } SIMD_FORCE_INLINE btScalar getHitFraction() const diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp index ea7dc86c4..3196369e1 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp @@ -115,7 +115,9 @@ void btCollisionWorld::addCollisionObject(btCollisionObject* collisionObject,sho //check that the object isn't already added btAssert( m_collisionObjects.findLinearSearch(collisionObject) == m_collisionObjects.size()); + btAssert(collisionObject->getWorldArrayIndex() == -1); // do not add the same object to more than one collision world + collisionObject->setWorldArrayIndex(m_collisionObjects.size()); m_collisionObjects.push_back(collisionObject); //calculate new AABB @@ -195,6 +197,7 @@ void btCollisionWorld::updateAabbs() for ( int i=0;igetWorldArrayIndex() == i); //only update aabb of active objects if (m_forceUpdateAllAabbs || colObj->isActive()) @@ -253,9 +256,25 @@ void btCollisionWorld::removeCollisionObject(btCollisionObject* collisionObject) } - //swapremove - m_collisionObjects.remove(collisionObject); - + int iObj = collisionObject->getWorldArrayIndex(); + btAssert(iObj >= 0 && iObj < m_collisionObjects.size()); // trying to remove an object that was never added or already removed previously? + if (iObj >= 0 && iObj < m_collisionObjects.size()) + { + btAssert(collisionObject == m_collisionObjects[iObj]); + m_collisionObjects.swap(iObj, m_collisionObjects.size()-1); + m_collisionObjects.pop_back(); + if (iObj < m_collisionObjects.size()) + { + m_collisionObjects[iObj]->setWorldArrayIndex(iObj); + } + } + else + { + // slow linear search + //swapremove + m_collisionObjects.remove(collisionObject); + } + collisionObject->setWorldArrayIndex(-1); } diff --git a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp index 988fd2459..caf0258a4 100644 --- a/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp +++ b/src/BulletDynamics/ConstraintSolver/btSequentialImpulseConstraintSolver.cpp @@ -751,7 +751,7 @@ int btSequentialImpulseConstraintSolver::getOrInitSolverBody(btCollisionObject& // Kinematic bodies can be in multiple islands at once, so it is a // race condition to write to them, so we use an alternate method // to record the solverBodyId - int uniqueId = body.getUniqueId(); + int uniqueId = body.getWorldArrayIndex(); const int INVALID_SOLVER_BODY_ID = -1; if (uniqueId >= m_kinematicBodyUniqueIdToSolverBodyTable.size()) { diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp index 5f4aaa4db..5e51a994c 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.cpp @@ -149,7 +149,6 @@ void btDiscreteDynamicsWorldMt::solveConstraints(btContactSolverInfo& solverInfo { BT_PROFILE("solveConstraints"); - m_solverIslandCallbackMt->setup(&solverInfo, getDebugDrawer()); m_constraintSolver->prepareSolve(getCollisionWorld()->getNumCollisionObjects(), getCollisionWorld()->getDispatcher()->getNumManifolds()); @@ -161,8 +160,3 @@ void btDiscreteDynamicsWorldMt::solveConstraints(btContactSolverInfo& solverInfo } -void btDiscreteDynamicsWorldMt::addCollisionObject(btCollisionObject* collisionObject, short int collisionFilterGroup, short int collisionFilterMask) -{ - collisionObject->setUniqueId(m_collisionObjects.size()); - btDiscreteDynamicsWorld::addCollisionObject(collisionObject, collisionFilterGroup, collisionFilterMask); -} diff --git a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h index af40129b8..b28371b51 100644 --- a/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h +++ b/src/BulletDynamics/Dynamics/btDiscreteDynamicsWorldMt.h @@ -35,8 +35,6 @@ protected: public: BT_DECLARE_ALIGNED_ALLOCATOR(); - virtual void addCollisionObject(btCollisionObject* collisionObject,short int collisionFilterGroup=btBroadphaseProxy::StaticFilter,short int collisionFilterMask=btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter); - btDiscreteDynamicsWorldMt(btDispatcher* dispatcher,btBroadphaseInterface* pairCache,btConstraintSolver* constraintSolver,btCollisionConfiguration* collisionConfiguration); virtual ~btDiscreteDynamicsWorldMt(); }; From 8c69fa13cab52c178d343348a9a14717173be520 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Thu, 17 Nov 2016 15:15:52 -0800 Subject: [PATCH 02/39] add pybullet getCameraImage, replacing renderImage, cleaner API: always pass in width, hight and viewMatrix, projectionMatrix, optionally lightDir added helper methods computeViewMatrix, computeViewMatrixFromYawPitchRoll, computeProjectionMatrix, computeProjectionMatrixFOV see Bullet/examples/pybullet/testrender.py + testrender_np.py for example use add missing base_link.stl for husky.urdf --- data/husky/meshes/base_link.stl | Bin 0 -> 60484 bytes examples/SharedMemory/PhysicsClientC_API.cpp | 377 +++++++++-------- examples/SharedMemory/PhysicsClientC_API.h | 24 +- .../PhysicsServerCommandProcessor.cpp | 4 + examples/SharedMemory/SharedMemoryCommands.h | 2 + .../TinyRendererVisualShapeConverter.cpp | 40 +- .../TinyRendererVisualShapeConverter.h | 3 +- examples/pybullet/pybullet.c | 397 ++++++++++++++++-- examples/pybullet/test.py | 2 +- examples/pybullet/testrender.py | 37 +- examples/pybullet/testrender_np.py | 39 +- 11 files changed, 664 insertions(+), 261 deletions(-) create mode 100644 data/husky/meshes/base_link.stl diff --git a/data/husky/meshes/base_link.stl b/data/husky/meshes/base_link.stl new file mode 100644 index 0000000000000000000000000000000000000000..db63bd20f234bd73aa0a8fd8f243b96480296e26 GIT binary patch literal 60484 zcmb6CWtbGl_dX6c!4~)6u(&U}3%fI2g zcXua&V8Q;Us%DzI`Q~?B&$BO}uRiClQ+29NRn6({x~mQ8)4Sh*&Ygn0^y}R#xN^_V zKXvNduSA)U@)d#$_aE3HxKt72|F6HDi43E}rMp`+DAsCLY>PNhq>)&ip@BzUmns^r zu7^$AAR-r45NqhZVZ59;+5B;Pt+)}LW32JrHnHRr%d^r)xaZPZbuDr}s^B36BLvfk zp7Yn6(#8+zVl0$=jo6(rU}H(K&g}Zw5xxxXhsatnsulCsiczho+!OIwl3`>%*q!z7 zIKuR7*9cj6spUrp+QGiqkTp7xJm+S^h*h-;NDv{t5b%gKrKLTEGBBbuA<@w4;1WNpM z51?%yN`1qqdFu1B|3KJU&OV=M)GM90ja%73iQiYshO+KTelm;&dX$(nO1Qr!Vq)~2l=3>z|9-T{7k4nFF1>e=6sf7@d`i2GA{q5s?@0$H z`>zFEr<6Vn+;<{S@*fC=)`$sy8~zqDs?}t9Eqn7u{X>&wNrCJCi;#6EE!hq=`ed8@ z2z6g0#`tZZ1QB#CdsBHtBaZ(!!q)P)&)<$NcQc4)i^o;C+#s5dt*v8wU4sM>^QLu~4j7Y>5T8HCaFied+h-Wl zx(_lgqfuhd$A&Q{$+zP0;YeO@ zY(asN0NOA#Le9JIKhK~ZESqhD81`L%>zi_U86xC$K#O(;_WEcTO-nBnhpY6m(oJr~ zP=biSjA|G&$wpARrDDtMt~@-$&kR?~88mClwYF-Mw9bq-(2p0Hcf7ioo`LK|JU+YCF~)wGeF>9c~-t{#Ic1~EA)tAoL{qs&8d1M^nUBU93_ZAFX)!bSuQ%wxG>p+a-~o9 zF4$di(kA=bS*!6GFUnnvib0eh0&DB^F4m-S>&+@Al9N63f??E;j<&LIoaPz%AvHrS ztf3RJ{&kF1WmfIDxY857C_x0))-d8v#PH=I4J!qo0K_{+FD zSiQgwtO>S>`dqh<<`^5H#xDAVMvU^PjBWIxigQkJ9^sF3+gGTCXv3g5=M?Ah{y4W0 zsP+F_t!R{}TKVI{uAyQ4HToL;N{zLi))*jXQEh`-DE%Y%b25U_Bf8~srp|YMR2WJS zK_k&ds~F@IgD!sz+BHE0w#hIk206uGxIYH%`XT~rYZwcc$5@*OMpfwOYGGonuqN0~ zhOxvLYSr2{#T8ZmdxjE3px^8m+~kizyM?HQXj*GWMe*-*jq)`vnVkg>juuUh$Fi)g z5}8kDMvLb^jb#7cOli(aK3s&;{o^e%&~N#hPloZ1l~%fc{i7UP)HPb%m_3yZ4NYR+ z?iDS5F7h+`rGG+mRP=D+qiZuqc0#;-9L0+bENoU@n8krWtrK&j#mqxfm?)Ww5a#CL z{9M~R-cIfJn^>!7 zhLNjzUtVcQLeqG^T43F;J&6`YvQK5nzklU^RXs+WqITSTa>Y$+E$_k)U0)P;9TYvrvMF!bL`k=G3Oqn-5USL;L>B()^mh zyjyIb1A$tR9Y>4xt4)(K&|V&#;IDJFZqEGkM=}a6CbbemP?#R zpac>9+mBN=R`-`9@k+`_YwnVr?)jH~WQahmkAuf58$V9YMTpCBt*o$F3%u=~CE_SS zgzF#O@>eB-330E>DKU2X?)W(!x;qf4^>ooFRjXPv3lrk>3roBhyUmrUaW4k~wX(e) zscKd2ZV^J1s29dg6ddhscView2_i~ej8!)JOv_J*sxNM{4xvlk?TUAHAW#b<*f6#y zufjWRJnx;qt^h{~BAj!{qM3vE;0}d7A@e3MM4%SVM268V=@4EcTb&&RCPq6DsO6kX z3RjBeSHfxwG=mt`qx7YjqNjxot~k*$e3FZGndvAtNTZbyT637 zQuh;@ST5FCSIa-J<$C3==c<-)!#q8>?mgg=BEEj9&YmNtOFsC_zNNMPn4A&XTi)_-kZ2>zfDFyq9A_EtDXlP}^~;RuN;~5~6M9M%MTW zk6r((n%;pxt%GgGDI2%rJ`!Th+u_!#>XYKPb>3m31QEHjXd6f7%8{6+&M+&@oSbeW zPZfp;)N17$t85I~n1v9Bd=;$4u0fu@orL&sP*;aBst51N+>G$kpMhLX>K-A`ESy7NQNqQ!#|4+Yo7`O_)}o z7S_r+`z-f$@J($JWvwfdkD&w+81shF_;83A*mw+USiQd`_X*WYG-P9F|A7%KcLVai z-ZRXvIY$f~JWKT6*3Ci*A~2c_V`ZiqR=SzXSnK)89SGFINTZ!)y*$>DkObC&Z!pXMTnfL|`-<#>F%B zt+y8zu?q`7I1s2M_YcyB-evS0QostjFjb`eGnAtQ5g5(1;tUm{=8%i5Q?14h1Zv6s zgS4UdB^yS!bJtFAOPpEXnWF>|82^UhdsUhh-`AG$8v`8()ROxLX+!Tzs(%~CPZq2# z?r$m1QGy6(ocB1(_<{LnC`4ea(5e;`D!Tr7%G2WYFtu_PWwB~a#d0yy3}Z{^ zBGD}OGgpbadaVs0P)kOaysy{VAI?QsJ&Vlse4?E`N)Ul@V;F^Lt!3LkyPEjd+CW*T zC1XY2*K6&wBT-hFaon3QMIM0?L|~-RFZvq8tgt!UJ|VkNrMv;;)lgiJk5bMp49UT2$UcKM|w}!scoSI5g04gKWT(>i!0vt9=S2-K3%CGYEX@H<)uhpxTJ8u{13fCLdTR^)xX4mPB9ux^!P zR*@Zg9Slei;f%r7v<~jLxQHcQtk=N+0<~nU$oqO7>`Lq43t9*79oOq%K!ONo3|5I0 zA}y_hfBM(K00OmStjPO%9qc}?ojXOMTcUt}9Slei;f%q4|CDA!X&tQYUk3vS)RNI9 z@9TAN)uXa}L`Wr3drnEUss$v7z_>Atm?V{XM$dWk@}Kz~2-Lz~-iDE6ZGZmi<`8kW z6=x_x1V)-+Y@j^c55->i@^#AQK%ka0C7Z7wHZL}5!$-J2I1s3XzZvLPYS}Jk_dY%N zxn)PhsbaC>-rbyRONCU9j1Hm=<8@L)^cdcdm-sb}g}=|RTr7$5J}U;ZiW%a)d72L4 zmz&3mBn`q?`_KQnu^pJ>py$DBs+yNt6^ZD)HHM=E5$F*byT6U|Enm~oTDt1Kz+Z}! zs7>LNDcaj8mFdi|tbAIQ{nTNwHLi0-M-~SWSX&xbj}0-TY*%Ym@ly;XSVO0cY!g0s z8zh(#aq>otg+4(W=tIM3v1x-ZSF+8X-l<|7-bDnqkJgVQG;W8^4ck3-vk$e<9{P=* z_7URO!`b2vjoa+QzC|rW(yfM*ja@H|-R|_%Vc1(ac6a45d>^Ou;?aeK1A$uj)PbJ9?nz{pxZQ)Fe|lJr-L@4+ zvJEtLQ47(ObuRMRmo$F^zUP;87G^dPAzL0O$uPDq7|b$cj`yzdkKLaJPG$Z5V>i$a zd^$j*{drZhe$xUGWoYc81Y3?Cp*&o>GNSFWFpKXlVM#A0p{FGKX}scd3TN(hV%>)9 z$d!TCk~@_gPcslL`zBCZ!|1mnt7!F0FKc}4dNpAAI;>GxbRyA z%?a@%n0ylV-68oD;Kyf~S)Gs~W~LWW4g_l58#9W{q9<`FvPi^V(^|3l3&uz6%Q}>| zZ9JMi8P<^XeO<_`Ib<|5_K#rhm_p{wX`|R@dRF)@gG5v>{g~a2$P(Y8Q%62@w9I<6AJ4)@?H&#AToOV8h zXDoR&F88Mhj#_B%-R80EF4eZ#nrwuqc_BStmOPm^YC}Vg5=1y_8iDPz74}X-#*S^p#%{fUyfEb>f}5| zh}I7(^Wt+4hNpX1z=1%mMscH+jVkOAA%aIGF*W1$2Qw?>XoHagckLWtOj z5#nx(P$9?lprE~z2VBnFa0tRqVy(axod26RXFr4rVW9ko5NgWMb?h*&#W zdv{!hLS*A?vwXhUsS|ql9g1-vP|G>m57x@!>OEzH=jJCT0=1lRUcjtoJ~|V;xrAn%hq>9>R7K2wJ4dr=bU#fW^`xP2N7ks? zUe~h)kq#T<$Bt&@>n3IWTRZI;M()oa*`N6r`|h`E!_Tc7!?x8AVyk=QH4%ZeHH^tQ zvhYmv?z;NktIN^)KANw>j9?Z|^Hq}H$Ff;et8P!_?2~XnDSox#s<_;d;T*Nl-fuL+ z$(9#bE)jn{OT$0SX(Vo@s>@M=2xqO%{`-opuQepXHKsj}UOAerejm(^Ju7IUJ*+Lg zFWM`HH46DFqUM9aj&`7Tu_VK&bh8v+bLZ!sFVi~Pfi-lt{B^BiJnD9MM6*d%7)lT! zXQD~eay`Q>OcliwAI#t?nyst@fm$K;$FZs8-RW873^#&ixS|(t#5bfF4kd_?Gm*5R zXSkncHRK(CyWn~CDZK-MTIUvxQ8p&6md^*LW?0Jpxu3xO^XYyTN)X|`Hc}z3|1IBu z7(6nGdAUwXFTWIHp#%|f?vl0AbK?IRJ{4yN7IW`D)xm*4t>z&y%ErI#Z;_2lNAp@O zYE|@foL;|f-?E|s|z@pHn$93_ZIeJWNVV!n~@Gfe1O&@7E8Z}>3E)?!(xh4E;= z*Qeg!4VpEAJs{IgPFv-YNFb-gg{EBBACk?MMH$3JM4=s*3A@a#gvm1OntOb!H= zo^ZuUevn1c$V*nN2ZGNfCLfP|1|qt?`P#%GRe%6Tt{sHfm$*)<$WEsg`3gW9Cr?R zC-$Cbq685*dJN-CNR;*W`sMDMuXWT0%0ev}oASPn+T|HTE#Is+?mLIesi+M|5b<#M z2!*KDU+!d#E+wpYO>4X6G;wp3AOc4Z0Y>I!#ggrC-`p7GK%ka$T+RIHwz;M42Jg7m z!yO3Js?%GKl0{GRQLT3R>hMfc7n}RP&%#lH2yg0fsvR?jr6)v^yZ!jHawB~cx-DcV zK?IIt%BuY`oFD3*#T+CKnutIxx!Oq|>UFT;FAaFY=LgKBb<$h7_Mw(@w6D#~c)3^W zS+>Xw4g_l9dPVP%d8e^Di=T*0Et*>>L4VI-wh?NPo7o=II73X~uMqktmnaer$> z#S?CEW1a(nTDZa)M!DiqR?=o$y$4=}Fq9y|86U~bDClh3mP)kOdysvk!g*?;Pf`w1SPJavrB#4l)B5mju=j#{@AW%z2 zn!K;~qF={gK!OMvE7FEuqw-S>_N5s7*&l-e1Zv4hllS#r^y?T5NDv`oMcUA7R7Z-z zJ`{uQn>q#q2-K31ChzOrt4T4Kiem7ue{>86B#4l)B5mk3>b*P4xz(#7)g-P(sE0=3Y#VN7WsS6(8#zWF;)f(Wc3?RV!7R8RXB z)tt2h>x+3NEXgqHrMxQI)ANt=h1xUBEvzUzhK-F4Vp%R`Hb0db&34yG$};7Vx!1a_ zQy!UyDM10BLquIW#!K}-MEGD)CGaS?n&|)r#;Q4o3;r&}n0K#eTfx$H@`CvA+rQ3EDs(8pc!lYG6X9&7QN* zEQfayf$gKGOLKOy--c!ln^vY5M;quXL>tDAdAnF<*R-%ggg^-*uziLRH+L6na%Jnz zR$tk`k%4G>hh^b;5wx)#PnRx|VIE&<)uCs1+5KZzKD*1P#_riwOU2E8{rJ1@O%oB) zMnDUnY#7FkxC3m<@g6+E@4u+B!9fp*|i2lCY~{jBdI8@eh_SjJF-EywoJ?~hMec*ccc z*3qsWv6RMZQhKgZmc}bSH*#icw_Y5?u3jE!oh*`up%$WL4+d&W&(-Ss#J#z_tUjGe z`%r>4#F7kSQRRNTqL>_UZm1r+0iU1^^r2yFJJg@gzTMK*%ly^hT|_wB@$#2ltYV`1 zJ0JMRRlo-J8v4yJp3UCH#L&5++rL7f7TTlupwa&C&HsfJBm_zjfgYjEcFPmy>(x=# zpG`me9@iKzh8JkUTHI*Q`kkC0y3B0Mwq5GL)^9v2Dr9NGR@S*q^KNYR1HSaHqO2*G zU;08e9%bt?HDT$S-!@;LoWNq|HD-Tb?!Zz-k7u%^lH=ObDG3+;8s!@LDaJ}NXR8Yl zs8!|hQFdxaV>Z6Bi);*?lU#l~XobGsABMF;MAv^Nh-k9We_Lm=QD{{!*ZP({t>3r( z!BB#TZvRYR-#2LHN5s{A9x83*sJAe*L!vFBAC>jy>}FT(R%4YH9wi*>E*3ILUDp^T zGpSc^2FdqitX|=1BM^aFHyR%m*-A8Foqyxh4pFkdLM)oLbq7ii@${6o(K4%C)iT%E z8gZ9wJYT;!9{rAJ^a#Bj{i08te6#<4f(+$Rf(WM#%)=o9wSFHmPPM#E!x~hpab-$X zkiObJy5x>F$+xiX1*vaKZFC(fFsp6)ldnRLi7<&6UiR>IMD*z~ zNR_)sSnf{GV%2q~x6y>yRXBG)m;3^sfBBFg!GHH@nR>8or*1ZvTUQHW(pOF%o$_8bz1BN1zYCFxoP`U6`& zv8W!eLqF6uv7f%QW8>BCTd*vw36}H)A+Jz^2((AL*V64=`REr**GI!V!(xw$fs>lE zZBK8SDRzz*Z$~y~fA?+A{(N>+T&&%k{TUKLEuXR0aFux;!_AXB-EwX}(z&^s!*M=G zv|-$Ck)Xo+BaysP>h=sJh@kPtWJz+hqn!S~*W)_TGv{j)?z+%=S(=@t)~gFS%`Ans zh!yjiv&U&xxC|rD<$SKA)Q;#rv%*n=h?UPLD)dR3?QCDElMqNtS>= z&RXSu@gZUv*_gMxj0Q7C>z<-EIJ`g?fAEZ$ak__1l9!GR6OrEg{X5<&h48! zR8okuJ3``7f(Z1XvmIDpYzNg!wdrHGx@5zBJdr1uYV}8x`L30@x3Jr*o3l$fSGmv& z`{o~I)226PH`d6NQ~$;CYsofjlQALtU;)j$MP|jQy5FPKS&mS7{~L-;`i^B*DbGx@ zao}lA7qvqn`V^b!MjL3Ga*?;+G9S>|E?awoW@qQv4frb6ix=Baf(UApLNCXe znosyRBn-9Co^$L<8#Gg^nc*ufRYSRw{a*yFY6?LTTMK*ezY+Upln%poVBK-N>2}Mv zy#HQUJRT9K&ot$j6ejjX>*hcE))g_w$sEdeE2;%UXzC?U~HN zauJOy5#=)aq_=XX$|u|(>T*P&7REn)yE{#EG~Yy(G&N%pF2-$? zQMbeRkUI(3!Xl+ClprEq@nbBcXCoGNP$J4?uWD^xn_@?XsrfnjWJ=CStU}U8tk#Rp z41Gwa+}xJHYvr^tf9);yvSm2`y<1X8 z4njA@f(U2JOU=!1$*8@a zuBropTCybR1#M%+l>An=Kla2AqS1m9MEqL*m_nrY$Z@6r^u8TEifHtq6M+&$IBle& z+I+XDMfu7!cF|YpQS<`6XZh^7uj}4utIqOuCiWB}q&+znbj$y&R+Lq&HQ1{6xHdxx zBG5LCcB++Z%^MnD*mAUoZ8D4%e#8VqpyX@Bms<6vFjOi=wP@Cyq07c@uWCJ2M~tbc}U6*N_d`W18dX z+IrrQB|2$RpZ{2Ij&Jm;#H?nPXa@qdqUs%ErP?%RwSQxT_`7^AUz>3*v(dyD2LiQ{ zCpgafhcsi&UP#2NRE2!QuW)nd2s(8UB#5ZE@)#Smq8SS-DEFd8Clv4jD-?J;0}=9t!-0<|8i{xJNYSth4~BALbPFo zG)TaIs6CMtJ>QVyY>D&L?#jp5&$Sz~Mg4D4t&X?K;oGqLd-HLh7zYBi68Mg@3zwU) zA|oXtZ_8tB;fNkQ*~soLtO?pfk5Cq8*}trQg?2ny$$woaL4?yrj%kJXx=EGzq0^({ z5rJAbdgzOhb!WxlW!pw~YyFRf z#Ga8y<8i#A7NQL!dT|F+lpW+MI6ub9$d9w3H1{3%nU2x!Y{%(mG5qPOc=zUAXPy-j{t>TyT_fnLz_uFNx}+nQw?*2DmW!?y9FN@H*Libq_v-^FljIhN}v zNf~)v`WyGNk1-r2h(LSP=cQ^`^_rwIC;Ttis!;I6g=d@Bu-f+o-W$TN~LYWV&`lj#O{b1R;SSW?z3}( zEtDW)SFNq=*yN_n9G`)*2H&@@Vet{q+=IFXTPQ(9^|V`APqP^tRxg|o1DDmX#pV$LXSFcv zh+28_Qr8j_+)Qhs1QBSDYL%=tKR>O2_nW9h9On{@-~&aD zv2V{bV|S}npxGz1vdJH04L3)9F2+%Uh_cg;vEHwnGLa~h5Wh4udH7%D&C}0|ag-op zeCp$DQoknbLh{mtXz_1z_Q$inyyc-7fpy0kqHQ{tv-2eOcXU_IyR32`Pz(FXFp4*P z&t8lv$Tzpo=;%R2;OH@o@{Mn>J))jDDjpayw7+x`!@cQzrN4C_w~{1$xWk#0*iTU?(do zcnd=WYB@*AijOs|OarsI{+*o5s#kognne#E{?>(B&UVb&UV!JVG{!w9Qxywa8`z`d zNmt5rBHnb%%@Zye;hV6shGS+x1lpz(Pfi!MuFRh0TQ!bzlmvE8Ly|_ASVO~@+q{64 z<$}k1u2mI|5=5X!XwQ(;y)}@n#hM@jZ5zhBSB!Ufw%Rphcu|fm$8xbG+Fxa@%0DK_ z=^iyHzy13|`Ueqc&oG*g9?pw*%jXO3deq#IYYQuos4Sgv|?k5sr~&7$2TL-!ZXLJ3eRPzXJ01o1Oc1vxc1QBSDzOH#&s=}q#{j9Y2mouy{J_{+5b&EJYqA|PHqZiF^7cbq3 z%e}ar)u6&V2LiRQeTI>5Y)03`oke_;55!oV=u}v_16Y>fLLQhA@3%6d%uq1Sd#$aw+szj&RT7#mC=mD=?tNiX|0{t(}>)Yoe0#z=U;}===;uA{|%#= zck@nx5=1zklI^|N#oF}robbLmFD7O1Zv?^IeH$ID+BLCJ@{j?1{@`bkR$XY6r#Of$qhn4Blpq2##dK0(<&P|KL0`5iPcxaVwaY>+d^?4n z4^}I04Q2*=cCMtgxyUh5eQ+Z-XYU>JV}|3R^Oz>AP?LuyzX+&Y3%h zhsZ3aEkVS3$6GH6=DDn%&y$;{-HR%L5sp4VU$t#FQT$N88GB#6 z6Xp6QP~Jz*>+2{}gb37Xm1&ar--U)uT$69soKKV9`n}A3mh;z=9JR3JPQ;Pcw?)3{ z;k2{GG6XwRcabZ&t@D4g_j# z?>k<1K?LpL)LN@^$kV$OZshswA0>ru}Z3S!LyW8B4o755rnvJDe?#r?Kn$V}AL*G$njQHy$~yVeF)`*!L-t{x zX*NB6T#Q`NgpK@>5)yR(OYXH)w)y7lqeT^PW>Wi)ZEMy1 z?uK}`s)xY01@O(Y;Ecz_sF3FDR)3in9b3M?*&;z)m0k2)JZay76-nNjty}q~GL12_n#k^m{NdkZ?xIHBvC5Uj?HvTYU_&*J2`N|b@+Q4?8 z7Yrkee$k(u_~Xv(Ef#wm5@?6hSF-K?jBqHHi*3T%()S-d|8Ua*bYQf zCN;DnzgHsIvwcDa3$q6Ji=OgKLgp;jshnl;*^T)6?dd!TrloTrP;17_En;ko#%$rI zXvzUxcv_7we0<)$y?kB=0<|c^D!$}i7kO&%w?&?~m%q*}bFa1p5#`cu6(cFXd**wY z-)%av2LCtYzWZrtu!RytP^MUX$ss4~TZ2cIyyXsWu5!q>1Q9zIZ52b)(>#Av=BZOp zslih=Fw9GZgDsRGf->IXOD;U9Lk+&YUkWp8Qv}u4;bRQGsJ@qZXp+`T6VdVrH6dd~)TLjx`EL40@fO#O-`5_FXT?V>4uO z_zK(PM1(fFA`-u5{9~SP96g8#tRcP0u_LeLOO%rZZLVaY7ZHK|L?SUfs6l3L0 zFww*jj$WWVtQzeyb1NfI?_%T?N)Uk~pOPP$|Hsxm?QBiYxt5^>5!nBRu_^B~c5zu3 zYss_K3?+zg_D9!(wRqUvX|5?Pa#@I&xDnrDNd_=}9$85RsZj zqRg;eE;W@#;y*cySoJ!V_5FF7Ti^SRsadpM%1{%%>qOMvQNU`K^>BFY;3^hM5P`Od z8K_=vzQ>&9OEEulnT9u;&5$F+m;tm;M)Ixh$Tf-RSt!U*b ze8SaoSYd|^YzLz0eTILct>=5k_-+PWb&M;F56m-C%OA&BdovyK4iDe%K?x$9Im@hc zzFmzKD_so|g}D)dT9{ijjNbG#v1X_7Y80d7zYsF3Y8dIN_OljJKJj;*%TQSZ`JO($ ze@A%@bzgpaKw~$$qg9mhiMcZzWGF!dTQQ@rS)VdA?YEceI)k=Q_@#@qP->{rb#gG}193_aLyq~h6-}tR@W{LSe zXH(YeD+Fpe-|Vm3HXU~l4i^upRwzLPW$}~^{pRx8(0qK>j#K8tfmIv`)WUCCXf>D^ z#b@<;>05gEo{17fP!>Eb52wF^I838G|H*+YC1uZ1f(Xh1Duj$1!$?69HG#5&jdX_ImLLLSg<^12l=WS% zQD%)0#o@+!9gh{+G>01t>OE3?&>U{85#9e&ak$-hGR!Jcccr(F=5S;0W=|E9G>02o zTjXcq=Wt`^=~{ER-F+No{WhquZ_Xmc;btS~RA5_+&dg-%4^0tqio>nW=HXW9mUrCI zt@ld~H@jAJhAG>=dxR*UIo#|T(wiKWhFR^~N4OG~QygwANtKb}56$6bBd{cSUSD5p z-Oz--&;Ke8H@oiFpG32Y*{6!P#JfbNDYGZk4$a~AGw)*Uf4?yN8_nTn+n`gSSu^ra z7UFP2G@ahsbAVNA{#vt$=5VvM=xkIQ?W`5c7G*to*~!qya;*2zJMLN66o;EFK?I#cuWaaZ=qH_x;B5}S@q}m&HyeRkbVj^F=riKS zHT2EaGqr_j99-%tSXuEvWwY& zl^kxi7M&4pqp^LoI(vp%L&n{TU$k6txUtN$!$h#=aI?!Ljv2eQio?yC-MWqEMoY!v zW=rTaZoB1l`nO#YJw@)_)haT(y65y+#o=a`i!~(17;JgXm7?rV-+6*Ghnp=y1o1qv zf5{7)!|i+Td6B+yjN8xQW+PCG&eLZ($h$U&8zT-kub;!smLP)ID%5?O!;KS%o7>Of zW=jx3Y*(sQHisK04mXdV!_7vZ7I9Cg`!Z-H)P2n>v)@;N|LPj#8lXAcYzZQWOHA3&9B!lQ7w1jxb@Fu89BwuOwTOE{ z-PgP_=Q2imci&0sEl%$OkvJ`;fT%n#0XTpccl8;&9s`zpfeG=Zxf6v;B@XuuY1?O`Y7*BIRVs z;ieFB#NkLpwBm46hypRk%A*bJb0>m0+!R9Q8PEo5A)4Nr%v@Sjjf~_4TBnyBZnodC zR?gYyREZ8|jh0b7$KkvTC5XV7r&G)ihp;3~#)t^bUBd>KXsGrd7~66;An)rv!{zF8 zSk*zZ*u!m#!_Af;!WrjRGS%SwXD$<$G%d?9epA$)t~lIm2_ocfKqB-mV@jST{9WZ_{EzL5yT+Cv!WrkY&(!DNUtA;x zFH+n!HUhQe{z2N%yNt1e3-FESr?P)Ehnp=y1V%HR**{FM_{fXmK~2TsW+PBb?jNKL zy)TI$-OigM!7X-8bJy4sL^x-LU9U=u76;mj+?u<_Mxd75KS&#TUo!FAFw0k{Hk+Xn;)P2q2mZVN!D^a5bEO)TtaI+vn7ad#^8n;!+7~UgS|g#4mTTtS~6Co4ZYS5*wc#lEp52BY7RGB zf(T~}((AFj^6Fcjv6{opMxd6A6=_4Swb30tNt_IBLmQk@xjF*rdiB7EbHn1^+r2kRZYtgT!UZiOW>@ zxlHY{P|F!nhiM&r6Ow>;_OF8h8>l6tOWxP(-~w6)8_+r!>t6>05=6*Yk@sybQ%+o_ z+|OldOAz6V!E9&i)A{X-#N!2e9SoF(S~6DTeZ3BzpmlHrt%Gs?bub`71jY?z2WcIQ z8*)*U)*NnjS*RsrMV6%3!A7Inc^`bf$%<}JT&A`J5zZJa@Vd0vu&=Es<6j2@WuX@S zj;1&JAC|T57puh9%vBt2%7$Da5#fxeyh$rtcXpijmCzh+HUhQqmp6T{wzj`D?8Xqb zx2586vwyiG!Wn}zC=b`7*b6g9SHlj5A+C9B$$A)FD5Io1N3cY@IW!MjUSHY^o~{YfBC{ z8-ZF*8^qzJPJ#Molvy4nm>0v^Dh@Z*4nK#RYKP38AsX$`S;bRV`Ko=>-g-eiSeT6< z_96BrdoJ;#=D}j69^???6c5&z4{^S?-nQ0Xsoy#f#EE2U;co`YY*!iLE7h`xbtO)5 zxUnqva*EBwgN0g%rmq?+e>Us1YGAdgnNG5d*}vitLF`I)NiE&PN4C1EZ}z9c@m)2Co1Oi@mZL`uquq*eCULm&*_y-6&Z-b=6YEKt zB0q;4WLUzVmKF0l4CXC6C=NGUf(YVvvTIAM(+>^Swrp44u7u)nvn5z}XBH>#m=Ep( zNvFj7IoxcYpbhjPaa3*EU=~ZV+0{#PxY^!Cg!7m1xFj)Fo1t^JAJ!ahc5AT@&~J*> z%Bq(*d-xDywZgtdEkrBUH!Eb>@a++r!_DqB^bgjM&KDiJ%4gBoO`$p5?5w=B(WUiB z`puy@+}KEZ>M&D{-KZeL95}U?)uVvoaI+Dzh5;>nPC?%^tWMz;{`xC|C#s*a! zsm3m9A(~FPDf!t=`A#H6*hLAp9G_Frd&q6eusKV^c+NeF!;J;gQ<7bp!_9t9;mo~mtJhE* zyfTolyRA6fY%SRb0krI!KyB#^vQ=5x!CAd{l~Ibr&6Z#diNnnq6-3jL0~hJI5VZdMN(?H4tN zn_Vl^LVLtSLpIDGyKf(%IoxdjAj0V@Ug(Xl;5RG1bv1{Z_=ldveLkc(+{EwnB*xF- zCeG2d=5V|JJhP}0Qp6XeIoxano$G6B(FvGBK8e#DZi%L~68V;mk3Xe3+(fRZhQiO` zCbI4yAzYfnO=PBLg_^@{KrQ8X3Ql8ejplF@cc~qk!)@rf5Nk%7YvFl5D-JhX3+>T)&muF`R&%(u zxj<*C2PJd&)*NoO1QE_!1)Y8%o-J?V{y}rN*}lSB(OJxPZHYtrXhAD^!-THEn#0Ym z71o5#c!qWmhnqzlZV|&Zhnp=y1f4c5a!@<;Y13y)4zoN3N=K~I9BwuOwdjmzae#c) zRdKkLsao60zhRgwgXVCvC5WIi;*|}3Mtu7Rm91^v55}d?9BwuOwdm|HT2^AU%e z%g^CvOAtY4#48*6jQC*_BiQv8pjK6ak#nt9B#G*5p+hpvSD+$ zapG|E_&MBc1ZvTV?+T$$e9zu|F!$B>dWL8YHyeRkbRM?4Z*#bD;&5~MIoxasBIv|- zWka9%9=3_`N;NimDrycl8-ZFFkBY;M6Nj72&*5fADkA7ycV$C!xLt0R&zzq+q1(^l zW+PC`Ioi+G%HkP5WrNGl;btRHi%!#pIA6u8`7WOcF8@YzxY-EQa?T|qlI`-nF}9eE zHHVv6(okX(*iH8}hug5?9Yw*Iy`F6g6o;E_gHHbz-RmY5{WOQ0ZO<@%{rpjED74s&*Box* zZv7y!R&%)72x6$POQLU=a%8a*&AaRQQFFN2*6EyW(bWhRahk(T9H3fh4!5)eN?E(< zE6_BW!_C&BGs10q#1Wxdt~uOFJxgO1o7;$WNv$~CYzZQqwW|02l{h|QNPITpa2vjI zw7C2}SRBzDZnix-Ti>oNjjNt9;#AmQ@$EH-n=L`_Vo8Qk?Pe(}+vph;{?;6BcDY!0 zI$IxFP8@F5_}k&}Z6_%XH(P=TITH!$bDP7>A`UlCan0doBT$P@;}^TgyEccLRqW!8 zhb_>$h|aK7yuP2nJ4t__iYY0P8@FW zehxQVf(YWbQ1>;5TWnW47^qGncOA{)W=jx33^g$O%w98qwaJ>(>(Lx;HUhPX5yPI9 z=v&LP$Gz=mm5R@zIoxasBIrDQn0+pUE_Nr3+#5GYbGUs$fELE1d}1g6V)e-U`8nLwwV%UHT{}43)Hj60eWfIR4mTTtC20%NhP)!4FuN>bGE>)n4mWizZGS-! zhue14BE~7D<>zqw55)AN*Fw=cB8cHiAvA~E$%!qjpmZZW-8F}s=ujrHngI}jwkdNL z-OyqwK6vkH4mTTtS~AXMNjlEcm6{{+JecmOs5#th2_n!VbedKArQ$`wJnoU2!_7vZ zmYf-+4Lvht9QcHFUcSNi_VW*ttI?JqLdLm7=r~WlyeL1pc$VqsaI+j9O{K=5XWx+&<)9uQ}Xo2_kUx&=;T~QT+D$<=&&3!_7vZ zmW*0yLr3l2jG>%3+`RiVhnp=y1o1qn`%v)o8?n&xn`C5XUrOy{2eGThqIJ&SLK=5VtSs3q4y>0P}JCi|sGR0D zChvQZP;57+gp3twL$6UiC1-U^0IU1`wzvV^H4LyVrzIIInd2o*AS$+-wOVoO{s;5qbH? z_$}f$&EaMvPz!&nD-JhC9B$0d;ieGsw>~1Ad(nuS---%d+}4F+io?xDpqBIZ;HCCi z%~DA>vQ*_1hntN+EzAcf4mXQ9+=QRQ&Ccl|!ufm9b0)ntBhx7FIL+Z^BTx&oUy8%c zA`Umx&*5fg?ht{|Wf+s%4zUW{%f_Z(QygwK0<~n+${y6eIf=tfadU*XKPlPL>|6$B zxt!UkcDwRM(24KX=dfXt!_CeDVt&t=ha(QRIQe|=_D{_vhntN+EwoKvhP98A?+#i6 zOGY|sg$S&n;&4+>`}`bkcK!-;R!$q~QeI^}>G?+$&EaNeBZz%S?2HW(lEdv|snOzP zound*;=!8JBA$iJBBrLZio?xDpcZCZh%4pFelh)44=YQ84Uz{-T&*1>x@rzLJHvu# z!}xe1ft5K+11qWKaI=3eVYyfmJq0M-nwLx(@6H>dc(BCVt-+$J=E1Vtf%zHYGCk6V zUwKn3zP09XvvV2Pa?G|E#>^j23$eB%FHan9_?wJan?y;<`$!HqXTD_OzMf(oJ-b_T z{+>gE2;z3KYfERCUcb!RmF~)G=h!1T+-wQf-DzWP#eUXwF*!a?bGX^wMH|lFoKG6} zvL@ZzY-V;&(f?`whi}$9q`)*DDS;F_@m+bmC6bGX?)K^vG)CT_q( z{jEuRT6$V&4maDoh;X)}&g@;H^1j^_&ilu1!0*^==r?*YN~8Vs(7D?-euY3Sv`1gQ z&}g@A{%?B$|7Z{R2N6zRJxF-Mw_GK}6lfyk>06zNk?qpV#$pz6xGg27 zw&_`#h>?oJt!MfJW`|c%ywCBMzT$Mw)x%6pL^9%Vdqb>m+vhbFFExjokR@pjw>Qa0 zdx*o07hkj0g$QCqu(jwENs(x0V=+l_xamBO&ii1k5J9JasoH7|w*Vr=kj0@W`3j-z zX~dN8FK?5%rElvk45P2&*>bAyWzFHH%Jp-&scX&Q)}T~SxMWx9H#&{vaI+EgjjFBn zu<=n=u|yM5OL4d*JJDCZS;JTF@a;eeBIxT=h1MKyHKI4i6NeigP-Ia&`W?~e5yR;F zOK-)=dRB9|sj_4bBEo4S;H!^8MayAXs6}76s**H^+u+Tm6(?&2vxMYu6TcR0BK|F@ zINXHnXFrFVx~{1>-0t?=rPyevFU#OS&=;VpTtA1Ky4GJWpD13!MI3H?iRN&#ZQ#hD zlmBdcboxb#7OvmOSEV(Fn=L^E_CK8pyfc$(hqp;7$$e(qpz{G0TGpM;@l)3h4ma-S zaAUHyehxQvE!!c#qLueGhg+w|C&Of)rz?I^GP2ncY&qJd?BJj6)VCS2n#0XTpq8^% z8B1*1F2Cl8Y@F564tXY^tcmm}j!?tM+Pk_M?RP@+J4QPq=zDI3mLva5CRJYHD8Z3I z?NbN`hnvdQ(pi(L9exfsb?xVHQ`dTC2#iEOhnp%(j$JI**@FSZzxx+R4mZ0jM9??N zsw4-8o2nHe=%h-8mbG$@tAGvpzx>`=deqP1W|xaStM%nv^6Ro)p=ce^@(XEMl7qvI zUu?Nba=6*$qL%zxS|S`AZrsn|rVw%@Vok6lT`M_CRQ(-(~A%BOUXv}`(<2c1Iv{sxyq9K9BzNt ziXaX*tB~e!QxaKsY?C~lR3h{#1rw@OQiv6M6o;EFK?M3x_lNuiDX-9r@_Ytau55=q z4?IZmV){5t-LC7gIHdo6?eA_+$Q2v3q)RaT7V*tQsk5mXk3d z%kp!$F?sFha8uX%gpJj+OSxu{jUnq5hnqt9Io#B>w1KuM_gcTDul%<$R$|TJCJv=- zE_M=!+q1SuMZGc2#VO6#9B%4b_S*luKjhiL0so-ioTEhdVXPJZCe2oqAVNm4 zEJ<^?Sqb987d?-$s%j25WkZfQ)WQ);=Ve6x9w*yjPJiKu4@AgQN~8_V;TFGVbA{bc zi2Zcjem9ndTFxGPTyRSSakyEFiNg&gh>)jkNE>o2ILEF$7ez|^9B!&jehxQvUyt2@ zuPX7ilEclG(D@ZMg4(369UN{dK2Qto$=Oxf)?-)NkQo;F|5sYdo}a_*D?}g$sVrLy zd+`6-kcg858%Pc}g^(@8y3?s4%7z?ovMz=p-wXeBp5kz`5vb)HiTiG}ij(b_lH=WW zl;A9ZwzUoUuUw~acK&*vm+K(z^d%-%Ap(-G5NdtYh-Lnhhu`~89+rL&tRDe1){x$( zzSP?V|U*xo;c+zi9ju48MEgY#S_Pg zC(iBXiL)h$z~5AK5?iXuR-`9eL`C9>!{1Rj`y{AyO#HmGnP{MR;%aAgSz+^@czY60 z93oIlo+&)bYAQ5O+~a>EtOHqJd6N=P93oJQn3_brsZE6DiQAf_g0uElC(gEk2((A%Yb*0fL)>QMv*)|Y?o;Hlgqj`Al z*%2(kX~h$#5b|VRY?C~8YuC;%vWTf1nTP z9mwBnSp6>^^pw#&aS9#)+&4w@#Mu%=@Ri5J>J`m|=7}>_7BG8{;J*K_t@DnqqS)j3 zA|fKvLRUaaLQxbIkR&%dBPB+VBDpDOl<-0k@F+zg$RmUnjx<5R0|;p7(rlCn_wEc* z1jGcTqo{PAsDSW5n(}@#b2Ira=jETAbAP|@PTASHd%v?gpXJ1f!w4$W9>!C@NE3z= z7oF40J<#H5FF)7pRa_iF1>R*k&Lc0kmu-HTDLyouIP14z7OLsprOu^f&NGw6r6b)r z&Xzb|ZEja6c6ADh1)38#C%uk)#e2!SK%6*KU=~rkMERpBqN(P@{q|y^h#fmncE}z; z8+4ca20%6Th~v~-azi{3n<<+&zY)L)D*R=XdAEryJGreq-E6`pRA3gKS;sl|zyX%F zy+42R-TM^D$o3WX5B7rNe0r`5-)DG&y`E&Z3?d}(wsQk?`j8Kb2MD6>2wKrB-EYP8^?KX@VPLIB_Kr+T*vl45Go=8fs1)uQ@a|;cOqxi7SbK z0((KtJLVoy{l}W99fFI?@YiZVMld1Rc6TVkiL))oIRO5)GwpATmlPMnRP zB9ZnHUhdL-)lKaqyl`<6zh3i7I6#~@jG#j8NPLxMAH#_&9G1uzjr=)0$#CLq1Qqy; zjCRfbs59@Kz9w*HzvjeQ?-jGuUbFM-q=*Z87ur`I?#NgCx;W4zSWjXE6^%$SmlQWT zseNn16@vWx>7NC1h%AQ@RA3G1snT*8vR>zyga?T%hqDh}^V^9F^6dUJaYK{kMzwQg zeCs%`29f13f(o@)@uI7#!jR<#b$8{h>apHILzc42TP+CwOKQ?wc1SRTr%<~!%8@Q=hT$;ZT# z6XInLBFkYG*4?j|wX2~#zPO&aWXN)M?4pABYWBKuoR*KSaz|as;ZHxJ$#Qm-;Mv4} zqZQr*GugkR`|wFIniFSdYE<~oIdS6XS+xg3w+tsvU+24t6Ng#;T8-ZjBNN-^g=Y~b z4(ncg_Y&d6K|5~se@MQPKh~XSIB_)EvWd67uPMKG&in2P!-=zz;=4)3iNhMw zESes}GY^Ckiii`35mfm5O3iTUm$v$kH9>{HR%Nd;Iri|1P=DgYVaxHjcqDpnyLJcJ z@cz2t!G;s3+Y#Z!*>i*C5$SKjXnFnhMsCtT&508|?hcAY#EHX^k82^cMo%6?e&d>f z!P7J+&MJr>CiV%@seZwa$#hhWw>I#vAspU$)s^udYc zH?<9=$k_ulC(cGtf#uQOR8dcSxjSPh?`t@5cI@Ix4DDgeN{tJOvzimP`G-?+r#{N$ z55{RuoK;{JanNl0=(&uE)j}sXHgl&KPMq%D2q%uI@4*Ns&h`TB(me5a+}KWM!nMw5 zPMnP>I$N>A-}1fPKHj+K`jmtSC(hQlSP|jGL9NzwtQHDHPj_czYEGPuphE4%tjbfh zRpU?nncqK+`@(SIY~&7CO{>l7Qctz7^S6I_mCk5RoK>JFhmIaO=ErNx zs+DJY3k@gEDlp5xV)9AtrQXPs6WoS|6Q>nw?FJQoSMAHW<-G3~E%W9WPMlR>7Ov1a zPToUR`RYHnyMNuQsc%}L)`U=j{yvR%qKpmyr4p-dIB`~iS-8gLI2~W=%j`9uY3_)qd9R_fmyiP>o|ow zV|iZQ7#34UbKnwMH&_8z0>>7v=j8qW0lxt z!-=yB%u?f6T_1)McaE-)f}&x98%~^!ph8_MN@3PHYtl6spuN@8vNb2pM($K7ht+W6 z$gS1iPZ77475lB|?~+@qKR2r~GcUi)E3SNpr5aA0ji3VEXd)1|`&+b{KSazioH(n% zEPMinxB!W5c!O9+>?KazS|SY(&Q2B)P8^$^mm(sZI9B3vUdoE&H!=@;%W^d*&PIsA zWEJ>?2i0nBfd6ykKJOZF;xK{=@?lwtTRX8J!1LSO&lR$Pi_^rt%@il@ z{ym-e@EsN0ABhu(WndPOcI>JwP0~+2Et|!@mC%Yfao8u=SHxOl@3l!2w=^ftBi|?I z;ki$}PTmqKFe{__6t?wncOf+=?nI?1{_B%x#qD{T6K9WwE%z&OUpmRwCdSD{h7)HM z*bY?FTS9L{vol+>Wy9{zFwDYQVVlT#EFWYS>JOD~WsmVGFw5UpGs@f}FLkWW58nNd z#FpcT!Ct4m?%OuxFPsXpw!1Yajurd6*jj%(h!e+&6X!-aaaMs@#1GTooQ4y3D6tVA z_eZbrH--~uBdDNzIQ_ZtkmvSqELq%oH`8$9bQ#KH#pBXFoK_eoHM}5N_N-YYaKv!p zYy?|Qexf}R4Xa5F`cp-K!eN$IderwaTx+EOI&ZkqjqJ-(*DY zGO)hb4u8utXzZTfF}mOsja@tkcw8)xyzmR-+}sr-cxmFqp@Mu-T@&TpqT1A{_}&L2 zsPOmIYN}O->0MioGj6RtF1Ew3IN2$QPaQKPv|&ws-+YC=fal+FuF@LI-~Vh1tuvfB zJ4d0y-&ZSptn^Ozswirb_eu;Ww&7@Zag#W4=|x3s$+8qN#&F_Tv8(DhoulS?2fn4Z z>J2B(Mo>XSEjFV{P#8|!!bv^(*4Sfgj2tNNi3EJQtxmN<_T^*g;*{pZU2FD+SLcn) zaF>a>5+kS}CzTcZrH-?C>rY;j`s2Mmh7)HasPNaSMr>8DX`dIpUL&;kY899@WKkiD zT0?W9=EOC9s=8OJ?~9(|#9;&#wpxYIB|0m3)#2rf}*wI#KGJi9CLv^(K$=}Sv7;>yo9qFs%ekk@LJY*{UF(( zKy%{kvGCkruRBgc;(k`^YJb`Ot7-v^U@u^Kbni2{36GxCR`wgLIdQfORQOxIA-y6m zwIf9?*;hw#;;aI*hz4eR#BqAPcSU@)uoq9*ra5tT#Nj#jxBU38)nqXKdHzY_=K+kM z0{f5{pw)9^`5F(f_bMGyoH$zss`0v^x9Cy_xid~K-+0dq&55&D6uFLiMpc|RY?GNw zURd{aNO9tP5m1oJY1Nt&$NQ~s;np;qI30;_;%xu;6|q-x`I+Qd;g&lzC(a%Vd(>C9 zBzf$4$6HKfIgFr!$a1X2JwKe5B$o~= z@7>PQWH}o_1+li+-kQl`oF>byKkD)=J)iR)C$ik$s3OMtrHDpEmRovnAdz?QyxPv!veJsb>0JBg{?By$Ov$V?nWinsx z`&Pp-hP_Vn)y8XV&(DozrE1lEeT8lEEAqM@WnYtf*Mi7$7(oTr&~g4MXvim2s4Iql zuE}z?7g2%di5$p5eY~Q(b9ny$>4@UQVPE+b@dYtFvGz9`dl*ifJr*jkY{y|;ACl|b z_ua~d6KBi7TKQYvzi+g>)}>Fv?N%K)Mo@u0V!l6$XHm=|(wi;M-;O}|Y3@AwU1%P0 z;;;;C2de2=ga796l)^lBb2-h4v!et@J35}46UWb0-<7a9O>^R`1BnX1XIblJF2A^R zdFWDU&55%L%tCLGd{Oeje;Dv~Nc90m{-45d;>b_rUC2+2aN@LUpq{|SXZ*<5(4VXK z0%-4qoZfsj`H5eWUxE=-_@C12)2#+~$WOfgjON7IV__EgeoXl#h7-4sh-~Nn9Va53 zIIF-c@__W`=1q&f`xd$*iTaj3Q*+{M1Qq1_=`zey#e4QI^jN)A(fyETS(M?#X@z==1{LJ{=~|g5u=l@s+S~c$o8bs2&MGhqpSdJHPLq(AbaA`4 zW~1iBSp{a{8xgcBL;mic=eN7%3@1)2)LR>tH3NZ xDwRKHyzu=r+NXavOw=%(I2%C)xr6$1b=}aNK3!1>m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } +void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + for (int i = 0; i<3; i++) + { + command->m_requestPixelDataArguments.m_lightDirection[i] = lightDirection[i]; + } + command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION; +} + + +void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]) +{ + b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]); + b3Vector3 center = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]); + b3Vector3 up = b3MakeVector3(cameraUp[0], cameraUp[1], cameraUp[2]); + b3Vector3 f = (center - eye).normalized(); + b3Vector3 u = up.normalized(); + b3Vector3 s = (f.cross(u)).normalized(); + u = s.cross(f); + + viewMatrix[0 * 4 + 0] = s.x; + viewMatrix[1 * 4 + 0] = s.y; + viewMatrix[2 * 4 + 0] = s.z; + + viewMatrix[0 * 4 + 1] = u.x; + viewMatrix[1 * 4 + 1] = u.y; + viewMatrix[2 * 4 + 1] = u.z; + + viewMatrix[0 * 4 + 2] = -f.x; + viewMatrix[1 * 4 + 2] = -f.y; + viewMatrix[2 * 4 + 2] = -f.z; + + viewMatrix[0 * 4 + 3] = 0.f; + viewMatrix[1 * 4 + 3] = 0.f; + viewMatrix[2 * 4 + 3] = 0.f; + + viewMatrix[3 * 4 + 0] = -s.dot(eye); + viewMatrix[3 * 4 + 1] = -u.dot(eye); + viewMatrix[3 * 4 + 2] = f.dot(eye); + viewMatrix[3 * 4 + 3] = 1.f; +} + + +void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[16]) +{ + b3Vector3 camUpVector; + b3Vector3 camForward; + b3Vector3 camPos; + b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]); + b3Vector3 eyePos = b3MakeVector3(0, 0, 0); + + int forwardAxis(-1); + + { + + switch (upAxis) + { + + case 1: + { + + + forwardAxis = 0; + eyePos[forwardAxis] = -distance; + camForward = b3MakeVector3(eyePos[0], eyePos[1], eyePos[2]); + if (camForward.length2() < B3_EPSILON) + { + camForward.setValue(1.f, 0.f, 0.f); + } + else + { + camForward.normalize(); + } + b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547); + b3Quaternion rollRot(camForward, rollRad); + + camUpVector = b3QuatRotate(rollRot, b3MakeVector3(0, 1, 0)); + //gLightPos = b3MakeVector3(-50.f,100,30); + break; + } + case 2: + { + + + forwardAxis = 1; + eyePos[forwardAxis] = -distance; + camForward = b3MakeVector3(eyePos[0], eyePos[1], eyePos[2]); + if (camForward.length2() < B3_EPSILON) + { + camForward.setValue(1.f, 0.f, 0.f); + } + else + { + camForward.normalize(); + } + + b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547); + b3Quaternion rollRot(camForward, rollRad); + + camUpVector = b3QuatRotate(rollRot, b3MakeVector3(0, 0, 1)); + //gLightPos = b3MakeVector3(-50.f,30,100); + break; + } + default: + { + //b3Assert(0); + return; + } + }; + } + + + b3Scalar yawRad = yaw * b3Scalar(0.01745329251994329547);// rads per deg + b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547);// rads per deg + + b3Quaternion pitchRot(camUpVector, pitchRad); + + b3Vector3 right = camUpVector.cross(camForward); + b3Quaternion yawRot(right, -yawRad); + + eyePos = b3Matrix3x3(pitchRot) * b3Matrix3x3(yawRot) * eyePos; + camPos = eyePos; + camPos += camTargetPos; + + float camPosf[4] = { camPos[0],camPos[1],camPos[2],0 }; + float camPosTargetf[4] = { camTargetPos[0],camTargetPos[1],camTargetPos[2],0 }; + float camUpf[4] = { camUpVector[0],camUpVector[1],camUpVector[2],0 }; + + b3ComputeViewMatrixFromPositions(camPosf, camPosTargetf, camUpf,viewMatrix); + +} + + +void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[16]) +{ + projectionMatrix[0 * 4 + 0] = (float(2) * nearVal) / (right - left); + projectionMatrix[0 * 4 + 1] = float(0); + projectionMatrix[0 * 4 + 2] = float(0); + projectionMatrix[0 * 4 + 3] = float(0); + + projectionMatrix[1 * 4 + 0] = float(0); + projectionMatrix[1 * 4 + 1] = (float(2) * nearVal) / (top - bottom); + projectionMatrix[1 * 4 + 2] = float(0); + projectionMatrix[1 * 4 + 3] = float(0); + + projectionMatrix[2 * 4 + 0] = (right + left) / (right - left); + projectionMatrix[2 * 4 + 1] = (top + bottom) / (top - bottom); + projectionMatrix[2 * 4 + 2] = -(farVal + nearVal) / (farVal - nearVal); + projectionMatrix[2 * 4 + 3] = float(-1); + + projectionMatrix[3 * 4 + 0] = float(0); + projectionMatrix[3 * 4 + 1] = float(0); + projectionMatrix[3 * 4 + 2] = -(float(2) * farVal * nearVal) / (farVal - nearVal); + projectionMatrix[3 * 4 + 3] = float(0); +} + + +void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, float projectionMatrix[16]) +{ + float yScale = 1.0 / tan((3.141592538 / 180.0) * fov / 2); + float xScale = yScale / aspect; + + projectionMatrix[0 * 4 + 0] = xScale; + projectionMatrix[0 * 4 + 1] = float(0); + projectionMatrix[0 * 4 + 2] = float(0); + projectionMatrix[0 * 4 + 3] = float(0); + + projectionMatrix[1 * 4 + 0] = float(0); + projectionMatrix[1 * 4 + 1] = yScale; + projectionMatrix[1 * 4 + 2] = float(0); + projectionMatrix[1 * 4 + 3] = float(0); + + projectionMatrix[2 * 4 + 0] = 0; + projectionMatrix[2 * 4 + 1] = 0; + projectionMatrix[2 * 4 + 2] = (nearVal + farVal) / (nearVal - farVal); + projectionMatrix[2 * 4 + 3] = float(-1); + + projectionMatrix[3 * 4 + 0] = float(0); + projectionMatrix[3 * 4 + 1] = float(0); + projectionMatrix[3 * 4 + 2] = (float(2) * farVal * nearVal) / (nearVal - farVal); + projectionMatrix[3 * 4 + 3] = float(0); +} + + void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); - b3Vector3 camUpVector; - b3Vector3 camForward; - b3Vector3 camPos; - b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0],cameraTargetPosition[1],cameraTargetPosition[2]); - b3Vector3 eyePos = b3MakeVector3(0,0,0); - - int forwardAxis(-1); - - { - - switch (upAxis) - { - - case 1: - { - - - forwardAxis = 0; - eyePos[forwardAxis] = -distance; - camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]); - if (camForward.length2() < B3_EPSILON) - { - camForward.setValue(1.f,0.f,0.f); - } else - { - camForward.normalize(); - } - b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547); - b3Quaternion rollRot(camForward,rollRad); - - camUpVector = b3QuatRotate(rollRot,b3MakeVector3(0,1,0)); - //gLightPos = b3MakeVector3(-50.f,100,30); - break; - } - case 2: - { - - - forwardAxis = 1; - eyePos[forwardAxis] = -distance; - camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]); - if (camForward.length2() < B3_EPSILON) - { - camForward.setValue(1.f,0.f,0.f); - } else - { - camForward.normalize(); - } - - b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547); - b3Quaternion rollRot(camForward,rollRad); - - camUpVector = b3QuatRotate(rollRot,b3MakeVector3(0,0,1)); - //gLightPos = b3MakeVector3(-50.f,30,100); - break; - } - default: - { - //b3Assert(0); - return; - } - }; - } - - - b3Scalar yawRad = yaw * b3Scalar(0.01745329251994329547);// rads per deg - b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547);// rads per deg - - b3Quaternion pitchRot(camUpVector,pitchRad); - - b3Vector3 right = camUpVector.cross(camForward); - b3Quaternion yawRot(right,-yawRad); - - - - eyePos = b3Matrix3x3(pitchRot) * b3Matrix3x3(yawRot) * eyePos; - camPos = eyePos; - camPos += camTargetPos; - - float camPosf[4] = {camPos[0],camPos[1],camPos[2],0}; - float camPosTargetf[4] = {camTargetPos[0],camTargetPos[1],camTargetPos[2],0}; - float camUpf[4] = {camUpVector[0],camUpVector[1],camUpVector[2],0}; - - b3RequestCameraImageSetViewMatrix(commandHandle,camPosf,camPosTargetf,camUpf); + + b3ComputeViewMatrixFromYawPitchRoll(cameraTargetPosition, distance, yaw, pitch, roll, upAxis, command->m_requestPixelDataArguments.m_viewMatrix); + command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } + + + + void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle commandHandle, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]) { - b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]); - b3Vector3 center = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]); - b3Vector3 up = b3MakeVector3(cameraUp[0], cameraUp[1], cameraUp[2]); - b3Vector3 f = (center - eye).normalized(); - b3Vector3 u = up.normalized(); - b3Vector3 s = (f.cross(u)).normalized(); - u = s.cross(f); - - float viewMatrix[16]; - - viewMatrix[0*4+0] = s.x; - viewMatrix[1*4+0] = s.y; - viewMatrix[2*4+0] = s.z; - - viewMatrix[0*4+1] = u.x; - viewMatrix[1*4+1] = u.y; - viewMatrix[2*4+1] = u.z; - - viewMatrix[0*4+2] =-f.x; - viewMatrix[1*4+2] =-f.y; - viewMatrix[2*4+2] =-f.z; - - viewMatrix[0*4+3] = 0.f; - viewMatrix[1*4+3] = 0.f; - viewMatrix[2*4+3] = 0.f; - - viewMatrix[3*4+0] = -s.dot(eye); - viewMatrix[3*4+1] = -u.dot(eye); - viewMatrix[3*4+2] = f.dot(eye); - viewMatrix[3*4+3] = 1.f; + float viewMatrix[16]; + b3ComputeViewMatrixFromPositions(cameraPosition, cameraTargetPosition, cameraUp, viewMatrix); struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); - for (int i=0;i<16;i++) - { - command->m_requestPixelDataArguments.m_viewMatrix[i] = viewMatrix[i]; - } + + b3ComputeViewMatrixFromPositions(cameraPosition, cameraTargetPosition, cameraUp, command->m_requestPixelDataArguments.m_viewMatrix); + command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float left, float right, float bottom, float top, float nearVal, float farVal) { - float frustum[16]; - - frustum[0*4+0] = (float(2) * nearVal) / (right - left); - frustum[0*4+1] = float(0); - frustum[0*4+2] = float(0); - frustum[0*4+3] = float(0); - - frustum[1*4+0] = float(0); - frustum[1*4+1] = (float(2) * nearVal) / (top - bottom); - frustum[1*4+2] = float(0); - frustum[1*4+3] = float(0); - - frustum[2*4+0] = (right + left) / (right - left); - frustum[2*4+1] = (top + bottom) / (top - bottom); - frustum[2*4+2] = -(farVal + nearVal) / (farVal - nearVal); - frustum[2*4+3] = float(-1); - - frustum[3*4+0] = float(0); - frustum[3*4+1] = float(0); - frustum[3*4+2] = -(float(2) * farVal * nearVal) / (farVal - nearVal); - frustum[3*4+3] = float(0); struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); - for (int i=0;i<16;i++) - { - command->m_requestPixelDataArguments.m_projectionMatrix[i] = frustum[i]; - } + + b3ComputeProjectionMatrix(left, right, bottom, top, nearVal, farVal, command->m_requestPixelDataArguments.m_projectionMatrix); + command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle commandHandle, float fov, float aspect, float nearVal, float farVal) { - float yScale = 1.0 / tan((3.141592538 / 180.0) * fov / 2); - float xScale = yScale / aspect; - - float frustum[16]; - - frustum[0*4+0] = xScale; - frustum[0*4+1] = float(0); - frustum[0*4+2] = float(0); - frustum[0*4+3] = float(0); - - frustum[1*4+0] = float(0); - frustum[1*4+1] = yScale; - frustum[1*4+2] = float(0); - frustum[1*4+3] = float(0); - - frustum[2*4+0] = 0; - frustum[2*4+1] = 0; - frustum[2*4+2] = (nearVal + farVal) / (nearVal - farVal); - frustum[2*4+3] = float(-1); - - frustum[3*4+0] = float(0); - frustum[3*4+1] = float(0); - frustum[3*4+2] = (float(2) * farVal * nearVal) / (nearVal - farVal); - frustum[3*4+3] = float(0); + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); - for (int i=0;i<16;i++) - { - command->m_requestPixelDataArguments.m_projectionMatrix[i] = frustum[i]; - } + + b3ComputeProjectionMatrixFOV(fov, aspect, nearVal, farVal, command->m_requestPixelDataArguments.m_projectionMatrix); + command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES; } diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 18eba1c0a..529e50e94 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -95,14 +95,30 @@ int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle); ///request an image from a simulated camera, using a software renderer. b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); -void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]); -void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis); -void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal); -void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle command, float fov, float aspect, float nearVal, float farVal); void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); +void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]); void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer); void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); +///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices +void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]); +void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[16]); + +///compute a projection matrix, helper function for b3RequestCameraImageSetCameraMatrices +void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[16]); +void b3ComputeProjectionMatrixFOV(float fov, float aspect, float nearVal, float farVal, float projectionMatrix[16]); + + +/* obsolete, please use b3ComputeViewProjectionMatrices */ +void b3RequestCameraImageSetViewMatrix(b3SharedMemoryCommandHandle command, const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3]); +/* obsolete, please use b3ComputeViewProjectionMatrices */ +void b3RequestCameraImageSetViewMatrix2(b3SharedMemoryCommandHandle commandHandle, const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis); +/* obsolete, please use b3ComputeViewProjectionMatrices */ +void b3RequestCameraImageSetProjectionMatrix(b3SharedMemoryCommandHandle command, float left, float right, float bottom, float top, float nearVal, float farVal); +/* obsolete, please use b3ComputeViewProjectionMatrices */ +void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle command, float fov, float aspect, float nearVal, float farVal); + + ///request an contact point information b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient); void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 9791ab288..8bb278673 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1416,6 +1416,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { // printf("-------------------------------\nRendering\n"); + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION) != 0) + { + m_data->m_visualConverter.setLightDirection(clientCmd.m_requestPixelDataArguments.m_lightDirection[0], clientCmd.m_requestPixelDataArguments.m_lightDirection[1], clientCmd.m_requestPixelDataArguments.m_lightDirection[2]); + } if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0) { diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 715bdd11d..40b62f518 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -138,12 +138,14 @@ struct RequestPixelDataArgs int m_startPixelIndex; int m_pixelWidth; int m_pixelHeight; + float m_lightDirection[3]; }; enum EnumRequestPixelDataUpdateFlags { REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1, REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=4, + REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=8, //don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h }; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 643c7c1c0..676ca65d3 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -73,14 +73,17 @@ struct TinyRendererVisualShapeConverterInternalData b3AlignedObjectArray m_textures; b3AlignedObjectArray m_depthBuffer; b3AlignedObjectArray m_segmentationMaskBuffer; - + btVector3 m_lightDirection; + bool m_hasLightDirection; SimpleCamera m_camera; + TinyRendererVisualShapeConverterInternalData() :m_upAxis(2), m_swWidth(START_WIDTH), m_swHeight(START_HEIGHT), - m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB) + m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB), + m_hasLightDirection(false) { m_depthBuffer.resize(m_swWidth*m_swHeight); m_segmentationMaskBuffer.resize(m_swWidth*m_swHeight,-1); @@ -108,7 +111,11 @@ TinyRendererVisualShapeConverter::~TinyRendererVisualShapeConverter() delete m_data; } - +void TinyRendererVisualShapeConverter::setLightDirection(float x, float y, float z) +{ + m_data->m_lightDirection.setValue(x, y, z); + m_data->m_hasLightDirection = true; +} void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, b3VisualShapeData& visualShapeOut) @@ -677,16 +684,23 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo btVector3 lightDirWorld(-5,200,-40); - switch (m_data->m_upAxis) - { - case 1: - lightDirWorld = btVector3(-50.f,100,30); - break; - case 2: - lightDirWorld = btVector3(-50.f,30,100); - break; - default:{} - }; + if (m_data->m_hasLightDirection) + { + lightDirWorld = m_data->m_lightDirection; + } + else + { + switch (m_data->m_upAxis) + { + case 1: + lightDirWorld = btVector3(-50.f, 100, 30); + break; + case 2: + lightDirWorld = btVector3(-50.f, 30, 100); + break; + default: {} + }; + } lightDirWorld.normalize(); diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.h b/examples/SharedMemory/TinyRendererVisualShapeConverter.h index 48c5c1079..1a4a02f76 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.h +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.h @@ -32,7 +32,8 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter void getWidthAndHeight(int& width, int& height); void setWidthAndHeight(int width, int height); - + void setLightDirection(float x, float y, float z); + void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied); void render(); diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 47aaee9d9..17e782b8b 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1377,15 +1377,18 @@ static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) { PyObject* seq; seq = PySequence_Fast(objMat, "expected a sequence"); - len = PySequence_Size(objMat); - if (len == 16) { - for (i = 0; i < len; i++) { - matrix[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - Py_DECREF(seq); - return 1; + if (seq) + { + len = PySequence_Size(objMat); + if (len == 16) { + for (i = 0; i < len; i++) { + matrix[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + Py_DECREF(seq); + return 1; + } + Py_DECREF(seq); } - Py_DECREF(seq); return 0; } @@ -1397,20 +1400,24 @@ static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) { // vector - float[3] which will be set by values from objMat static int pybullet_internalSetVector(PyObject* objVec, float vector[3]) { int i, len; - PyObject* seq; + PyObject* seq=0; if (objVec==NULL) return 0; seq = PySequence_Fast(objVec, "expected a sequence"); - len = PySequence_Size(objVec); - if (len == 3) { - for (i = 0; i < len; i++) { - vector[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - Py_DECREF(seq); - return 1; + if (seq) + { + + len = PySequence_Size(objVec); + if (len == 3) { + for (i = 0; i < len; i++) { + vector[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + Py_DECREF(seq); + return 1; + } + Py_DECREF(seq); } - Py_DECREF(seq); return 0; } @@ -1422,15 +1429,18 @@ static int pybullet_internalSetVectord(PyObject* obVec, double vector[3]) { return 0; seq = PySequence_Fast(obVec, "expected a sequence"); - len = PySequence_Size(obVec); - if (len == 3) { - for (i = 0; i < len; i++) { - vector[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - Py_DECREF(seq); - return 1; - } - Py_DECREF(seq); + if (seq) + { + len = PySequence_Size(obVec); + if (len == 3) { + for (i = 0; i < len; i++) { + vector[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + Py_DECREF(seq); + return 1; + } + Py_DECREF(seq); + } return 0; } @@ -2196,6 +2206,302 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py return Py_None; } + + +/// Render an image from the current timestep of the simulation, width, height are required, other args are optional +// getCameraImage(w, h, view[16], projection[16], lightpos[3]) +static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds) +{ + /// request an image from a simulated camera, using a software renderer. + struct b3CameraImageData imageData; + PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0; + int width, height; + int size = PySequence_Size(args); + float viewMatrix[16]; + float projectionMatrix[16]; + float lightDir[3]; + // inialize cmd + b3SharedMemoryCommandHandle command; + + if (0 == sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + command = b3InitRequestCameraImage(sm); + + // set camera resolution, optionally view, projection matrix, light direction + static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection",NULL }; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOO", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj)) + { + return NULL; + } + b3RequestCameraImageSetPixelResolution(command, width, height); + + // set camera matrices only if set matrix function succeeds + if (pybullet_internalSetMatrix(objViewMat, viewMatrix) && (pybullet_internalSetMatrix(objProjMat, projectionMatrix))) + { + b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); + } + //set light pos only if function succeeds + if (pybullet_internalSetVector(lightDirObj, lightDir)) + { + b3RequestCameraImageSetLightDirection(command, lightDir); + } + + + if (b3CanSubmitCommand(sm)) + { + b3SharedMemoryStatusHandle statusHandle; + int statusType; + + // b3RequestCameraImageSelectRenderer(command,ER_BULLET_HARDWARE_OPENGL); + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + statusType = b3GetStatusType(statusHandle); + if (statusType == CMD_CAMERA_IMAGE_COMPLETED) { + PyObject* item2; + PyObject* pyResultList; // store 4 elements in this result: width, + // height, rgbData, depth + +#ifdef PYBULLET_USE_NUMPY + PyObject* pyRGB; + PyObject* pyDep; + PyObject* pySeg; + + int i, j, p; + + b3GetCameraImageData(sm, &imageData); + // TODO(hellojas): error handling if image size is 0 + pyResultList = PyTuple_New(5); + PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); + PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); + + int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values + + npy_intp rgb_dims[3] = { imageData.m_pixelHeight, imageData.m_pixelWidth, + bytesPerPixel }; + npy_intp dep_dims[2] = { imageData.m_pixelHeight, imageData.m_pixelWidth }; + npy_intp seg_dims[2] = { imageData.m_pixelHeight, imageData.m_pixelWidth }; + + pyRGB = PyArray_SimpleNew(3, rgb_dims, NPY_UINT8); + pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32); + pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32); + + memcpy(PyArray_DATA(pyRGB), imageData.m_rgbColorData, + imageData.m_pixelHeight * imageData.m_pixelWidth * bytesPerPixel); + memcpy(PyArray_DATA(pyDep), imageData.m_depthValues, + imageData.m_pixelHeight * imageData.m_pixelWidth); + memcpy(PyArray_DATA(pySeg), imageData.m_segmentationMaskValues, + imageData.m_pixelHeight * imageData.m_pixelWidth); + + PyTuple_SetItem(pyResultList, 2, pyRGB); + PyTuple_SetItem(pyResultList, 3, pyDep); + PyTuple_SetItem(pyResultList, 4, pySeg); +#else//PYBULLET_USE_NUMPY + PyObject* pylistRGB; + PyObject* pylistDep; + PyObject* pylistSeg; + + int i, j, p; + + b3GetCameraImageData(sm, &imageData); + // TODO(hellojas): error handling if image size is 0 + pyResultList = PyTuple_New(5); + PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth)); + PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight)); + + { + PyObject* item; + int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values + int num = + bytesPerPixel * imageData.m_pixelWidth * imageData.m_pixelHeight; + pylistRGB = PyTuple_New(num); + pylistDep = + PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight); + pylistSeg = + PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight); + for (i = 0; i < imageData.m_pixelWidth; i++) { + for (j = 0; j < imageData.m_pixelHeight; j++) { + // TODO(hellojas): validate depth values make sense + int depIndex = i + j * imageData.m_pixelWidth; + { + item = PyFloat_FromDouble(imageData.m_depthValues[depIndex]); + PyTuple_SetItem(pylistDep, depIndex, item); + } + { + item2 = + PyLong_FromLong(imageData.m_segmentationMaskValues[depIndex]); + PyTuple_SetItem(pylistSeg, depIndex, item2); + } + + for (p = 0; p < bytesPerPixel; p++) { + int pixelIndex = + bytesPerPixel * (i + j * imageData.m_pixelWidth) + p; + item = PyInt_FromLong(imageData.m_rgbColorData[pixelIndex]); + PyTuple_SetItem(pylistRGB, pixelIndex, item); + } + } + } + } + + PyTuple_SetItem(pyResultList, 2, pylistRGB); + PyTuple_SetItem(pyResultList, 3, pylistDep); + PyTuple_SetItem(pyResultList, 4, pylistSeg); + return pyResultList; +#endif//PYBULLET_USE_NUMPY + + return pyResultList; + } + } + + Py_INCREF(Py_None); + return Py_None; + +} + + + +static PyObject* pybullet_computeViewMatrix(PyObject* self, PyObject* args, PyObject *keywds) +{ + PyObject* camEyeObj = 0; + PyObject* camTargetPositionObj = 0; + PyObject* camUpVectorObj = 0; + float camEye[3]; + float camTargetPosition[3]; + float camUpVector[3]; + + // set camera resolution, optionally view, projection matrix, light position + static char *kwlist[] = { "cameraEyePosition", "cameraTargetPosition", "cameraUpVector",NULL }; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "OOO", kwlist, &camEyeObj, &camTargetPositionObj, &camUpVectorObj)) + { + return NULL; + } + + if (pybullet_internalSetVector(camEyeObj, camEye) && + pybullet_internalSetVector(camTargetPositionObj, camTargetPosition) && + pybullet_internalSetVector(camUpVectorObj, camUpVector)) + { + float viewMatrix[16]; + PyObject* pyResultList=0; + int i; + b3ComputeViewMatrixFromPositions(camEye, camTargetPosition, camUpVector, viewMatrix); + + pyResultList = PyTuple_New(16); + for (i = 0; i < 16; i++) + { + PyObject* item = PyFloat_FromDouble(viewMatrix[i]); + PyTuple_SetItem(pyResultList, i, item); + } + return pyResultList; + } + + PyErr_SetString(SpamError, "Error in computeViewMatrix."); + return NULL; +} + +///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices +static PyObject* pybullet_computeViewMatrixFromYawPitchRoll(PyObject* self, PyObject* args, PyObject *keywds) +{ + PyObject* cameraTargetPositionObj = 0; + float cameraTargetPosition[3]; + float distance, yaw, pitch, roll; + int upAxisIndex; + float viewMatrix[16]; + PyObject* pyResultList = 0; + int i; + + // set camera resolution, optionally view, projection matrix, light position + static char *kwlist[] = { "cameraTargetPosition", "distance", "yaw", "pitch", "roll", "upAxisIndex" ,NULL }; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "Offffi", kwlist, &cameraTargetPositionObj, &distance,&yaw,&pitch,&roll, &upAxisIndex)) + { + return NULL; + } + + if (!pybullet_internalSetVector(cameraTargetPositionObj, cameraTargetPosition)) + { + PyErr_SetString(SpamError, "Cannot convert cameraTargetPosition."); + return NULL; + } + + b3ComputeViewMatrixFromYawPitchRoll(cameraTargetPosition, distance, yaw, pitch, roll, upAxisIndex, viewMatrix); + + pyResultList = PyTuple_New(16); + for (i = 0; i < 16; i++) + { + PyObject* item = PyFloat_FromDouble(viewMatrix[i]); + PyTuple_SetItem(pyResultList, i, item); + } + return pyResultList; + + +} + +///compute a projection matrix, helper function for b3RequestCameraImageSetCameraMatrices +static PyObject* pybullet_computeProjectionMatrix(PyObject* self, PyObject* args, PyObject *keywds) +{ + PyObject* pyResultList = 0; + float left; + float right; + float bottom; + float top; + float nearVal; + float farVal; + float projectionMatrix[16]; + int i; + + // set camera resolution, optionally view, projection matrix, light position + static char *kwlist[] = { "left", "right", "bottom", "top", "nearVal", "farVal" ,NULL }; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ffffff", kwlist, &left, &right, &bottom, &top, &nearVal, &farVal)) + { + return NULL; + } + + + b3ComputeProjectionMatrix(left, right, bottom, top, nearVal, farVal, projectionMatrix); + + pyResultList = PyTuple_New(16); + for (i = 0; i < 16; i++) + { + PyObject* item = PyFloat_FromDouble(projectionMatrix[i]); + PyTuple_SetItem(pyResultList, i, item); + } + return pyResultList; + +} + +static PyObject* pybullet_computeProjectionMatrixFOV(PyObject* self, PyObject* args, PyObject *keywds) +{ + float fov, aspect, nearVal, farVal; + PyObject* pyResultList = 0; + float projectionMatrix[16]; + int i; + + static char *kwlist[] = { "fov","aspect","nearVal","farVal",NULL }; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ffff", kwlist, &fov, &aspect, &nearVal, &farVal)) + { + return NULL; + } + + b3ComputeProjectionMatrixFOV(fov, aspect, nearVal, farVal, projectionMatrix); + + pyResultList = PyTuple_New(16); + for (i = 0; i < 16; i++) + { + PyObject* item = PyFloat_FromDouble(projectionMatrix[i]); + PyTuple_SetItem(pyResultList, i, item); + } + return pyResultList; + +} + + // Render an image from the current timestep of the simulation // // Examples: @@ -2219,7 +2525,7 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py // TODO(hellojas): fix image is cut off at head // TODO(hellojas): should we add check to give minimum image resolution // to see object based on camera position? -static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) { +static PyObject* pybullet_renderImageObsolete(PyObject* self, PyObject* args) { /// request an image from a simulated camera, using a software renderer. struct b3CameraImageData imageData; PyObject* objViewMat, *objProjMat; @@ -2277,7 +2583,8 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) { b3RequestCameraImageSetPixelResolution(command, width, height); if (pybullet_internalSetVector(objCameraPos, cameraPos) && pybullet_internalSetVector(objTargetPos, targetPos) && - pybullet_internalSetVector(objCameraUp, cameraUp)) { + pybullet_internalSetVector(objCameraUp, cameraUp)) + { b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos, cameraUp); } else { @@ -3020,15 +3327,35 @@ static PyMethodDef SpamMethods[] = { "[x,y,z] in Cartesian coordinates, flag to select TORQUE_IN_LINK_FRAME or " "TORQUE_IN_WORLD_FRAME coordinates"}, - {"renderImage", pybullet_renderImage, METH_VARARGS, - "Render an image (given the pixel resolution width, height, camera view " - "matrix, projection matrix, near, and far values), and return the " - "8-8-8bit RGB pixel data and floating point depth values" -#ifdef PYBULLET_USE_NUMPY - " as NumPy arrays" -#endif + {"renderImage", pybullet_renderImageObsolete, METH_VARARGS, + "obsolete, please use getCameraImage and getViewProjectionMatrices instead" }, + { "getCameraImage",(PyCFunction)pybullet_getCameraImage, METH_VARARGS| METH_KEYWORDS, + "Render an image (given the pixel resolution width, height, camera viewMatrix " + ", projectionMatrix and lightDirection), and return the " + "8-8-8bit RGB pixel data and floating point depth values" +#ifdef PYBULLET_USE_NUMPY + " as NumPy arrays" +#endif + }, + + { "computeViewMatrix", (PyCFunction)pybullet_computeViewMatrix, METH_VARARGS | METH_KEYWORDS, + "Compute a camera viewmatrix from camera eye, target position and up vector " + }, + + { "computeViewMatrixFromYawPitchRoll",(PyCFunction)pybullet_computeViewMatrixFromYawPitchRoll, METH_VARARGS | METH_KEYWORDS, + "Compute a camera viewmatrix from camera eye, target position and up vector " + }, + + { "computeProjectionMatrix", (PyCFunction)pybullet_computeProjectionMatrix, METH_VARARGS | METH_KEYWORDS, + "Compute a camera projection matrix from screen left/right/bottom/top/near/far values" + }, + + { "computeProjectionMatrixFOV", (PyCFunction)pybullet_computeProjectionMatrixFOV, METH_VARARGS | METH_KEYWORDS, + "Compute a camera projection matrix from fov, aspect ratio, near, far values" + }, + {"getContactPoints", (PyCFunction)pybullet_getContactPointData, METH_VARARGS | METH_KEYWORDS, "Return existing contact points after the stepSimulation command. " "Optional arguments one or two object unique " diff --git a/examples/pybullet/test.py b/examples/pybullet/test.py index 1a184985f..762026246 100644 --- a/examples/pybullet/test.py +++ b/examples/pybullet/test.py @@ -3,7 +3,7 @@ import time #choose connection method: GUI, DIRECT, SHARED_MEMORY pybullet.connect(pybullet.GUI) - +pybullet.loadURDF("plane.urdf",0,0,-1) #load URDF, given a relative or absolute file+path obj = pybullet.loadURDF("r2d2.urdf") diff --git a/examples/pybullet/testrender.py b/examples/pybullet/testrender.py index da96bbbc5..5935c388f 100644 --- a/examples/pybullet/testrender.py +++ b/examples/pybullet/testrender.py @@ -5,7 +5,7 @@ import pybullet pybullet.connect(pybullet.GUI) pybullet.loadURDF("r2d2.urdf") -camTargetPos = [0,0,0] +camTargetPos = [0.,0.,0.] cameraUp = [0,0,1] cameraPos = [1,1,1] yaw = 40 @@ -18,29 +18,28 @@ pixelWidth = 320 pixelHeight = 240 nearPlane = 0.01 farPlane = 1000 - +lightDirection = [0,1,0] fov = 60 #img_arr = pybullet.renderImage(pixelWidth, pixelHeight) #renderImage(w, h, view[16], projection[16]) #img_arr = pybullet.renderImage(pixelWidth, pixelHeight, cameraPos, camTargetPos, cameraUp, nearPlane, farPlane) for pitch in range (0,360,10) : - img_arr = pybullet.renderImage(pixelWidth, pixelHeight, camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex, nearPlane, farPlane, fov) - - w=img_arr[0] #width of the image, in pixels - h=img_arr[1] #height of the image, in pixels - rgb=img_arr[2] #color data RGB - dep=img_arr[3] #depth data - - #print 'width = %d height = %d' % (w,h) - - # reshape creates np array - np_img_arr = np.reshape(rgb, (h, w, 4)) - np_img_arr = np_img_arr*(1./255.) - - #show - plt.imshow(np_img_arr,interpolation='none') - #plt.show() - plt.pause(0.01) + viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) + aspect = pixelWidth / pixelHeight; + projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); + img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection) + w=img_arr[0] + h=img_arr[1] + rgb=img_arr[2] + dep=img_arr[3] + #print 'width = %d height = %d' % (w,h) + # reshape creates np array + np_img_arr = np.reshape(rgb, (h, w, 4)) + np_img_arr = np_img_arr*(1./255.) + #show + plt.imshow(np_img_arr,interpolation='none') + + plt.pause(0.01) pybullet.resetSimulation() diff --git a/examples/pybullet/testrender_np.py b/examples/pybullet/testrender_np.py index 56439dde6..b8fca10eb 100644 --- a/examples/pybullet/testrender_np.py +++ b/examples/pybullet/testrender_np.py @@ -1,3 +1,6 @@ + +#make sure to compile pybullet with PYBULLET_USE_NUMPY enabled, otherwise use testrender.py (slower but compatible without numpy) + import numpy as np import matplotlib.pyplot as plt import pybullet @@ -23,28 +26,30 @@ farPlane = 1000 fov = 60 main_start = time.time() -#img_arr = pybullet.renderImage(pixelWidth, pixelHeight) -#renderImage(w, h, view[16], projection[16]) -#img_arr = pybullet.renderImage(pixelWidth, pixelHeight, cameraPos, camTargetPos, cameraUp, nearPlane, farPlane) for pitch in range (0,360,10) : - start = time.time() - img_arr = pybullet.renderImage(pixelWidth, pixelHeight, camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex, nearPlane, farPlane, fov) - stop = time.time() - print "renderImage %f" % (stop - start) + start = time.time() + viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) + aspect = pixelWidth / pixelHeight; + projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); + img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, [0,1,0]) + stop = time.time() + print ("renderImage %f" % (stop - start)) - w=img_arr[0] #width of the image, in pixels - h=img_arr[1] #height of the image, in pixels - rgb=img_arr[2] #color data RGB - dep=img_arr[3] #depth data + w=img_arr[0] #width of the image, in pixels + h=img_arr[1] #height of the image, in pixels + rgb=img_arr[2] #color data RGB + dep=img_arr[3] #depth data - #print 'width = %d height = %d' % (w,h) + print 'width = %d height = %d' % (w,h) - #show - plt.imshow(rgb,interpolation='none') - #plt.show() - plt.pause(0.01) + #note that sending the data to matplotlib is really slow + #show + plt.imshow(rgb,interpolation='none') + #plt.show() + plt.pause(0.01) main_stop = time.time() -print "Total time %f" % (main_stop - main_start) + +print ("Total time %f" % (main_stop - main_start)) pybullet.resetSimulation() From 936a104fb245c41af1d186632d44f1ce4e0cd904 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 18 Nov 2016 08:08:46 -0800 Subject: [PATCH 03/39] re-enable samurai.urdf loading for VR demo --- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 8bb278673..ee7d06624 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -3937,7 +3937,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() m_data->m_hasGround = true; loadUrdf("plane.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, true, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); -// loadUrdf("samurai.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); + loadUrdf("samurai.urdf", btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); // loadUrdf("quadruped/quadruped.urdf", btVector3(2, 2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); if (m_data->m_gripperRigidbodyFixed == 0) From 9ee1c4ec245ff0fc860fc56c78910d4ab0dd0579 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sat, 19 Nov 2016 17:13:56 -0800 Subject: [PATCH 04/39] regular OR wireframe rendering, not both add option to perform filtering of 'getClosestPoints' using linkA/linkB. don't use 'realtimesimulation' as default add/remove debug items within same thread pybullet, report contact points and normal as [x,y,z] triplet/vector, not 3 scalars separate 'getClosestPointsAlgorithm': box-box doesn't report closest points with positive distance, and the query shouldn't impact regular 'closesst points' --- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 2 +- examples/SharedMemory/PhysicsClientC_API.cpp | 33 +++ examples/SharedMemory/PhysicsClientC_API.h | 4 + .../PhysicsServerCommandProcessor.cpp | 36 ++- .../SharedMemory/PhysicsServerExample.cpp | 223 ++++++++---------- examples/SharedMemory/SharedMemoryCommands.h | 4 + examples/pybullet/pybullet.c | 112 +++++---- .../BroadphaseCollision/btDispatcher.h | 8 +- .../btCollisionConfiguration.h | 3 + .../btCollisionDispatcher.cpp | 28 ++- .../CollisionDispatch/btCollisionDispatcher.h | 8 +- .../CollisionDispatch/btCollisionWorld.cpp | 4 +- .../btCompoundCollisionAlgorithm.cpp | 39 ++- .../btCompoundCompoundCollisionAlgorithm.cpp | 29 ++- .../btConvexConcaveCollisionAlgorithm.cpp | 15 +- .../btDefaultCollisionConfiguration.cpp | 80 +++++++ .../btDefaultCollisionConfiguration.h | 2 + .../Gimpact/btGImpactCollisionAlgorithm.h | 2 +- .../btSoftBodyConcaveCollisionAlgorithm.cpp | 7 +- 19 files changed, 417 insertions(+), 222 deletions(-) diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index 962f04437..ca86cda97 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -1167,7 +1167,7 @@ void OpenGLExampleBrowser::update(float deltaTime) } BT_PROFILE("Render Scene"); sCurrentDemo->renderScene(); - } + } else { B3_PROFILE("physicsDebugDraw"); glPolygonMode( GL_FRONT_AND_BACK, GL_FILL ); diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index d0b0413f1..e61130446 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -1504,6 +1504,8 @@ b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClient command->m_requestContactPointArguments.m_startingContactPointIndex = 0; command->m_requestContactPointArguments.m_objectAIndexFilter = -1; command->m_requestContactPointArguments.m_objectBIndexFilter = -1; + command->m_requestContactPointArguments.m_linkIndexAIndexFilter = -2; + command->m_requestContactPointArguments.m_linkIndexBIndexFilter = -2; command->m_updateFlags = 0; return (b3SharedMemoryCommandHandle) command; } @@ -1516,6 +1518,37 @@ void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int body command->m_requestContactPointArguments.m_objectAIndexFilter = bodyUniqueIdA; } +void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CONTACT_POINT_INFORMATION); + command->m_updateFlags |= CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER; + command->m_requestContactPointArguments.m_linkIndexAIndexFilter= linkIndexA; +} + +void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CONTACT_POINT_INFORMATION); + command->m_updateFlags |= CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER; + command->m_requestContactPointArguments.m_linkIndexBIndexFilter = linkIndexB; +} + +void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA) +{ + b3SetContactFilterLinkA(commandHandle, linkIndexA); +} + +void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB) +{ + b3SetContactFilterLinkB(commandHandle, linkIndexB); +} + + + + void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 529e50e94..e9df467ec 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -123,12 +123,16 @@ void b3RequestCameraImageSetFOVProjectionMatrix(b3SharedMemoryCommandHandle comm b3SharedMemoryCommandHandle b3InitRequestContactPointInformation(b3PhysicsClientHandle physClient); void b3SetContactFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA); void b3SetContactFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB); +void b3SetContactFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); +void b3SetContactFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); void b3GetContactPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo); ///compute the closest points between two bodies b3SharedMemoryCommandHandle b3InitClosestDistanceQuery(b3PhysicsClientHandle physClient); void b3SetClosestDistanceFilterBodyA(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdA); +void b3SetClosestDistanceFilterLinkA(b3SharedMemoryCommandHandle commandHandle, int linkIndexA); void b3SetClosestDistanceFilterBodyB(b3SharedMemoryCommandHandle commandHandle, int bodyUniqueIdB); +void b3SetClosestDistanceFilterLinkB(b3SharedMemoryCommandHandle commandHandle, int linkIndexB); void b3SetClosestDistanceThreshold(b3SharedMemoryCommandHandle commandHandle, double distance); void b3GetClosestPointInformation(b3PhysicsClientHandle physClient, struct b3ContactInformation* contactPointInfo); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index ee7d06624..056784ada 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -542,7 +542,7 @@ struct PhysicsServerCommandProcessorInternalData m_kukaGripperMultiBody(0), m_kukaGripperRevolute1(0), m_kukaGripperRevolute2(0), - m_allowRealTimeSimulation(true), + m_allowRealTimeSimulation(false), m_huskyId(-1), m_KukaId(-1), m_sphereId(-1), @@ -2769,6 +2769,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm int bodyUniqueIdA = clientCmd.m_requestContactPointArguments.m_objectAIndexFilter; int bodyUniqueIdB = clientCmd.m_requestContactPointArguments.m_objectBIndexFilter; + bool hasLinkIndexAFilter = (0!=(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER)); + bool hasLinkIndexBFilter = (0!=(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER)); + + int linkIndexA = clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter; + int linkIndexB = clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter; + btAlignedObjectArray setA; btAlignedObjectArray setB; btAlignedObjectArray setALinkIndex; @@ -2783,15 +2789,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { if (bodyA->m_multiBody->getBaseCollider()) { - setA.push_back(bodyA->m_multiBody->getBaseCollider()); - setALinkIndex.push_back(-1); + if (!hasLinkIndexAFilter || (linkIndexA == -1)) + { + setA.push_back(bodyA->m_multiBody->getBaseCollider()); + setALinkIndex.push_back(-1); + } } for (int i = 0; i < bodyA->m_multiBody->getNumLinks(); i++) { if (bodyA->m_multiBody->getLink(i).m_collider) { - setA.push_back(bodyA->m_multiBody->getLink(i).m_collider); - setALinkIndex.push_back(i); + if (!hasLinkIndexAFilter || (linkIndexA == i)) + { + setA.push_back(bodyA->m_multiBody->getLink(i).m_collider); + setALinkIndex.push_back(i); + } } } } @@ -2811,15 +2823,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { if (bodyB->m_multiBody->getBaseCollider()) { - setB.push_back(bodyB->m_multiBody->getBaseCollider()); - setBLinkIndex.push_back(-1); + if (!hasLinkIndexBFilter || (linkIndexB == -1)) + { + setB.push_back(bodyB->m_multiBody->getBaseCollider()); + setBLinkIndex.push_back(-1); + } } for (int i = 0; i < bodyB->m_multiBody->getNumLinks(); i++) { if (bodyB->m_multiBody->getLink(i).m_collider) { - setB.push_back(bodyB->m_multiBody->getLink(i).m_collider); - setBLinkIndex.push_back(i); + if (!hasLinkIndexBFilter || (linkIndexB ==i)) + { + setB.push_back(bodyB->m_multiBody->getLink(i).m_collider); + setBLinkIndex.push_back(i); + } } } } diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index c4aa9455a..55cefb05a 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -126,10 +126,6 @@ enum MultiThreadedGUIHelperCommunicationEnums eGUIHelperRemoveAllGraphicsInstances, eGUIHelperCopyCameraImageData, eGUIHelperAutogenerateGraphicsObjects, - eGUIUserDebugAddText, - eGUIUserDebugAddLine, - eGUIUserDebugRemoveItem, - eGUIUserDebugRemoveAllItems, }; #include @@ -701,43 +697,36 @@ public: m_tmpText.m_textColorRGB[2] = textColorRGB[2]; m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugAddText); + m_userDebugText.push_back(m_tmpText); m_cs->unlock(); - while (m_cs->getSharedParam(1) != eGUIHelperIdle) - { - b3Clock::usleep(150); - } return m_userDebugText[m_userDebugText.size()-1].m_itemUniqueId; } btAlignedObjectArray m_userDebugLines; - UserDebugDrawLine m_tmpLine; virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime ) { - m_tmpLine.m_lifeTime = lifeTime; - m_tmpLine.m_lineWidth = lineWidth; - m_tmpLine.m_itemUniqueId = m_uidGenerator++; - m_tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0]; - m_tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1]; - m_tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2]; + UserDebugDrawLine tmpLine; - m_tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0]; - m_tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1]; - m_tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2]; + tmpLine.m_lifeTime = lifeTime; + tmpLine.m_lineWidth = lineWidth; + tmpLine.m_itemUniqueId = m_uidGenerator++; + tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0]; + tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1]; + tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2]; + + tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0]; + tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1]; + tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2]; - m_tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0]; - m_tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1]; - m_tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2]; + tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0]; + tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1]; + tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2]; m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugAddLine); + m_userDebugLines.push_back(tmpLine); m_cs->unlock(); - while (m_cs->getSharedParam(1) != eGUIHelperIdle) - { - b3Clock::usleep(150); - } return m_userDebugLines[m_userDebugLines.size()-1].m_itemUniqueId; } @@ -747,23 +736,38 @@ public: { m_removeDebugItemUid = debugItemUniqueId; m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugRemoveItem); - m_cs->unlock(); - while (m_cs->getSharedParam(1) != eGUIHelperIdle) + + for (int i = 0; iunlock(); + } virtual void removeAllUserDebugItems( ) { m_cs->lock(); - m_cs->setSharedParam(1, eGUIUserDebugRemoveAllItems); + m_userDebugLines.clear(); + m_userDebugText.clear(); + m_uidGenerator = 0; m_cs->unlock(); - while (m_cs->getSharedParam(1) != eGUIHelperIdle) - { - b3Clock::usleep(150); - } } @@ -825,6 +829,7 @@ public: virtual bool wantsTermination(); virtual bool isConnected(); virtual void renderScene(); + void drawUserDebugLines(); virtual void exitPhysics(); virtual void physicsDebugDraw(int debugFlags); @@ -1247,60 +1252,6 @@ void PhysicsServerExample::stepSimulation(float deltaTime) break; } - case eGUIUserDebugAddText: - { - m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText); - m_multiThreadedHelper->getCriticalSection()->lock(); - m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle); - m_multiThreadedHelper->getCriticalSection()->unlock(); - break; - } - case eGUIUserDebugAddLine: - { - m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine); - m_multiThreadedHelper->getCriticalSection()->lock(); - m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle); - m_multiThreadedHelper->getCriticalSection()->unlock(); - break; - } - case eGUIUserDebugRemoveItem: - { - for (int i=0;im_userDebugLines.size();i++) - { - if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid) - { - m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1); - m_multiThreadedHelper->m_userDebugLines.pop_back(); - break; - } - } - - - for (int i=0;im_userDebugText.size();i++) - { - if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid) - { - m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1); - m_multiThreadedHelper->m_userDebugText.pop_back(); - break; - } - } - - m_multiThreadedHelper->getCriticalSection()->lock(); - m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle); - m_multiThreadedHelper->getCriticalSection()->unlock(); - break; - } - case eGUIUserDebugRemoveAllItems: - { - m_multiThreadedHelper->m_userDebugLines.clear(); - m_multiThreadedHelper->m_userDebugText.clear(); - m_multiThreadedHelper->m_uidGenerator = 0; - m_multiThreadedHelper->getCriticalSection()->lock(); - m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle); - m_multiThreadedHelper->getCriticalSection()->unlock(); - break; - } case eGUIHelperIdle: { break; @@ -1353,7 +1304,53 @@ extern int gHuskyId; extern btTransform huskyTr; +void PhysicsServerExample::drawUserDebugLines() +{ + static char line0[1024]; + static char line1[1024]; + //draw all user-debug-lines + + //add array of lines + + //draw all user- 'text3d' messages + if (m_multiThreadedHelper) + { + m_args[0].m_cs->lock(); + for (int i = 0; im_userDebugLines.size(); i++) + { + btVector3 from; + from.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0], + m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1], + m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]); + btVector3 toX; + toX.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0], + m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1], + m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]); + + btVector3 color; + color.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0], + m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1], + m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]); + + + m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth); + } + + for (int i = 0; im_userDebugText.size(); i++) + { + m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text, + m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0], + m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1], + m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2], + m_multiThreadedHelper->m_userDebugText[i].textSize); + + } + m_args[0].m_cs->unlock(); + + } + +} void PhysicsServerExample::renderScene() { @@ -1369,48 +1366,8 @@ void PhysicsServerExample::renderScene() B3_PROFILE("PhysicsServerExample::RenderScene"); - static char line0[1024]; - static char line1[1024]; - - //draw all user-debug-lines - - //add array of lines - - //draw all user- 'text3d' messages - if (m_multiThreadedHelper) - { - - for (int i=0;im_userDebugLines.size();i++) - { - btVector3 from; - from.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0], - m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1], - m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]); - btVector3 toX; - toX.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0], - m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1], - m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]); - - btVector3 color; - color.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0], - m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1], - m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]); - - - m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth); - } - - for (int i=0;im_userDebugText.size();i++) - { - m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text, - m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0], - m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1], - m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2], - m_multiThreadedHelper->m_userDebugText[i].textSize); - - } - } + drawUserDebugLines(); if (gEnableRealTimeSimVR) { @@ -1424,6 +1381,7 @@ void PhysicsServerExample::renderScene() static int count = 0; count++; +#if 0 if (0 == (count & 1)) { btScalar curTime = m_clock.getTimeSeconds(); @@ -1444,6 +1402,7 @@ void PhysicsServerExample::renderScene() worseFps = 1000000; } } +#endif #ifdef BT_ENABLE_VR if ((gInternalSimFlags&2 ) && m_tinyVrGui==0) @@ -1544,6 +1503,8 @@ void PhysicsServerExample::renderScene() void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags) { + drawUserDebugLines(); + ///debug rendering m_physicsServer.physicsDebugDraw(debugDrawFlags); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 40b62f518..515fa5079 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -154,6 +154,8 @@ enum EnumRequestContactDataUpdateFlags { CMD_REQUEST_CONTACT_POINT_HAS_QUERY_MODE=1, CMD_REQUEST_CONTACT_POINT_HAS_CLOSEST_DISTANCE_THRESHOLD=2, + CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER = 4, + CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER = 8, }; struct RequestContactDataArgs @@ -161,6 +163,8 @@ struct RequestContactDataArgs int m_startingContactPointIndex; int m_objectAIndexFilter; int m_objectBIndexFilter; + int m_linkIndexAIndexFilter; + int m_linkIndexBIndexFilter; double m_closestDistanceThreshold; int m_mode; }; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 17e782b8b..8163fbd1b 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1501,7 +1501,7 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj res = pybullet_internalSetVectord(textPositionObj,posXYZ); if (!res) { - PyErr_SetString(SpamError, "Error converting lineFrom[3]"); + PyErr_SetString(SpamError, "Error converting textPositionObj[3]"); return NULL; } @@ -1510,7 +1510,7 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj res = pybullet_internalSetVectord(textColorRGBObj,colorRGB); if (!res) { - PyErr_SetString(SpamError, "Error converting lineTo[3]"); + PyErr_SetString(SpamError, "Error converting textColorRGBObj[3]"); return NULL; } } @@ -1848,23 +1848,22 @@ static PyObject* MyConvertContactPoint( struct b3ContactInformation* contactPoin 2 int m_bodyUniqueIdB; 3 int m_linkIndexA; 4 int m_linkIndexB; - 5-6-7 double m_positionOnAInWS[3];//contact point location on object A, + 5 double m_positionOnAInWS[3];//contact point location on object A, in world space coordinates - 8-9-10 double m_positionOnBInWS[3];//contact point location on object + 6 double m_positionOnBInWS[3];//contact point location on object A, in world space coordinates - 11-12-13 double m_contactNormalOnBInWS[3];//the separating contact + 7 double m_contactNormalOnBInWS[3];//the separating contact normal, pointing from object B towards object A - 14 double m_contactDistance;//negative number is penetration, positive + 8 double m_contactDistance;//negative number is penetration, positive is distance. - - 15 double m_normalForce; + 9 double m_normalForce; */ int i; PyObject* pyResultList = PyTuple_New(contactPointPtr->m_numContactPoints); for (i = 0; i < contactPointPtr->m_numContactPoints; i++) { - PyObject* contactObList = PyTuple_New(16); // see above 16 fields + PyObject* contactObList = PyTuple_New(10); // see above 10 fields PyObject* item; item = PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_contactFlags); @@ -1881,42 +1880,61 @@ static PyObject* MyConvertContactPoint( struct b3ContactInformation* contactPoin item = PyInt_FromLong(contactPointPtr->m_contactPointData[i].m_linkIndexB); PyTuple_SetItem(contactObList, 4, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnAInWS[0]); - PyTuple_SetItem(contactObList, 5, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnAInWS[1]); - PyTuple_SetItem(contactObList, 6, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnAInWS[2]); - PyTuple_SetItem(contactObList, 7, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnBInWS[0]); - PyTuple_SetItem(contactObList, 8, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnBInWS[1]); - PyTuple_SetItem(contactObList, 9, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_positionOnBInWS[2]); - PyTuple_SetItem(contactObList, 10, item); + { + PyObject* posAObj = PyTuple_New(3); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[0]); - PyTuple_SetItem(contactObList, 11, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[1]); - PyTuple_SetItem(contactObList, 12, item); - item = PyFloat_FromDouble( - contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[2]); - PyTuple_SetItem(contactObList, 13, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnAInWS[0]); + PyTuple_SetItem(posAObj, 0, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnAInWS[1]); + PyTuple_SetItem(posAObj, 1, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnAInWS[2]); + PyTuple_SetItem(posAObj, 2, item); + + PyTuple_SetItem(contactObList, 5, posAObj); + } + + { + PyObject* posBObj = PyTuple_New(3); + + + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnBInWS[0]); + PyTuple_SetItem(posBObj, 0, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnBInWS[1]); + PyTuple_SetItem(posBObj, 1, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_positionOnBInWS[2]); + PyTuple_SetItem(posBObj, 2, item); + + PyTuple_SetItem(contactObList, 6, posBObj); + + } + + { + PyObject* normalOnB = PyTuple_New(3); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[0]); + PyTuple_SetItem(normalOnB, 0, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[1]); + PyTuple_SetItem(normalOnB, 1, item); + item = PyFloat_FromDouble( + contactPointPtr->m_contactPointData[i].m_contactNormalOnBInWS[2]); + PyTuple_SetItem(normalOnB, 2, item); + PyTuple_SetItem(contactObList, 7, normalOnB); + } item = PyFloat_FromDouble( contactPointPtr->m_contactPointData[i].m_contactDistance); - PyTuple_SetItem(contactObList, 14, item); + PyTuple_SetItem(contactObList, 8, item); item = PyFloat_FromDouble( contactPointPtr->m_contactPointData[i].m_normalForce); - PyTuple_SetItem(contactObList, 15, item); + PyTuple_SetItem(contactObList, 9, item); PyTuple_SetItem(pyResultList, i, contactObList); } @@ -1982,6 +2000,9 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py int size = PySequence_Size(args); int bodyUniqueIdA = -1; int bodyUniqueIdB = -1; + int linkIndexA = -2; + int linkIndexB = -2; + double distanceThreshold = 0.f; b3SharedMemoryCommandHandle commandHandle; @@ -1991,15 +2012,15 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py PyObject* pyResultList = 0; - static char *kwlist[] = { "bodyA", "bodyB", "distance", NULL }; + static char *kwlist[] = { "bodyA", "bodyB", "distance", "linkIndexA","linkIndexB",NULL }; if (0 == sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid", kwlist, - &bodyUniqueIdA, &bodyUniqueIdB, &distanceThreshold)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "iid|ii", kwlist, + &bodyUniqueIdA, &bodyUniqueIdB, &distanceThreshold, &linkIndexA, &linkIndexB)) return NULL; @@ -2007,7 +2028,14 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py b3SetClosestDistanceFilterBodyA(commandHandle, bodyUniqueIdA); b3SetClosestDistanceFilterBodyB(commandHandle, bodyUniqueIdB); b3SetClosestDistanceThreshold(commandHandle, distanceThreshold); - + if (linkIndexA >= -1) + { + b3SetClosestDistanceFilterLinkA(commandHandle, linkIndexA); + } + if (linkIndexB >= -1) + { + b3SetClosestDistanceFilterLinkB(commandHandle, linkIndexB); + } statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); diff --git a/src/BulletCollision/BroadphaseCollision/btDispatcher.h b/src/BulletCollision/BroadphaseCollision/btDispatcher.h index 89c307d14..7b0f9489a 100644 --- a/src/BulletCollision/BroadphaseCollision/btDispatcher.h +++ b/src/BulletCollision/BroadphaseCollision/btDispatcher.h @@ -64,6 +64,12 @@ struct btDispatcherInfo btScalar m_convexConservativeDistanceThreshold; }; +enum ebtDispatcherQueryType +{ + BT_CONTACT_POINT_ALGORITHMS = 1, + BT_CLOSEST_POINT_ALGORITHMS = 2 +}; + ///The btDispatcher interface class can be used in combination with broadphase to dispatch calculations for overlapping pairs. ///For example for pairwise collision detection, calculating contact points stored in btPersistentManifold or user callbacks (game logic). class btDispatcher @@ -73,7 +79,7 @@ class btDispatcher public: virtual ~btDispatcher() ; - virtual btCollisionAlgorithm* findAlgorithm(const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btPersistentManifold* sharedManifold=0) = 0; + virtual btCollisionAlgorithm* findAlgorithm(const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btPersistentManifold* sharedManifold, ebtDispatcherQueryType queryType) = 0; virtual btPersistentManifold* getNewManifold(const btCollisionObject* b0,const btCollisionObject* b1)=0; diff --git a/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h b/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h index 669498494..35f77d4e6 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionConfiguration.h @@ -40,6 +40,9 @@ public: virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0,int proxyType1) =0; + virtual btCollisionAlgorithmCreateFunc* getClosestPointsAlgorithmCreateFunc(int proxyType0, int proxyType1) = 0; + + }; #endif //BT_COLLISION_CONFIGURATION diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp index cf1adbefa..737067ef9 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.cpp @@ -50,8 +50,10 @@ m_dispatcherFlags(btCollisionDispatcher::CD_USE_RELATIVE_CONTACT_BREAKING_THRESH { for (int j=0;jgetCollisionAlgorithmCreateFunc(i,j); - btAssert(m_doubleDispatch[i][j]); + m_doubleDispatchContactPoints[i][j] = m_collisionConfiguration->getCollisionAlgorithmCreateFunc(i,j); + btAssert(m_doubleDispatchContactPoints[i][j]); + m_doubleDispatchClosestPoints[i][j] = m_collisionConfiguration->getClosestPointsAlgorithmCreateFunc(i, j); + } } @@ -61,7 +63,12 @@ m_dispatcherFlags(btCollisionDispatcher::CD_USE_RELATIVE_CONTACT_BREAKING_THRESH void btCollisionDispatcher::registerCollisionCreateFunc(int proxyType0, int proxyType1, btCollisionAlgorithmCreateFunc *createFunc) { - m_doubleDispatch[proxyType0][proxyType1] = createFunc; + m_doubleDispatchContactPoints[proxyType0][proxyType1] = createFunc; +} + +void btCollisionDispatcher::registerClosestPointsCreateFunc(int proxyType0, int proxyType1, btCollisionAlgorithmCreateFunc *createFunc) +{ + m_doubleDispatchClosestPoints[proxyType0][proxyType1] = createFunc; } btCollisionDispatcher::~btCollisionDispatcher() @@ -138,14 +145,23 @@ void btCollisionDispatcher::releaseManifold(btPersistentManifold* manifold) -btCollisionAlgorithm* btCollisionDispatcher::findAlgorithm(const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btPersistentManifold* sharedManifold) + +btCollisionAlgorithm* btCollisionDispatcher::findAlgorithm(const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btPersistentManifold* sharedManifold, ebtDispatcherQueryType algoType) { btCollisionAlgorithmConstructionInfo ci; ci.m_dispatcher1 = this; ci.m_manifold = sharedManifold; - btCollisionAlgorithm* algo = m_doubleDispatch[body0Wrap->getCollisionShape()->getShapeType()][body1Wrap->getCollisionShape()->getShapeType()]->CreateCollisionAlgorithm(ci,body0Wrap,body1Wrap); + btCollisionAlgorithm* algo = 0; + if (algoType == BT_CONTACT_POINT_ALGORITHMS) + { + algo = m_doubleDispatchContactPoints[body0Wrap->getCollisionShape()->getShapeType()][body1Wrap->getCollisionShape()->getShapeType()]->CreateCollisionAlgorithm(ci, body0Wrap, body1Wrap); + } + else + { + algo = m_doubleDispatchClosestPoints[body0Wrap->getCollisionShape()->getShapeType()][body1Wrap->getCollisionShape()->getShapeType()]->CreateCollisionAlgorithm(ci, body0Wrap, body1Wrap); + } return algo; } @@ -262,7 +278,7 @@ void btCollisionDispatcher::defaultNearCallback(btBroadphasePair& collisionPair, //dispatcher will keep algorithms persistent in the collision pair if (!collisionPair.m_algorithm) { - collisionPair.m_algorithm = dispatcher.findAlgorithm(&obj0Wrap,&obj1Wrap); + collisionPair.m_algorithm = dispatcher.findAlgorithm(&obj0Wrap,&obj1Wrap,0, BT_CONTACT_POINT_ALGORITHMS); } if (collisionPair.m_algorithm) diff --git a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h index 92696ee54..b97ee3c1b 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionDispatcher.h @@ -57,7 +57,9 @@ protected: btPoolAllocator* m_persistentManifoldPoolAllocator; - btCollisionAlgorithmCreateFunc* m_doubleDispatch[MAX_BROADPHASE_COLLISION_TYPES][MAX_BROADPHASE_COLLISION_TYPES]; + btCollisionAlgorithmCreateFunc* m_doubleDispatchContactPoints[MAX_BROADPHASE_COLLISION_TYPES][MAX_BROADPHASE_COLLISION_TYPES]; + + btCollisionAlgorithmCreateFunc* m_doubleDispatchClosestPoints[MAX_BROADPHASE_COLLISION_TYPES][MAX_BROADPHASE_COLLISION_TYPES]; btCollisionConfiguration* m_collisionConfiguration; @@ -84,6 +86,8 @@ public: ///registerCollisionCreateFunc allows registration of custom/alternative collision create functions void registerCollisionCreateFunc(int proxyType0,int proxyType1, btCollisionAlgorithmCreateFunc* createFunc); + void registerClosestPointsCreateFunc(int proxyType0, int proxyType1, btCollisionAlgorithmCreateFunc *createFunc); + int getNumManifolds() const { return int( m_manifoldsPtr.size()); @@ -115,7 +119,7 @@ public: virtual void clearManifold(btPersistentManifold* manifold); - btCollisionAlgorithm* findAlgorithm(const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btPersistentManifold* sharedManifold = 0); + btCollisionAlgorithm* findAlgorithm(const btCollisionObjectWrapper* body0Wrap,const btCollisionObjectWrapper* body1Wrap,btPersistentManifold* sharedManifold, ebtDispatcherQueryType queryType); virtual bool needsCollision(const btCollisionObject* body0,const btCollisionObject* body1); diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp index 3196369e1..133994112 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp @@ -1231,7 +1231,7 @@ struct btSingleContactCallback : public btBroadphaseAabbCallback btCollisionObjectWrapper ob0(0,m_collisionObject->getCollisionShape(),m_collisionObject,m_collisionObject->getWorldTransform(),-1,-1); btCollisionObjectWrapper ob1(0,collisionObject->getCollisionShape(),collisionObject,collisionObject->getWorldTransform(),-1,-1); - btCollisionAlgorithm* algorithm = m_world->getDispatcher()->findAlgorithm(&ob0,&ob1); + btCollisionAlgorithm* algorithm = m_world->getDispatcher()->findAlgorithm(&ob0,&ob1,0, BT_CLOSEST_POINT_ALGORITHMS); if (algorithm) { btBridgedManifoldResult contactPointResult(&ob0,&ob1, m_resultCallback); @@ -1267,7 +1267,7 @@ void btCollisionWorld::contactPairTest(btCollisionObject* colObjA, btCollisionOb btCollisionObjectWrapper obA(0,colObjA->getCollisionShape(),colObjA,colObjA->getWorldTransform(),-1,-1); btCollisionObjectWrapper obB(0,colObjB->getCollisionShape(),colObjB,colObjB->getWorldTransform(),-1,-1); - btCollisionAlgorithm* algorithm = getDispatcher()->findAlgorithm(&obA,&obB); + btCollisionAlgorithm* algorithm = getDispatcher()->findAlgorithm(&obA,&obB, 0, BT_CLOSEST_POINT_ALGORITHMS); if (algorithm) { btBridgedManifoldResult contactPointResult(&obA,&obB, resultCallback); diff --git a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp index 13cddc11a..1fc960df5 100644 --- a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp @@ -65,7 +65,13 @@ void btCompoundCollisionAlgorithm::preallocateChildAlgorithms(const btCollisionO const btCollisionShape* childShape = compoundShape->getChildShape(i); btCollisionObjectWrapper childWrap(colObjWrap,childShape,colObjWrap->getCollisionObject(),colObjWrap->getWorldTransform(),-1,i);//wrong child trans, but unused (hopefully) - m_childCollisionAlgorithms[i] = m_dispatcher->findAlgorithm(&childWrap,otherObjWrap,m_sharedManifold); + m_childCollisionAlgorithms[i] = m_dispatcher->findAlgorithm(&childWrap,otherObjWrap,m_sharedManifold, BT_CONTACT_POINT_ALGORITHMS); + + + btAlignedObjectArray m_childCollisionAlgorithmsContact; + btAlignedObjectArray m_childCollisionAlgorithmsClosestPoints; + + } } } @@ -128,8 +134,14 @@ public: btTransform newChildWorldTrans = orgTrans*childTrans ; //perform an AABB check first - btVector3 aabbMin0,aabbMax0,aabbMin1,aabbMax1; + btVector3 aabbMin0,aabbMax0; childShape->getAabb(newChildWorldTrans,aabbMin0,aabbMax0); + + btVector3 extendAabb(m_resultOut->m_closestPointDistanceThreshold, m_resultOut->m_closestPointDistanceThreshold, m_resultOut->m_closestPointDistanceThreshold); + aabbMin0 -= extendAabb; + aabbMax0 += extendAabb; + + btVector3 aabbMin1, aabbMax1; m_otherObjWrap->getCollisionShape()->getAabb(m_otherObjWrap->getWorldTransform(),aabbMin1,aabbMax1); if (gCompoundChildShapePairCallback) @@ -142,12 +154,22 @@ public: { btCollisionObjectWrapper compoundWrap(this->m_compoundColObjWrap,childShape,m_compoundColObjWrap->getCollisionObject(),newChildWorldTrans,-1,index); + + btCollisionAlgorithm* algo = 0; - - //the contactpoint is still projected back using the original inverted worldtrans - if (!m_childCollisionAlgorithms[index]) - m_childCollisionAlgorithms[index] = m_dispatcher->findAlgorithm(&compoundWrap,m_otherObjWrap,m_sharedManifold); - + if (m_resultOut->m_closestPointDistanceThreshold > 0) + { + algo = m_dispatcher->findAlgorithm(&compoundWrap, m_otherObjWrap, 0, BT_CLOSEST_POINT_ALGORITHMS); + } + else + { + //the contactpoint is still projected back using the original inverted worldtrans + if (!m_childCollisionAlgorithms[index]) + { + m_childCollisionAlgorithms[index] = m_dispatcher->findAlgorithm(&compoundWrap, m_otherObjWrap, m_sharedManifold, BT_CONTACT_POINT_ALGORITHMS); + } + algo = m_childCollisionAlgorithms[index]; + } const btCollisionObjectWrapper* tmpWrap = 0; @@ -164,8 +186,7 @@ public: m_resultOut->setShapeIdentifiersB(-1,index); } - - m_childCollisionAlgorithms[index]->processCollision(&compoundWrap,m_otherObjWrap,m_dispatchInfo,m_resultOut); + algo->processCollision(&compoundWrap,m_otherObjWrap,m_dispatchInfo,m_resultOut); #if 0 if (m_dispatchInfo.m_debugDraw && (m_dispatchInfo.m_debugDraw->getDebugMode() & btIDebugDraw::DBG_DrawAabb)) diff --git a/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp index fcaa9f851..8dd7e4403 100644 --- a/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btCompoundCompoundCollisionAlgorithm.cpp @@ -164,9 +164,7 @@ struct btCompoundCompoundLeafCallback : btDbvt::ICollide btVector3 thresholdVec(m_resultOut->m_closestPointDistanceThreshold, m_resultOut->m_closestPointDistanceThreshold, m_resultOut->m_closestPointDistanceThreshold); aabbMin0 -= thresholdVec; - aabbMin1 -= thresholdVec; aabbMax0 += thresholdVec; - aabbMax1 += thresholdVec; if (gCompoundCompoundChildShapePairCallback) { @@ -183,17 +181,24 @@ struct btCompoundCompoundLeafCallback : btDbvt::ICollide btSimplePair* pair = m_childCollisionAlgorithmCache->findPair(childIndex0,childIndex1); btCollisionAlgorithm* colAlgo = 0; + if (m_resultOut->m_closestPointDistanceThreshold > 0) + { + colAlgo = m_dispatcher->findAlgorithm(&compoundWrap0, &compoundWrap1, 0, BT_CLOSEST_POINT_ALGORITHMS); + } + else + { + if (pair) + { + colAlgo = (btCollisionAlgorithm*)pair->m_userPointer; - if (pair) - { - colAlgo = (btCollisionAlgorithm*)pair->m_userPointer; - - } else - { - colAlgo = m_dispatcher->findAlgorithm(&compoundWrap0,&compoundWrap1,m_sharedManifold); - pair = m_childCollisionAlgorithmCache->addOverlappingPair(childIndex0,childIndex1); - btAssert(pair); - pair->m_userPointer = colAlgo; + } + else + { + colAlgo = m_dispatcher->findAlgorithm(&compoundWrap0, &compoundWrap1, m_sharedManifold, BT_CONTACT_POINT_ALGORITHMS); + pair = m_childCollisionAlgorithmCache->addOverlappingPair(childIndex0, childIndex1); + btAssert(pair); + pair->m_userPointer = colAlgo; + } } btAssert(colAlgo); diff --git a/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp index 322b1288d..c774383dc 100644 --- a/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btConvexConcaveCollisionAlgorithm.cpp @@ -118,8 +118,16 @@ partId, int triangleIndex) btCollisionObjectWrapper triObWrap(m_triBodyWrap,&tm,m_triBodyWrap->getCollisionObject(),m_triBodyWrap->getWorldTransform(),partId,triangleIndex);//correct transform? - btCollisionAlgorithm* colAlgo = ci.m_dispatcher1->findAlgorithm(m_convexBodyWrap,&triObWrap,m_manifoldPtr); - + btCollisionAlgorithm* colAlgo = 0; + + if (m_resultOut->m_closestPointDistanceThreshold > 0) + { + colAlgo = ci.m_dispatcher1->findAlgorithm(m_convexBodyWrap, &triObWrap, 0, BT_CLOSEST_POINT_ALGORITHMS); + } + else + { + colAlgo = ci.m_dispatcher1->findAlgorithm(m_convexBodyWrap, &triObWrap, m_manifoldPtr, BT_CONTACT_POINT_ALGORITHMS); + } const btCollisionObjectWrapper* tmpWrap = 0; if (m_resultOut->getBody0Internal() == m_triBodyWrap->getCollisionObject()) @@ -170,7 +178,8 @@ void btConvexTriangleCallback::setTimeStepAndCounters(btScalar collisionMarginTr const btCollisionShape* convexShape = static_cast(m_convexBodyWrap->getCollisionShape()); //CollisionShape* triangleShape = static_cast(triBody->m_collisionShape); convexShape->getAabb(convexInTriangleSpace,m_aabbMin,m_aabbMax); - btScalar extraMargin = collisionMarginTriangle; + btScalar extraMargin = collisionMarginTriangle+ resultOut->m_closestPointDistanceThreshold; + btVector3 extra(extraMargin,extraMargin,extraMargin); m_aabbMax += extra; diff --git a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp index 9e04d2aae..f6e4e57b0 100644 --- a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp +++ b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.cpp @@ -198,6 +198,86 @@ btDefaultCollisionConfiguration::~btDefaultCollisionConfiguration() } +btCollisionAlgorithmCreateFunc* btDefaultCollisionConfiguration::getClosestPointsAlgorithmCreateFunc(int proxyType0, int proxyType1) +{ + + + if ((proxyType0 == SPHERE_SHAPE_PROXYTYPE) && (proxyType1 == SPHERE_SHAPE_PROXYTYPE)) + { + return m_sphereSphereCF; + } +#ifdef USE_BUGGY_SPHERE_BOX_ALGORITHM + if ((proxyType0 == SPHERE_SHAPE_PROXYTYPE) && (proxyType1 == BOX_SHAPE_PROXYTYPE)) + { + return m_sphereBoxCF; + } + + if ((proxyType0 == BOX_SHAPE_PROXYTYPE) && (proxyType1 == SPHERE_SHAPE_PROXYTYPE)) + { + return m_boxSphereCF; + } +#endif //USE_BUGGY_SPHERE_BOX_ALGORITHM + + + if ((proxyType0 == SPHERE_SHAPE_PROXYTYPE) && (proxyType1 == TRIANGLE_SHAPE_PROXYTYPE)) + { + return m_sphereTriangleCF; + } + + if ((proxyType0 == TRIANGLE_SHAPE_PROXYTYPE) && (proxyType1 == SPHERE_SHAPE_PROXYTYPE)) + { + return m_triangleSphereCF; + } + + if (btBroadphaseProxy::isConvex(proxyType0) && (proxyType1 == STATIC_PLANE_PROXYTYPE)) + { + return m_convexPlaneCF; + } + + if (btBroadphaseProxy::isConvex(proxyType1) && (proxyType0 == STATIC_PLANE_PROXYTYPE)) + { + return m_planeConvexCF; + } + + + + if (btBroadphaseProxy::isConvex(proxyType0) && btBroadphaseProxy::isConvex(proxyType1)) + { + return m_convexConvexCreateFunc; + } + + if (btBroadphaseProxy::isConvex(proxyType0) && btBroadphaseProxy::isConcave(proxyType1)) + { + return m_convexConcaveCreateFunc; + } + + if (btBroadphaseProxy::isConvex(proxyType1) && btBroadphaseProxy::isConcave(proxyType0)) + { + return m_swappedConvexConcaveCreateFunc; + } + + + if (btBroadphaseProxy::isCompound(proxyType0) && btBroadphaseProxy::isCompound(proxyType1)) + { + return m_compoundCompoundCreateFunc; + } + + if (btBroadphaseProxy::isCompound(proxyType0)) + { + return m_compoundCreateFunc; + } + else + { + if (btBroadphaseProxy::isCompound(proxyType1)) + { + return m_swappedCompoundCreateFunc; + } + } + + //failed to find an algorithm + return m_emptyCreateFunc; + +} btCollisionAlgorithmCreateFunc* btDefaultCollisionConfiguration::getCollisionAlgorithmCreateFunc(int proxyType0,int proxyType1) { diff --git a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h index 93a45126b..17c7596cf 100644 --- a/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h +++ b/src/BulletCollision/CollisionDispatch/btDefaultCollisionConfiguration.h @@ -103,6 +103,8 @@ public: virtual btCollisionAlgorithmCreateFunc* getCollisionAlgorithmCreateFunc(int proxyType0,int proxyType1); + virtual btCollisionAlgorithmCreateFunc* getClosestPointsAlgorithmCreateFunc(int proxyType0, int proxyType1); + ///Use this method to allow to generate multiple contact points between at once, between two objects using the generic convex-convex algorithm. ///By default, this feature is disabled for best performance. ///@param numPerturbationIterations controls the number of collision queries. Set it to zero to disable the feature. diff --git a/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h b/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h index f85a94cb4..3e5675f72 100644 --- a/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h +++ b/src/BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h @@ -122,7 +122,7 @@ protected: checkManifold(body0Wrap,body1Wrap); btCollisionAlgorithm * convex_algorithm = m_dispatcher->findAlgorithm( - body0Wrap,body1Wrap,getLastManifold()); + body0Wrap,body1Wrap,getLastManifold(), BT_CONTACT_POINT_ALGORITHMS); return convex_algorithm ; } diff --git a/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp b/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp index 9f0d44526..ab84bddf2 100644 --- a/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp +++ b/src/BulletSoftBody/btSoftBodyConcaveCollisionAlgorithm.cpp @@ -120,8 +120,8 @@ void btSoftBodyTriangleCallback::processTriangle(btVector3* triangle,int partId, btCollisionObjectWrapper softBody(0,m_softBody->getCollisionShape(),m_softBody,m_softBody->getWorldTransform(),-1,-1); //btCollisionObjectWrapper triBody(0,tm, ob, btTransform::getIdentity());//ob->getWorldTransform());//?? btCollisionObjectWrapper triBody(0,tm, m_triBody, m_triBody->getWorldTransform(),partId, triangleIndex); - - btCollisionAlgorithm* colAlgo = ci.m_dispatcher1->findAlgorithm(&softBody,&triBody,0);//m_manifoldPtr); + ebtDispatcherQueryType algoType = m_resultOut->m_closestPointDistanceThreshold > 0 ? BT_CLOSEST_POINT_ALGORITHMS : BT_CONTACT_POINT_ALGORITHMS; + btCollisionAlgorithm* colAlgo = ci.m_dispatcher1->findAlgorithm(&softBody,&triBody,0, algoType);//m_manifoldPtr); colAlgo->processCollision(&softBody,&triBody,*m_dispatchInfoPtr,m_resultOut); colAlgo->~btCollisionAlgorithm(); @@ -164,7 +164,8 @@ void btSoftBodyTriangleCallback::processTriangle(btVector3* triangle,int partId, btCollisionObjectWrapper softBody(0,m_softBody->getCollisionShape(),m_softBody,m_softBody->getWorldTransform(),-1,-1); btCollisionObjectWrapper triBody(0,tm, m_triBody, m_triBody->getWorldTransform(),partId, triangleIndex);//btTransform::getIdentity());//?? - btCollisionAlgorithm* colAlgo = ci.m_dispatcher1->findAlgorithm(&softBody,&triBody,0);//m_manifoldPtr); + ebtDispatcherQueryType algoType = m_resultOut->m_closestPointDistanceThreshold > 0 ? BT_CLOSEST_POINT_ALGORITHMS : BT_CONTACT_POINT_ALGORITHMS; + btCollisionAlgorithm* colAlgo = ci.m_dispatcher1->findAlgorithm(&softBody,&triBody,0, algoType);//m_manifoldPtr); colAlgo->processCollision(&softBody,&triBody,*m_dispatchInfoPtr,m_resultOut); colAlgo->~btCollisionAlgorithm(); From 93ba8af0238bc0b6e4f5bcc732f533c34fcce6cf Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sun, 20 Nov 2016 12:52:12 -0800 Subject: [PATCH 05/39] Add shared memory API to change light color. --- examples/SharedMemory/PhysicsClientC_API.cpp | 11 +++++++++++ examples/SharedMemory/PhysicsClientC_API.h | 1 + .../PhysicsServerCommandProcessor.cpp | 5 +++++ examples/SharedMemory/SharedMemoryCommands.h | 6 ++++-- .../TinyRendererVisualShapeConverter.cpp | 19 +++++++++++++++++-- .../TinyRendererVisualShapeConverter.h | 1 + examples/TinyRenderer/TinyRenderer.cpp | 11 +++++++++-- examples/TinyRenderer/TinyRenderer.h | 1 + 8 files changed, 49 insertions(+), 6 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index d0b0413f1..1edfc5edf 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -1244,6 +1244,17 @@ void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHa command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION; } +void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + for (int i = 0; i<3; i++) + { + command->m_requestPixelDataArguments.m_lightColor[i] = lightColor[i]; + } + command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR; +} void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]) { diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 529e50e94..023962c2a 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -97,6 +97,7 @@ b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physC void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]); +void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]); void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer); void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index ee7d06624..373f11989 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1420,6 +1420,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { m_data->m_visualConverter.setLightDirection(clientCmd.m_requestPixelDataArguments.m_lightDirection[0], clientCmd.m_requestPixelDataArguments.m_lightDirection[1], clientCmd.m_requestPixelDataArguments.m_lightDirection[2]); } + + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR) != 0) + { + m_data->m_visualConverter.setLightColor(clientCmd.m_requestPixelDataArguments.m_lightColor[0], clientCmd.m_requestPixelDataArguments.m_lightColor[1], clientCmd.m_requestPixelDataArguments.m_lightColor[2]); + } if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0) { diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 40b62f518..07c40d90c 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -139,13 +139,15 @@ struct RequestPixelDataArgs int m_pixelWidth; int m_pixelHeight; float m_lightDirection[3]; + float m_lightColor[3]; }; enum EnumRequestPixelDataUpdateFlags { REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1, - REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=4, - REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=8, + REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=2, + REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=4, + REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR=8, //don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h }; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 676ca65d3..34478bee7 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -75,6 +75,8 @@ struct TinyRendererVisualShapeConverterInternalData b3AlignedObjectArray m_segmentationMaskBuffer; btVector3 m_lightDirection; bool m_hasLightDirection; + btVector3 m_lightColor; + bool m_hasLightColor; SimpleCamera m_camera; @@ -83,7 +85,8 @@ struct TinyRendererVisualShapeConverterInternalData m_swWidth(START_WIDTH), m_swHeight(START_HEIGHT), m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB), - m_hasLightDirection(false) + m_hasLightDirection(false), + m_hasLightColor(false) { m_depthBuffer.resize(m_swWidth*m_swHeight); m_segmentationMaskBuffer.resize(m_swWidth*m_swHeight,-1); @@ -117,6 +120,11 @@ void TinyRendererVisualShapeConverter::setLightDirection(float x, float y, float m_data->m_hasLightDirection = true; } +void TinyRendererVisualShapeConverter::setLightColor(float x, float y, float z) +{ + m_data->m_lightColor.setValue(x, y, z); + m_data->m_hasLightColor = true; +} void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, b3VisualShapeData& visualShapeOut) { @@ -704,6 +712,12 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo lightDirWorld.normalize(); + btVector3 lightColor(1.0,1.0,1.0); + if (m_data->m_hasLightColor) + { + lightColor = m_data->m_lightColor; + } + // printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size()); for (int i=0;im_swRenderInstances.size();i++) { @@ -737,6 +751,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo renderObj->m_viewMatrix[i][j] = viewMat[i+4*j]; renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); renderObj->m_lightDirWorld = lightDirWorld; + renderObj->m_lightColor = lightColor; } } TinyRenderer::renderObject(*renderObj); @@ -900,4 +915,4 @@ int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename) return registerTexture(image, width, height); } return -1; -} \ No newline at end of file +} diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.h b/examples/SharedMemory/TinyRendererVisualShapeConverter.h index 1a4a02f76..b2ed166e6 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.h +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.h @@ -33,6 +33,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter void getWidthAndHeight(int& width, int& height); void setWidthAndHeight(int width, int height); void setLightDirection(float x, float y, float z); + void setLightColor(float x, float y, float z); void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 0a5b7c861..76b9e4053 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -19,6 +19,7 @@ struct Shader : public IShader { Model* m_model; Vec3f m_light_dir_local; + Vec3f m_light_color; Matrix& m_modelMat; Matrix m_invModelMat; @@ -32,9 +33,10 @@ struct Shader : public IShader { mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS //mat<3,3,float> ndc_tri; // triangle in normalized device coordinates - Shader(Model* model, Vec3f light_dir_local, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) + Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) :m_model(model), m_light_dir_local(light_dir_local), + m_light_color(light_color), m_modelView1(modelView), m_projectionMatrix(projectionMatrix), m_modelMat(modelMat), @@ -83,6 +85,10 @@ struct Shader : public IShader { color.bgra[1] *= m_colorRGBA[1]; color.bgra[2] *= m_colorRGBA[2]; color.bgra[3] *= m_colorRGBA[3]; + + color.bgra[0] *= m_light_color[0]; + color.bgra[1] *= m_light_color[1]; + color.bgra[2] *= m_light_color[2]; return false; } @@ -260,6 +266,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) int height = renderData.m_rgbColorBuffer.get_height(); Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); + Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]); Model* model = renderData.m_model; if (0==model) return; @@ -278,7 +285,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) { Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); + Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); //printf("Render %d triangles.\n",model->nfaces()); for (int i=0; infaces(); i++) diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index 1819790a6..fcb8298bd 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -18,6 +18,7 @@ struct TinyRenderObjectData Matrix m_viewportMatrix; btVector3 m_localScaling; btVector3 m_lightDirWorld; + btVector3 m_lightColor; //Model (vertices, indices, textures, shader) Matrix m_modelMatrix; From be5b8a3d7b5536920164f54d40e7c07423498341 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sun, 20 Nov 2016 13:14:18 -0800 Subject: [PATCH 06/39] Set light color in pybullet. --- examples/pybullet/pybullet.c | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 17e782b8b..1e3c10a38 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -2209,17 +2209,18 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py /// Render an image from the current timestep of the simulation, width, height are required, other args are optional -// getCameraImage(w, h, view[16], projection[16], lightpos[3]) +// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3]) static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds) { /// request an image from a simulated camera, using a software renderer. struct b3CameraImageData imageData; - PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0; + PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0; int width, height; int size = PySequence_Size(args); float viewMatrix[16]; float projectionMatrix[16]; float lightDir[3]; + float lightColor[3]; // inialize cmd b3SharedMemoryCommandHandle command; @@ -2232,9 +2233,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec command = b3InitRequestCameraImage(sm); // set camera resolution, optionally view, projection matrix, light direction - static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection",NULL }; + static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOO", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOO", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj)) { return NULL; } @@ -2245,11 +2246,16 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec { b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); } - //set light pos only if function succeeds + //set light direction only if function succeeds if (pybullet_internalSetVector(lightDirObj, lightDir)) { b3RequestCameraImageSetLightDirection(command, lightDir); } + //set light color only if function succeeds + if (pybullet_internalSetVector(lightColorObj, lightColor)) + { + b3RequestCameraImageSetLightColor(command, lightColor); + } if (b3CanSubmitCommand(sm)) From f9c1e19587d5d0d0a87a70a1b8c1b85bc4dbafc4 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sun, 20 Nov 2016 15:38:42 -0800 Subject: [PATCH 07/39] revert 'addUserDebugLine/Text' to lockless rendering on main thread, at the cost of slower add/remove for now. --- .../SharedMemory/PhysicsServerExample.cpp | 136 ++++++++++++------ 1 file changed, 92 insertions(+), 44 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 55cefb05a..bf3bf20b5 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -126,6 +126,10 @@ enum MultiThreadedGUIHelperCommunicationEnums eGUIHelperRemoveAllGraphicsInstances, eGUIHelperCopyCameraImageData, eGUIHelperAutogenerateGraphicsObjects, + eGUIUserDebugAddText, + eGUIUserDebugAddLine, + eGUIUserDebugRemoveItem, + eGUIUserDebugRemoveAllItems, }; #include @@ -697,36 +701,43 @@ public: m_tmpText.m_textColorRGB[2] = textColorRGB[2]; m_cs->lock(); - m_userDebugText.push_back(m_tmpText); + m_cs->setSharedParam(1, eGUIUserDebugAddText); m_cs->unlock(); + while (m_cs->getSharedParam(1) != eGUIHelperIdle) + { + b3Clock::usleep(150); + } return m_userDebugText[m_userDebugText.size()-1].m_itemUniqueId; } btAlignedObjectArray m_userDebugLines; + UserDebugDrawLine m_tmpLine; virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime ) { - UserDebugDrawLine tmpLine; + m_tmpLine.m_lifeTime = lifeTime; + m_tmpLine.m_lineWidth = lineWidth; + m_tmpLine.m_itemUniqueId = m_uidGenerator++; + m_tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0]; + m_tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1]; + m_tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2]; - tmpLine.m_lifeTime = lifeTime; - tmpLine.m_lineWidth = lineWidth; - tmpLine.m_itemUniqueId = m_uidGenerator++; - tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0]; - tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1]; - tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2]; - - tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0]; - tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1]; - tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2]; + m_tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0]; + m_tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1]; + m_tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2]; - tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0]; - tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1]; - tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2]; + m_tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0]; + m_tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1]; + m_tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2]; m_cs->lock(); - m_userDebugLines.push_back(tmpLine); + m_cs->setSharedParam(1, eGUIUserDebugAddLine); m_cs->unlock(); + while (m_cs->getSharedParam(1) != eGUIHelperIdle) + { + b3Clock::usleep(150); + } return m_userDebugLines[m_userDebugLines.size()-1].m_itemUniqueId; } @@ -736,38 +747,23 @@ public: { m_removeDebugItemUid = debugItemUniqueId; m_cs->lock(); - - for (int i = 0; isetSharedParam(1, eGUIUserDebugRemoveItem); m_cs->unlock(); + while (m_cs->getSharedParam(1) != eGUIHelperIdle) + { + b3Clock::usleep(150); + } } virtual void removeAllUserDebugItems( ) { m_cs->lock(); - m_userDebugLines.clear(); - m_userDebugText.clear(); - m_uidGenerator = 0; + m_cs->setSharedParam(1, eGUIUserDebugRemoveAllItems); m_cs->unlock(); + while (m_cs->getSharedParam(1) != eGUIHelperIdle) + { + b3Clock::usleep(150); + } } @@ -1252,6 +1248,60 @@ void PhysicsServerExample::stepSimulation(float deltaTime) break; } + case eGUIUserDebugAddText: + { + m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText); + m_multiThreadedHelper->getCriticalSection()->lock(); + m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle); + m_multiThreadedHelper->getCriticalSection()->unlock(); + break; + } + case eGUIUserDebugAddLine: + { + m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine); + m_multiThreadedHelper->getCriticalSection()->lock(); + m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle); + m_multiThreadedHelper->getCriticalSection()->unlock(); + break; + } + case eGUIUserDebugRemoveItem: + { + for (int i=0;im_userDebugLines.size();i++) + { + if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid) + { + m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1); + m_multiThreadedHelper->m_userDebugLines.pop_back(); + break; + } + } + + + for (int i=0;im_userDebugText.size();i++) + { + if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid) + { + m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1); + m_multiThreadedHelper->m_userDebugText.pop_back(); + break; + } + } + + m_multiThreadedHelper->getCriticalSection()->lock(); + m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle); + m_multiThreadedHelper->getCriticalSection()->unlock(); + break; + } + case eGUIUserDebugRemoveAllItems: + { + m_multiThreadedHelper->m_userDebugLines.clear(); + m_multiThreadedHelper->m_userDebugText.clear(); + m_multiThreadedHelper->m_uidGenerator = 0; + m_multiThreadedHelper->getCriticalSection()->lock(); + m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle); + m_multiThreadedHelper->getCriticalSection()->unlock(); + break; + } case eGUIHelperIdle: { break; @@ -1316,7 +1366,7 @@ void PhysicsServerExample::drawUserDebugLines() //draw all user- 'text3d' messages if (m_multiThreadedHelper) { - m_args[0].m_cs->lock(); + for (int i = 0; im_userDebugLines.size(); i++) { btVector3 from; @@ -1346,8 +1396,6 @@ void PhysicsServerExample::drawUserDebugLines() m_multiThreadedHelper->m_userDebugText[i].textSize); } - m_args[0].m_cs->unlock(); - } } From 1bc427df6b0405909d53fb58bb1f3ea631eb3860 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Sun, 20 Nov 2016 16:22:20 -0800 Subject: [PATCH 08/39] fix compile issue when using VR --- examples/SharedMemory/PhysicsServerExample.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index bf3bf20b5..aff18b0f8 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -1475,7 +1475,9 @@ void PhysicsServerExample::renderScene() tr = tr*b3Transform(b3Quaternion(0,0,-SIMD_HALF_PI),b3MakeVector3(0,0,0)); b3Scalar dt = 0.01; m_tinyVrGui->clearTextArea(); - + static char line0[1024]; + static char line1[1024]; + m_tinyVrGui->grapicalPrintf(line0,0,0,0,0,0,255); m_tinyVrGui->grapicalPrintf(line1,0,16,255,255,255,255); From 49b27f30bdbba8c316cc46726de100e558315d58 Mon Sep 17 00:00:00 2001 From: Lunkhound Date: Sun, 20 Nov 2016 16:38:11 -0800 Subject: [PATCH 09/39] example browser: slider widget improvements --- .../CommonParameterInterface.h | 4 ++- examples/Evolution/NN3DWalkers.cpp | 7 +---- examples/Evolution/NN3DWalkersTimeWarpBase.h | 19 +++++-------- .../GwenGUISupport/GwenParameterInterface.cpp | 22 +++++++++++---- examples/ExtendedTutorials/InclinedPlane.cpp | 28 +++++++++---------- examples/ExtendedTutorials/MultiPendulum.cpp | 21 ++++---------- examples/ExtendedTutorials/NewtonsCradle.cpp | 22 ++++----------- .../ExtendedTutorials/NewtonsRopeCradle.cpp | 21 ++++---------- .../CommonRigidBodyMTBase.cpp | 22 +++++++++++++-- .../MultiThreadedDemo/MultiThreadedDemo.cpp | 11 ++++++-- 10 files changed, 86 insertions(+), 91 deletions(-) diff --git a/examples/CommonInterfaces/CommonParameterInterface.h b/examples/CommonInterfaces/CommonParameterInterface.h index 3bb2f50c8..e2334108c 100644 --- a/examples/CommonInterfaces/CommonParameterInterface.h +++ b/examples/CommonInterfaces/CommonParameterInterface.h @@ -4,7 +4,7 @@ #pragma once -typedef void (*SliderParamChangedCallback) (float newVal); +typedef void (*SliderParamChangedCallback) (float newVal, void* userPointer); #include "LinearMath/btScalar.h" struct SliderParams @@ -16,6 +16,7 @@ struct SliderParams btScalar* m_paramValuePointer; void* m_userPointer; bool m_clampToNotches; + bool m_clampToIntegers; bool m_showValues; SliderParams(const char* name, btScalar* targetValuePointer) @@ -26,6 +27,7 @@ struct SliderParams m_paramValuePointer(targetValuePointer), m_userPointer(0), m_clampToNotches(true), + m_clampToIntegers(false), m_showValues(true) { } diff --git a/examples/Evolution/NN3DWalkers.cpp b/examples/Evolution/NN3DWalkers.cpp index 148ebee0c..53d59e485 100755 --- a/examples/Evolution/NN3DWalkers.cpp +++ b/examples/Evolution/NN3DWalkers.cpp @@ -552,10 +552,6 @@ struct WalkerFilterCallback : public btOverlapFilterCallback } }; -void floorNNSliderValue(float notUsed) { - gParallelEvaluations = floor(gParallelEvaluations); -} - void NN3DWalkersExample::initPhysics() { @@ -657,8 +653,7 @@ void NN3DWalkersExample::initPhysics() SliderParams slider("Parallel evaluations", &gParallelEvaluations); slider.m_minVal = 1; slider.m_maxVal = NUM_WALKERS; - slider.m_clampToNotches = false; - slider.m_callback = floorNNSliderValue; // hack to get integer values + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } diff --git a/examples/Evolution/NN3DWalkersTimeWarpBase.h b/examples/Evolution/NN3DWalkersTimeWarpBase.h index 6db8fadd1..a7a9a2a7d 100644 --- a/examples/Evolution/NN3DWalkersTimeWarpBase.h +++ b/examples/Evolution/NN3DWalkersTimeWarpBase.h @@ -138,19 +138,15 @@ static btScalar gCFMSingularityAvoidance = 0; //GUI related parameter changing helpers -inline void floorSliderValues(float notUsed) { // floor values that should be ints - gSolverIterations = floor(gSolverIterations); -} - -inline void twxChangePhysicsStepsPerSecond(float physicsStepsPerSecond) { // function to change simulation physics steps per second +inline void twxChangePhysicsStepsPerSecond(float physicsStepsPerSecond, void*) { // function to change simulation physics steps per second gPhysicsStepsPerSecond = physicsStepsPerSecond; } -inline void twxChangeFPS(float framesPerSecond) { +inline void twxChangeFPS(float framesPerSecond, void*) { gFramesPerSecond = framesPerSecond; } -inline void twxChangeERPCFM(float notUsed) { // function to change ERP/CFM appropriately +inline void twxChangeERPCFM(float notUsed, void*) { // function to change ERP/CFM appropriately gChangeErpCfm = true; } @@ -166,13 +162,12 @@ inline void changeSolver(int comboboxId, const char* item, void* userPointer) { } -inline void twxChangeSolverIterations(float notUsed){ // change the solver iterations +inline void twxChangeSolverIterations(float notUsed, void* userPtr) { // change the solver iterations - floorSliderValues(0); // floor the values set by slider } -inline void clampToCustomSpeedNotches(float speed) { // function to clamp to custom speed notches +inline void clampToCustomSpeedNotches(float speed, void*) { // function to clamp to custom speed notches double minSpeed = 0; double minSpeedDist = SimulationSpeeds::MAX_SPEED; for (int i = 0; i < SimulationSpeeds::NUM_SPEEDS; i++) { @@ -200,7 +195,7 @@ inline void switchMaximumSpeed(int buttonId, bool buttonState, void* userPointer // b3Printf("Run maximum speed %s", gMaximumSpeed?"on":"off"); } -inline void setApplicationTick(float frequency){ // set internal application tick +inline void setApplicationTick(float frequency, void*){ // set internal application tick gApplicationTick = 1000.0f/frequency; } @@ -383,7 +378,7 @@ struct NN3DWalkersTimeWarpBase: public CommonRigidBodyBase { slider.m_minVal = 0; slider.m_maxVal = 1000; slider.m_callback = twxChangePhysicsStepsPerSecond; - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } diff --git a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp index 449f27e0a..aa8c0b871 100644 --- a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp +++ b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp @@ -28,18 +28,20 @@ template struct MySliderEventHandler : public Gwen::Event::Handler { SliderParamChangedCallback m_callback; + void* m_userPointer; Gwen::Controls::TextBox* m_label; Gwen::Controls::Slider* m_pSlider; char m_variableName[1024]; T* m_targetValue; bool m_showValue; - MySliderEventHandler(const char* varName, Gwen::Controls::TextBox* label, Gwen::Controls::Slider* pSlider,T* target,SliderParamChangedCallback callback) + MySliderEventHandler(const char* varName, Gwen::Controls::TextBox* label, Gwen::Controls::Slider* pSlider,T* target, SliderParamChangedCallback callback, void* userPtr) :m_label(label), m_pSlider(pSlider), m_targetValue(target), m_showValue(true), - m_callback(callback) + m_callback(callback), + m_userPointer(userPtr) { memcpy(m_variableName,varName,strlen(varName)+1); } @@ -55,7 +57,7 @@ struct MySliderEventHandler : public Gwen::Event::Handler if (m_callback) { - (*m_callback)(v); + (*m_callback)(v, m_userPointer); } } @@ -223,12 +225,20 @@ void GwenParameterInterface::registerSliderFloatParameter(SliderParams& params) pSlider->SetPos( 10, m_gwenInternalData->m_curYposition ); pSlider->SetSize( 200, 20 ); pSlider->SetRange( params.m_minVal, params.m_maxVal); - pSlider->SetNotchCount(16);//float(params.m_maxVal-params.m_minVal)/100.f); - pSlider->SetClampToNotches( params.m_clampToNotches ); + if (params.m_clampToIntegers) + { + pSlider->SetNotchCount( int( params.m_maxVal - params.m_minVal ) ); + pSlider->SetClampToNotches( params.m_clampToNotches ); + } + else + { + pSlider->SetNotchCount( 16 );//float(params.m_maxVal-params.m_minVal)/100.f); + pSlider->SetClampToNotches( params.m_clampToNotches ); + } pSlider->SetValue( *params.m_paramValuePointer);//dimensions[i] ); char labelName[1024]; sprintf(labelName,"%s",params.m_name);//axisNames[0]); - MySliderEventHandler* handler = new MySliderEventHandler(labelName,label,pSlider,params.m_paramValuePointer,params.m_callback); + MySliderEventHandler* handler = new MySliderEventHandler(labelName,label,pSlider,params.m_paramValuePointer,params.m_callback, params.m_userPointer); handler->m_showValue = params.m_showValues; m_paramInternalData->m_sliderEventHandlers.push_back(handler); diff --git a/examples/ExtendedTutorials/InclinedPlane.cpp b/examples/ExtendedTutorials/InclinedPlane.cpp index dceafdbe8..2c36f8ffa 100644 --- a/examples/ExtendedTutorials/InclinedPlane.cpp +++ b/examples/ExtendedTutorials/InclinedPlane.cpp @@ -69,19 +69,19 @@ struct InclinedPlaneExample : public CommonRigidBodyBase }; -void onBoxFrictionChanged(float friction); +void onBoxFrictionChanged(float friction, void* userPtr); -void onBoxRestitutionChanged(float restitution); +void onBoxRestitutionChanged(float restitution, void* userPtr); -void onSphereFrictionChanged(float friction); +void onSphereFrictionChanged(float friction, void* userPtr); -void onSphereRestitutionChanged(float restitution); +void onSphereRestitutionChanged(float restitution, void* userPtr); -void onRampInclinationChanged(float inclination); +void onRampInclinationChanged(float inclination, void* userPtr); -void onRampFrictionChanged(float friction); +void onRampFrictionChanged(float friction, void* userPtr); -void onRampRestitutionChanged(float restitution); +void onRampRestitutionChanged(float restitution, void* userPtr); void InclinedPlaneExample::initPhysics() { @@ -306,35 +306,35 @@ bool InclinedPlaneExample::keyboardCallback(int key, int state) { // GUI parameter modifiers -void onBoxFrictionChanged(float friction){ +void onBoxFrictionChanged(float friction, void*){ if(gBox){ gBox->setFriction(friction); // b3Printf("Friction of box changed to %f",friction ); } } -void onBoxRestitutionChanged(float restitution){ +void onBoxRestitutionChanged(float restitution, void*){ if(gBox){ gBox->setRestitution(restitution); //b3Printf("Restitution of box changed to %f",restitution); } } -void onSphereFrictionChanged(float friction){ +void onSphereFrictionChanged(float friction, void*){ if(gSphere){ gSphere->setFriction(friction); //b3Printf("Friction of sphere changed to %f",friction ); } } -void onSphereRestitutionChanged(float restitution){ +void onSphereRestitutionChanged(float restitution, void*){ if(gSphere){ gSphere->setRestitution(restitution); //b3Printf("Restitution of sphere changed to %f",restitution); } } -void onRampInclinationChanged(float inclination){ +void onRampInclinationChanged(float inclination, void*){ if(ramp){ btTransform startTransform; startTransform.setIdentity(); @@ -351,14 +351,14 @@ void onRampInclinationChanged(float inclination){ } } -void onRampFrictionChanged(float friction){ +void onRampFrictionChanged(float friction, void*){ if(ramp){ ramp->setFriction(friction); //b3Printf("Friction of ramp changed to %f \n",friction ); } } -void onRampRestitutionChanged(float restitution){ +void onRampRestitutionChanged(float restitution, void*){ if(ramp){ ramp->setRestitution(restitution); //b3Printf("Restitution of ramp changed to %f \n",restitution); diff --git a/examples/ExtendedTutorials/MultiPendulum.cpp b/examples/ExtendedTutorials/MultiPendulum.cpp index 038aab3ec..b45eee755 100644 --- a/examples/ExtendedTutorials/MultiPendulum.cpp +++ b/examples/ExtendedTutorials/MultiPendulum.cpp @@ -71,11 +71,9 @@ struct MultiPendulumExample: public CommonRigidBodyBase { static MultiPendulumExample* mex = NULL; // Handle to the example to access it via functions. Do not use this in your simulation! -void onMultiPendulaLengthChanged(float pendulaLength); // Change the pendula length +void onMultiPendulaLengthChanged(float pendulaLength, void*); // Change the pendula length -void onMultiPendulaRestitutionChanged(float pendulaRestitution); // change the pendula restitution - -void floorMSliderValue(float notUsed); // floor the slider values which should be integers +void onMultiPendulaRestitutionChanged(float pendulaRestitution, void*); // change the pendula restitution void applyMForceWithForceScalar(float forceScalar); @@ -85,8 +83,7 @@ void MultiPendulumExample::initPhysics() { // Setup your physics scene SliderParams slider("Number of Pendula", &gPendulaQty); slider.m_minVal = 1; slider.m_maxVal = 50; - slider.m_callback = floorMSliderValue; // hack to get integer values - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } @@ -95,8 +92,7 @@ void MultiPendulumExample::initPhysics() { // Setup your physics scene SliderParams slider("Number of Displaced Pendula", &gDisplacedPendula); slider.m_minVal = 0; slider.m_maxVal = 49; - slider.m_callback = floorMSliderValue; // hack to get integer values - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } @@ -397,7 +393,7 @@ void MultiPendulumExample::applyPendulumForce(btScalar pendulumForce){ // GUI parameter modifiers -void onMultiPendulaLengthChanged(float pendulaLength) { // Change the pendula length +void onMultiPendulaLengthChanged(float pendulaLength, void*) { // Change the pendula length if (mex){ mex->changePendulaLength(pendulaLength); } @@ -405,18 +401,13 @@ void onMultiPendulaLengthChanged(float pendulaLength) { // Change the pendula le } -void onMultiPendulaRestitutionChanged(float pendulaRestitution) { // change the pendula restitution +void onMultiPendulaRestitutionChanged(float pendulaRestitution, void*) { // change the pendula restitution if (mex){ mex->changePendulaRestitution(pendulaRestitution); } } -void floorMSliderValue(float notUsed) { // floor the slider values which should be integers - gPendulaQty = floor(gPendulaQty); - gDisplacedPendula = floor(gDisplacedPendula); -} - void applyMForceWithForceScalar(float forceScalar) { if(mex){ btScalar appliedForce = forceScalar * gDisplacementForce; diff --git a/examples/ExtendedTutorials/NewtonsCradle.cpp b/examples/ExtendedTutorials/NewtonsCradle.cpp index 0d4c52095..54be8367a 100644 --- a/examples/ExtendedTutorials/NewtonsCradle.cpp +++ b/examples/ExtendedTutorials/NewtonsCradle.cpp @@ -71,11 +71,9 @@ struct NewtonsCradleExample: public CommonRigidBodyBase { static NewtonsCradleExample* nex = NULL; -void onPendulaLengthChanged(float pendulaLength); // Change the pendula length +void onPendulaLengthChanged(float pendulaLength, void* userPtr); // Change the pendula length -void onPendulaRestitutionChanged(float pendulaRestitution); // change the pendula restitution - -void floorSliderValue(float notUsed); // floor the slider values which should be integers +void onPendulaRestitutionChanged(float pendulaRestitution, void* userPtr); // change the pendula restitution void applyForceWithForceScalar(float forceScalar); @@ -85,8 +83,7 @@ void NewtonsCradleExample::initPhysics() { SliderParams slider("Number of Pendula", &gPendulaQty); slider.m_minVal = 1; slider.m_maxVal = 50; - slider.m_callback = floorSliderValue; // hack to get integer values - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } @@ -95,8 +92,7 @@ void NewtonsCradleExample::initPhysics() { SliderParams slider("Number of Displaced Pendula", &gDisplacedPendula); slider.m_minVal = 0; slider.m_maxVal = 49; - slider.m_callback = floorSliderValue; // hack to get integer values - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } @@ -343,25 +339,19 @@ void NewtonsCradleExample::applyPendulumForce(btScalar pendulumForce){ // GUI parameter modifiers -void onPendulaLengthChanged(float pendulaLength) { +void onPendulaLengthChanged(float pendulaLength, void*) { if (nex){ nex->changePendulaLength(pendulaLength); //b3Printf("Pendula length changed to %f \n",sliderValue ); } } -void onPendulaRestitutionChanged(float pendulaRestitution) { +void onPendulaRestitutionChanged(float pendulaRestitution, void*) { if (nex){ nex->changePendulaRestitution(pendulaRestitution); } } -void floorSliderValue(float notUsed) { - gPendulaQty = floor(gPendulaQty); - gDisplacedPendula = floor(gDisplacedPendula); - -} - void applyForceWithForceScalar(float forceScalar) { if(nex){ btScalar appliedForce = forceScalar * gDisplacementForce; diff --git a/examples/ExtendedTutorials/NewtonsRopeCradle.cpp b/examples/ExtendedTutorials/NewtonsRopeCradle.cpp index 94c96a71f..76eb115ea 100644 --- a/examples/ExtendedTutorials/NewtonsRopeCradle.cpp +++ b/examples/ExtendedTutorials/NewtonsRopeCradle.cpp @@ -105,9 +105,7 @@ struct NewtonsRopeCradleExample : public CommonRigidBodyBase { static NewtonsRopeCradleExample* nex = NULL; -void onRopePendulaRestitutionChanged(float pendulaRestitution); - -void floorRSliderValue(float notUsed); +void onRopePendulaRestitutionChanged(float pendulaRestitution, void*); void applyRForceWithForceScalar(float forceScalar); @@ -118,8 +116,7 @@ void NewtonsRopeCradleExample::initPhysics() SliderParams slider("Number of Pendula", &gPendulaQty); slider.m_minVal = 1; slider.m_maxVal = 50; - slider.m_callback = floorRSliderValue; // hack to get integer values - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } @@ -128,8 +125,7 @@ void NewtonsRopeCradleExample::initPhysics() SliderParams slider("Number of Displaced Pendula", &gDisplacedPendula); slider.m_minVal = 0; slider.m_maxVal = 49; - slider.m_callback = floorRSliderValue; // hack to get integer values - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } @@ -148,8 +144,7 @@ void NewtonsRopeCradleExample::initPhysics() SliderParams slider("Rope Resolution", &gRopeResolution); slider.m_minVal = 1; slider.m_maxVal = 20; - slider.m_clampToNotches = false; - slider.m_callback = floorRSliderValue; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider); } @@ -357,18 +352,12 @@ void NewtonsRopeCradleExample::applyPendulumForce(btScalar pendulumForce){ // GUI parameter modifiers -void onRopePendulaRestitutionChanged(float pendulaRestitution) { +void onRopePendulaRestitutionChanged(float pendulaRestitution, void*) { if (nex){ nex->changePendulaRestitution(pendulaRestitution); } } -void floorRSliderValue(float notUsed) { - gPendulaQty = floor(gPendulaQty); - gDisplacedPendula = floor(gDisplacedPendula); - gRopeResolution = floor(gRopeResolution); -} - void applyRForceWithForceScalar(float forceScalar) { if(nex){ btScalar appliedForce = forceScalar * gDisplacementForce; diff --git a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp index 26e430cc2..0e9e6c5b3 100644 --- a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp +++ b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp @@ -633,7 +633,7 @@ void apiSelectButtonCallback(int buttonId, bool buttonState, void* userPointer) } } -void setThreadCountCallback(float val) +void setThreadCountCallback(float val, void* userPtr) { if (gTaskMgr.getApi()==TaskManager::apiNone) { @@ -642,7 +642,14 @@ void setThreadCountCallback(float val) else { gTaskMgr.setNumThreads( int( gSliderNumThreads ) ); - gSliderNumThreads = float(gTaskMgr.getNumThreads()); + } +} + +void setSolverIterationCountCallback(float val, void* userPtr) +{ + if (btDiscreteDynamicsWorld* world = reinterpret_cast(userPtr)) + { + world->getSolverInfo().m_numIterations = btMax(1, int(gSliderSolverIterations)); } } @@ -728,6 +735,15 @@ void CommonRigidBodyMTBase::createDefaultParameters() button.m_callback = boolPtrButtonCallback; m_guiHelper->getParameterInterface()->registerButtonParameter( button ); } + { + SliderParams slider( "Solver iterations", &gSliderSolverIterations ); + slider.m_minVal = 1.0f; + slider.m_maxVal = 30.0f; + slider.m_callback = setSolverIterationCountCallback; + slider.m_userPointer = m_dynamicsWorld; + slider.m_clampToIntegers = true; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider ); + } if (m_multithreadedWorld) { // create a button for each supported threading API @@ -750,7 +766,7 @@ void CommonRigidBodyMTBase::createDefaultParameters() slider.m_minVal = 1.0f; slider.m_maxVal = float(gTaskMgr.getMaxNumThreads()*2); slider.m_callback = setThreadCountCallback; - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider ); } } diff --git a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp index d3a54856b..bb6c8a8b6 100644 --- a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp +++ b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp @@ -98,18 +98,25 @@ void MultiThreadedDemo::initPhysics() m_dynamicsWorld->setGravity( btVector3( 0, -10, 0 ) ); + { + SliderParams slider( "Stack height", &gSliderStackHeight ); + slider.m_minVal = 1.0f; + slider.m_maxVal = 30.0f; + slider.m_clampToIntegers = true; + m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider ); + } { SliderParams slider( "Stack rows", &gSliderStackRows ); slider.m_minVal = 1.0f; slider.m_maxVal = 20.0f; - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider ); } { SliderParams slider( "Stack columns", &gSliderStackColumns ); slider.m_minVal = 1.0f; slider.m_maxVal = 20.0f; - slider.m_clampToNotches = false; + slider.m_clampToIntegers = true; m_guiHelper->getParameterInterface()->registerSliderFloatParameter( slider ); } From 4300ef45a37ead1071f6c7e80631d136b00101cc Mon Sep 17 00:00:00 2001 From: Lunkhound Date: Sun, 20 Nov 2016 18:00:21 -0800 Subject: [PATCH 10/39] fix missing globals --- examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp | 2 ++ examples/MultiThreadedDemo/MultiThreadedDemo.cpp | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp index 0e9e6c5b3..8375489ee 100644 --- a/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp +++ b/examples/MultiThreadedDemo/CommonRigidBodyMTBase.cpp @@ -590,6 +590,8 @@ public: static bool gMultithreadedWorld = false; static bool gDisplayProfileInfo = false; static btScalar gSliderNumThreads = 1.0f; // should be int +static btScalar gSliderSolverIterations = 10.0f; // should be int + //////////////////////////////////// CommonRigidBodyMTBase::CommonRigidBodyMTBase( struct GUIHelperInterface* helper ) diff --git a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp index bb6c8a8b6..4a88207c6 100644 --- a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp +++ b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp @@ -90,7 +90,7 @@ MultiThreadedDemo::MultiThreadedDemo(struct GUIHelperInterface* helper) static btScalar gSliderStackRows = 8.0f; static btScalar gSliderStackColumns = 6.0f; - +static btScalar gSliderStackHeight = 15.0f; void MultiThreadedDemo::initPhysics() { From 0d5dcb3cc55ecc08c190bd6b21f8b8d1b54ba44a Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 21 Nov 2016 07:42:11 -0800 Subject: [PATCH 11/39] setDebugObjectColor --- examples/SharedMemory/PhysicsClientC_API.cpp | 51 ++++++++++++++++ examples/SharedMemory/PhysicsClientC_API.h | 7 +++ .../PhysicsServerCommandProcessor.cpp | 50 +++++++++++++++- examples/SharedMemory/SharedMemoryCommands.h | 15 ++++- .../TinyRendererVisualShapeConverter.cpp | 19 +++++- .../TinyRendererVisualShapeConverter.h | 1 + examples/TinyRenderer/TinyRenderer.cpp | 11 +++- examples/TinyRenderer/TinyRenderer.h | 1 + examples/pybullet/pybullet.c | 59 +++++++++++++++++-- .../CollisionDispatch/btCollisionObject.h | 24 +++++++- .../CollisionDispatch/btCollisionWorld.cpp | 2 + 11 files changed, 224 insertions(+), 16 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index e61130446..e60953750 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -1195,6 +1195,46 @@ int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle) return status->m_userDebugDrawArgs.m_debugItemUniqueId; } +b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient) +{ + PhysicsClient* cl = (PhysicsClient*)physClient; + b3Assert(cl); + b3Assert(cl->canSubmitCommand()); + struct SharedMemoryCommand* command = cl->getAvailableSharedMemoryCommand(); + b3Assert(command); + command->m_type = CMD_USER_DEBUG_DRAW; + command->m_updateFlags = 0; + return (b3SharedMemoryCommandHandle)command; +} + + + +void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_USER_DEBUG_DRAW); + command->m_updateFlags |= USER_DEBUG_SET_CUSTOM_OBJECT_COLOR; + command->m_userDebugDrawArgs.m_objectUniqueId = objectUniqueId; + command->m_userDebugDrawArgs.m_linkIndex = linkIndex; + command->m_userDebugDrawArgs.m_objectDebugColorRGB[0] = objectColorRGB[0]; + command->m_userDebugDrawArgs.m_objectDebugColorRGB[1] = objectColorRGB[1]; + command->m_userDebugDrawArgs.m_objectDebugColorRGB[2] = objectColorRGB[2]; +} + +void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_USER_DEBUG_DRAW); + command->m_updateFlags |= USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR; + command->m_userDebugDrawArgs.m_objectUniqueId = objectUniqueId; + command->m_userDebugDrawArgs.m_linkIndex = linkIndex; + +} + + + ///request an image from a simulated camera, using a software renderer. b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient) @@ -1244,6 +1284,17 @@ void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHa command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION; } +void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + for (int i = 0; i<3; i++) + { + command->m_requestPixelDataArguments.m_lightColor[i] = lightColor[i]; + } + command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR; +} void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]) { diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index e9df467ec..b9da28cd5 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -89,14 +89,21 @@ b3SharedMemoryCommandHandle b3InitUserDebugDrawAddLine3D(b3PhysicsClientHandle p b3SharedMemoryCommandHandle b3InitUserDebugDrawAddText3D(b3PhysicsClientHandle physClient, const char* txt, double positionXYZ[3], double colorRGB[3], double textSize, double lifeTime); b3SharedMemoryCommandHandle b3InitUserDebugDrawRemove(b3PhysicsClientHandle physClient, int debugItemUniqueId); b3SharedMemoryCommandHandle b3InitUserDebugDrawRemoveAll(b3PhysicsClientHandle physClient); + +b3SharedMemoryCommandHandle b3InitDebugDrawingCommand(b3PhysicsClientHandle physClient); +void b3SetDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex, double objectColorRGB[3]); +void b3RemoveDebugObjectColor(b3SharedMemoryCommandHandle commandHandle, int objectUniqueId, int linkIndex); + ///All debug items unique Ids are positive: a negative unique Id means failure. int b3GetDebugItemUniqueId(b3SharedMemoryStatusHandle statusHandle); + ///request an image from a simulated camera, using a software renderer. b3SharedMemoryCommandHandle b3InitRequestCameraImage(b3PhysicsClientHandle physClient); void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, float viewMatrix[16], float projectionMatrix[16]); void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]); +void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]); void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer); void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 056784ada..0df90f614 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -3531,7 +3531,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm for( int i=0;igetRigidBodyByIndex(i); - if (colObj) { btRigidBody* rb = btRigidBody::upcast(colObj); @@ -3594,7 +3593,54 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm SharedMemoryStatus& serverCmd = serverStatusOut; serverCmd.m_type = CMD_USER_DEBUG_DRAW_FAILED; hasStatus = true; - + + if ((clientCmd.m_updateFlags & USER_DEBUG_SET_CUSTOM_OBJECT_COLOR) || (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR)) + { + int bodyUniqueId = clientCmd.m_userDebugDrawArgs.m_objectUniqueId; + InteralBodyData* body = m_data->getHandle(bodyUniqueId); + if (body) + { + btCollisionObject* destColObj = 0; + + if (body->m_multiBody) + { + if (clientCmd.m_userDebugDrawArgs.m_linkIndex == -1) + { + destColObj = body->m_multiBody->getBaseCollider(); + } + else + { + if (clientCmd.m_userDebugDrawArgs.m_linkIndex >= 0 && clientCmd.m_userDebugDrawArgs.m_linkIndex < body->m_multiBody->getNumLinks()) + { + destColObj = body->m_multiBody->getLink(clientCmd.m_userDebugDrawArgs.m_linkIndex).m_collider; + } + } + + } + if (body->m_rigidBody) + { + destColObj = body->m_rigidBody; + } + + if (destColObj) + { + if (clientCmd.m_updateFlags & USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR) + { + destColObj->removeCustomDebugColor(); + serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED; + } + if (clientCmd.m_updateFlags & USER_DEBUG_SET_CUSTOM_OBJECT_COLOR) + { + btVector3 objectColorRGB; + objectColorRGB.setValue(clientCmd.m_userDebugDrawArgs.m_objectDebugColorRGB[0], + clientCmd.m_userDebugDrawArgs.m_objectDebugColorRGB[1], + clientCmd.m_userDebugDrawArgs.m_objectDebugColorRGB[2]); + destColObj->setCustomDebugColor(objectColorRGB); + serverCmd.m_type = CMD_USER_DEBUG_DRAW_COMPLETED; + } + } + } + } if (clientCmd.m_updateFlags & USER_DEBUG_HAS_TEXT) { diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 515fa5079..5b3346433 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -139,13 +139,15 @@ struct RequestPixelDataArgs int m_pixelWidth; int m_pixelHeight; float m_lightDirection[3]; + float m_lightColor[3]; }; enum EnumRequestPixelDataUpdateFlags { REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES=1, - REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=4, - REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=8, + REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=2, + REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=4, + REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR=8, //don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h }; @@ -524,7 +526,10 @@ enum EnumUserDebugDrawFlags USER_DEBUG_HAS_LINE=1, USER_DEBUG_HAS_TEXT=2, USER_DEBUG_REMOVE_ONE_ITEM=4, - USER_DEBUG_REMOVE_ALL=8 + USER_DEBUG_REMOVE_ALL=8, + USER_DEBUG_SET_CUSTOM_OBJECT_COLOR = 16, + USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR = 32, + }; struct UserDebugDrawArgs @@ -541,6 +546,10 @@ struct UserDebugDrawArgs double m_textPositionXYZ[3]; double m_textColorRGB[3]; double m_textSize; + + double m_objectDebugColorRGB[3]; + int m_objectUniqueId; + int m_linkIndex; }; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 676ca65d3..34478bee7 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -75,6 +75,8 @@ struct TinyRendererVisualShapeConverterInternalData b3AlignedObjectArray m_segmentationMaskBuffer; btVector3 m_lightDirection; bool m_hasLightDirection; + btVector3 m_lightColor; + bool m_hasLightColor; SimpleCamera m_camera; @@ -83,7 +85,8 @@ struct TinyRendererVisualShapeConverterInternalData m_swWidth(START_WIDTH), m_swHeight(START_HEIGHT), m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB), - m_hasLightDirection(false) + m_hasLightDirection(false), + m_hasLightColor(false) { m_depthBuffer.resize(m_swWidth*m_swHeight); m_segmentationMaskBuffer.resize(m_swWidth*m_swHeight,-1); @@ -117,6 +120,11 @@ void TinyRendererVisualShapeConverter::setLightDirection(float x, float y, float m_data->m_hasLightDirection = true; } +void TinyRendererVisualShapeConverter::setLightColor(float x, float y, float z) +{ + m_data->m_lightColor.setValue(x, y, z); + m_data->m_hasLightColor = true; +} void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, b3VisualShapeData& visualShapeOut) { @@ -704,6 +712,12 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo lightDirWorld.normalize(); + btVector3 lightColor(1.0,1.0,1.0); + if (m_data->m_hasLightColor) + { + lightColor = m_data->m_lightColor; + } + // printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size()); for (int i=0;im_swRenderInstances.size();i++) { @@ -737,6 +751,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo renderObj->m_viewMatrix[i][j] = viewMat[i+4*j]; renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); renderObj->m_lightDirWorld = lightDirWorld; + renderObj->m_lightColor = lightColor; } } TinyRenderer::renderObject(*renderObj); @@ -900,4 +915,4 @@ int TinyRendererVisualShapeConverter::loadTextureFile(const char* filename) return registerTexture(image, width, height); } return -1; -} \ No newline at end of file +} diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.h b/examples/SharedMemory/TinyRendererVisualShapeConverter.h index 1a4a02f76..b2ed166e6 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.h +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.h @@ -33,6 +33,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter void getWidthAndHeight(int& width, int& height); void setWidthAndHeight(int width, int height); void setLightDirection(float x, float y, float z); + void setLightColor(float x, float y, float z); void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 0a5b7c861..76b9e4053 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -19,6 +19,7 @@ struct Shader : public IShader { Model* m_model; Vec3f m_light_dir_local; + Vec3f m_light_color; Matrix& m_modelMat; Matrix m_invModelMat; @@ -32,9 +33,10 @@ struct Shader : public IShader { mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS //mat<3,3,float> ndc_tri; // triangle in normalized device coordinates - Shader(Model* model, Vec3f light_dir_local, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) + Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) :m_model(model), m_light_dir_local(light_dir_local), + m_light_color(light_color), m_modelView1(modelView), m_projectionMatrix(projectionMatrix), m_modelMat(modelMat), @@ -83,6 +85,10 @@ struct Shader : public IShader { color.bgra[1] *= m_colorRGBA[1]; color.bgra[2] *= m_colorRGBA[2]; color.bgra[3] *= m_colorRGBA[3]; + + color.bgra[0] *= m_light_color[0]; + color.bgra[1] *= m_light_color[1]; + color.bgra[2] *= m_light_color[2]; return false; } @@ -260,6 +266,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) int height = renderData.m_rgbColorBuffer.get_height(); Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); + Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]); Model* model = renderData.m_model; if (0==model) return; @@ -278,7 +285,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) { Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - Shader shader(model, light_dir_local, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); + Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); //printf("Render %d triangles.\n",model->nfaces()); for (int i=0; infaces(); i++) diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index 1819790a6..fcb8298bd 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -18,6 +18,7 @@ struct TinyRenderObjectData Matrix m_viewportMatrix; btVector3 m_localScaling; btVector3 m_lightDirWorld; + btVector3 m_lightColor; //Model (vertices, indices, textures, shader) Matrix m_modelMatrix; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 8163fbd1b..1947ec103 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1647,8 +1647,45 @@ static PyObject* pybullet_removeAllUserDebugItems(PyObject* self, PyObject* args Py_INCREF(Py_None); return Py_None; } - +static PyObject* pybullet_setDebugObjectColor(PyObject* self, PyObject* args, PyObject *keywds) +{ + PyObject* objectColorRGBObj = 0; + double objectColorRGB[3]; + + int objectUniqueId = -1; + int linkIndex = -2; + + static char *kwlist[] = { "objectUniqueId", "linkIndex","objectDebugColorRGB", NULL }; + + if (0 == sm) { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|O", kwlist, + &objectUniqueId, &linkIndex, &objectColorRGBObj)) + return NULL; + + if (objectColorRGBObj) + { + if (pybullet_internalSetVectord(objectColorRGBObj, objectColorRGB)) + { + b3SharedMemoryCommandHandle commandHandle = b3InitDebugDrawingCommand(sm); + b3SetDebugObjectColor(commandHandle, objectUniqueId, linkIndex, objectColorRGB); + b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + } + } + else + { + b3SharedMemoryCommandHandle commandHandle = b3InitDebugDrawingCommand(sm); + b3RemoveDebugObjectColor(commandHandle, objectUniqueId, linkIndex); + b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + } + Py_INCREF(Py_None); + return Py_None; +} + static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args) { @@ -2237,17 +2274,18 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py /// Render an image from the current timestep of the simulation, width, height are required, other args are optional -// getCameraImage(w, h, view[16], projection[16], lightpos[3]) +// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3]) static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds) { /// request an image from a simulated camera, using a software renderer. struct b3CameraImageData imageData; - PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0; + PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0; int width, height; int size = PySequence_Size(args); float viewMatrix[16]; float projectionMatrix[16]; float lightDir[3]; + float lightColor[3]; // inialize cmd b3SharedMemoryCommandHandle command; @@ -2260,9 +2298,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec command = b3InitRequestCameraImage(sm); // set camera resolution, optionally view, projection matrix, light direction - static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection",NULL }; + static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOO", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOO", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj)) { return NULL; } @@ -2273,11 +2311,16 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec { b3RequestCameraImageSetCameraMatrices(command, viewMatrix, projectionMatrix); } - //set light pos only if function succeeds + //set light direction only if function succeeds if (pybullet_internalSetVector(lightDirObj, lightDir)) { b3RequestCameraImageSetLightDirection(command, lightDir); } + //set light color only if function succeeds + if (pybullet_internalSetVector(lightColorObj, lightColor)) + { + b3RequestCameraImageSetLightColor(command, lightColor); + } if (b3CanSubmitCommand(sm)) @@ -3421,6 +3464,10 @@ static PyMethodDef SpamMethods[] = { "remove all user debug draw items" }, + { "setDebugObjectColor", (PyCFunction)pybullet_setDebugObjectColor, METH_VARARGS | METH_KEYWORDS, + "Override the wireframe debug drawing color for a particular object unique id / link index." + "If you ommit the color, the custom color will be removed." + }, {"getVisualShapeData", pybullet_getVisualShapeData, METH_VARARGS, diff --git a/src/BulletCollision/CollisionDispatch/btCollisionObject.h b/src/BulletCollision/CollisionDispatch/btCollisionObject.h index c285a83fb..0cae21000 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionObject.h +++ b/src/BulletCollision/CollisionDispatch/btCollisionObject.h @@ -122,6 +122,7 @@ protected: ///internal update revision number. It will be increased when the object changes. This allows some subsystems to perform lazy evaluation. int m_updateRevision; + btVector3 m_customDebugColorRGB; public: @@ -136,7 +137,8 @@ public: CF_CHARACTER_OBJECT = 16, CF_DISABLE_VISUALIZE_OBJECT = 32, //disable debug drawing CF_DISABLE_SPU_COLLISION_PROCESSING = 64,//disable parallel/SPU processing - CF_HAS_CONTACT_STIFFNESS_DAMPING = 128 + CF_HAS_CONTACT_STIFFNESS_DAMPING = 128, + CF_HAS_CUSTOM_DEBUG_RENDERING_COLOR = 256, }; enum CollisionObjectTypes @@ -556,6 +558,26 @@ public: return m_updateRevision; } + void setCustomDebugColor(const btVector3& colorRGB) + { + m_customDebugColorRGB = colorRGB; + m_collisionFlags |= CF_HAS_CUSTOM_DEBUG_RENDERING_COLOR; + } + + void removeCustomDebugColor() + { + m_collisionFlags &= ~CF_HAS_CUSTOM_DEBUG_RENDERING_COLOR; + } + + bool getCustomDebugColor(btVector3& colorRGB) const + { + bool hasCustomColor = (0!=(m_collisionFlags&CF_HAS_CUSTOM_DEBUG_RENDERING_COLOR)); + if (hasCustomColor) + { + colorRGB = m_customDebugColorRGB; + } + return hasCustomColor; + } inline bool checkCollideWith(const btCollisionObject* co) const { diff --git a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp index 133994112..3bbf7586e 100644 --- a/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp +++ b/src/BulletCollision/CollisionDispatch/btCollisionWorld.cpp @@ -1572,6 +1572,8 @@ void btCollisionWorld::debugDrawWorld() } }; + colObj->getCustomDebugColor(color); + debugDrawObject(colObj->getWorldTransform(),colObj->getCollisionShape(),color); } if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawAabb)) From 5be4409a1a52c741b13dafa924e1ef258248bc3a Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Mon, 21 Nov 2016 09:13:20 -0800 Subject: [PATCH 12/39] Render shadow buffer. --- examples/TinyRenderer/TinyRenderer.cpp | 56 +++++++++++++++++++++++++- examples/TinyRenderer/our_gl.cpp | 31 ++++++++++++++ 2 files changed, 85 insertions(+), 2 deletions(-) diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 76b9e4053..88102e86a 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -13,7 +13,7 @@ #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" - +const float depth = 2.f; struct Shader : public IShader { @@ -94,6 +94,55 @@ struct Shader : public IShader { } }; +struct DepthShader : public IShader { + + Model* m_model; + Matrix& m_modelMat; + Matrix m_invModelMat; + + Matrix& m_modelView1; + Matrix& m_projectionMatrix; + Vec3f m_localScaling; + Matrix& m_lightModelView; + + mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader + mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS + mat<4,3,float> varying_tri_light_view; // triangle coordinates (clip coordinates), written by VS, read by FS + mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS + + DepthShader(Model* model, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling) + :m_model(model), + m_modelView1(modelView), + m_lightModelView(lightModelView), + m_projectionMatrix(projectionMatrix), + m_modelMat(modelMat), + m_localScaling(localScaling) + { + m_invModelMat = m_modelMat.invert_transpose(); + } + virtual Vec4f vertex(int iface, int nthvert) { + Vec2f uv = m_model->uv(iface, nthvert); + varying_uv.set_col(nthvert, uv); + varying_nrm.set_col(nthvert, proj<3>(m_invModelMat*embed<4>(m_model->normal(iface, nthvert), 0.f))); + Vec3f unScaledVert = m_model->vert(iface, nthvert); + Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0], + unScaledVert[1]*m_localScaling[1], + unScaledVert[2]*m_localScaling[2]); + Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert); + varying_tri.set_col(nthvert, gl_Vertex); + Vec4f gl_VertexLightView = m_projectionMatrix*m_lightModelView*embed<4>(scaledVert); + varying_tri_light_view.set_col(nthvert, gl_VertexLightView); + return gl_Vertex; + } + + virtual bool fragment(Vec3f bar, TGAColor &color) { + Vec4f p = varying_tri_light_view*bar; + printf("coefficient: %f\n", 1.0-p[2]/depth); + color = TGAColor(255, 255, 255)*(1.0-p[2]/depth); + return false; + } +}; + TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer) :m_rgbColorBuffer(rgbColorBuffer), m_depthBuffer(depthBuffer), @@ -283,9 +332,12 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) { + Matrix lightViewMatrix = lookat(Vec3f(0.0,0.1,2.0), Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); + Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); + //Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); + DepthShader shader(model, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling); //printf("Render %d triangles.\n",model->nfaces()); for (int i=0; infaces(); i++) diff --git a/examples/TinyRenderer/our_gl.cpp b/examples/TinyRenderer/our_gl.cpp index eb5a05a78..21300945f 100644 --- a/examples/TinyRenderer/our_gl.cpp +++ b/examples/TinyRenderer/our_gl.cpp @@ -30,6 +30,7 @@ Matrix projection(float coeff) { } Matrix lookat(Vec3f eye, Vec3f center, Vec3f up) { + /* Vec3f z = (eye-center).normalize(); Vec3f x = cross(up,z).normalize(); Vec3f y = cross(z,x).normalize(); @@ -44,6 +45,36 @@ Matrix lookat(Vec3f eye, Vec3f center, Vec3f up) { Matrix ModelView; ModelView = Minv*Tr; return ModelView; + */ + + Vec3f f = (center - eye).normalize(); + Vec3f u = up.normalize(); + Vec3f s = cross(f,u).normalize(); + u = cross(s,f); + + Matrix ModelView; + ModelView[0][0] = s.x; + ModelView[0][1] = s.y; + ModelView[0][2] = s.z; + + ModelView[1][0] = u.x; + ModelView[1][1] = u.y; + ModelView[1][2] = u.z; + + ModelView[2][0] =-f.x; + ModelView[2][1] =-f.y; + ModelView[2][2] =-f.z; + + ModelView[3][0] = 0.f; + ModelView[3][1] = 0.f; + ModelView[3][2] = 0.f; + + ModelView[0][3] = -(s[0]*eye[0]+s[1]*eye[1]+s[2]*eye[2]); + ModelView[1][3] = -(u[0]*eye[0]+u[1]*eye[1]+u[2]*eye[2]); + ModelView[2][3] = f[0]*eye[0]+f[1]*eye[1]+f[2]*eye[2]; + ModelView[3][3] = 1.f; + + return ModelView; } Vec3f barycentric(Vec2f A, Vec2f B, Vec2f C, Vec2f P) { From d4a18c563434d20e576a61102a5332a31ef3f5fd Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Mon, 21 Nov 2016 10:18:48 -0800 Subject: [PATCH 13/39] Update NN3DWalkers.cpp the excessive stack-space requirements in printWalkerConfigs breaks some proprietary/internal build systems. --- examples/Evolution/NN3DWalkers.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/Evolution/NN3DWalkers.cpp b/examples/Evolution/NN3DWalkers.cpp index 148ebee0c..f1420410a 100755 --- a/examples/Evolution/NN3DWalkers.cpp +++ b/examples/Evolution/NN3DWalkers.cpp @@ -1035,6 +1035,7 @@ void NN3DWalkersExample::drawMarkings() { } void NN3DWalkersExample::printWalkerConfigs(){ +#if 0 char configString[25 + NUM_WALKERS*BODYPART_COUNT*JOINT_COUNT*(3+15+1) + NUM_WALKERS*4 + 1]; // 15 precision + [],\n char* runner = configString; sprintf(runner,"Population configuration:"); @@ -1058,4 +1059,5 @@ void NN3DWalkersExample::printWalkerConfigs(){ } runner[0] = '\0'; b3Printf(configString); +#endif } From 24b3e137a606a7da63272a202f2552219db90fe5 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Mon, 21 Nov 2016 10:21:14 -0800 Subject: [PATCH 14/39] Render shadow with depth from light. --- .../SharedMemory/PhysicsClientExample.cpp | 20 ++++- examples/SharedMemory/SharedMemoryPublic.h | 1 + examples/TinyRenderer/TinyRenderer.cpp | 87 ++++++++++++++++++- 3 files changed, 104 insertions(+), 4 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index b0fe2be97..b1bac89d0 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -89,10 +89,10 @@ protected: virtual void resetCamera() { - float dist = 4; + float dist = 1; float pitch = 193; float yaw = 25; - float targetPos[3]={0,0,0.5};//-3,2.8,-2.5}; + float targetPos[3]={0.008655,0.001998,0.679456};//-3,2.8,-2.5}; m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); } @@ -481,6 +481,21 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) } break; } + case CMD_UPDATE_LIGHT: + { + b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); + float viewMatrix[16]; + float projectionMatrix[16]; + m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); + m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); + + b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix); + b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight); + float lightDir[3] = {0.0,0.1,2.0}; + b3RequestCameraImageSetLightDirection(commandHandle, lightDir); + b3SubmitClientCommand(m_physicsClientHandle, commandHandle); + break; + } default: { b3Error("Unknown buttonId"); @@ -557,6 +572,7 @@ void PhysicsClientExample::createButtons() createButton("Load SDF",CMD_LOAD_SDF, isTrigger); createButton("Save World",CMD_SAVE_WORLD, isTrigger); createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger); + createButton("Update Light",CMD_UPDATE_LIGHT,isTrigger); createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger); createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger); createButton("Get Visual Shape Info",CMD_REQUEST_VISUAL_SHAPE_INFO, isTrigger); diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index d6a8e246a..557bdba52 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -38,6 +38,7 @@ enum EnumSharedMemoryClientCommand CMD_REQUEST_AABB_OVERLAP, CMD_SAVE_WORLD, CMD_REQUEST_VISUAL_SHAPE_INFO, + CMD_UPDATE_LIGHT, CMD_UPDATE_VISUAL_SHAPE, CMD_LOAD_TEXTURE, CMD_USER_DEBUG_DRAW, diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 88102e86a..55241670b 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -13,7 +13,7 @@ #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" -const float depth = 2.f; +const float depth = 10.f; struct Shader : public IShader { @@ -143,6 +143,88 @@ struct DepthShader : public IShader { } }; +struct ShadowShader : public IShader { + + Model* m_model; + Vec3f m_light_dir_local; + Vec3f m_light_color; + Matrix& m_modelMat; + Matrix m_invModelMat; + + Matrix& m_modelView1; + Matrix& m_projectionMatrix; + Vec3f m_localScaling; + Matrix& m_lightModelView; + Vec4f m_colorRGBA; + + mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader + mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS + mat<4,3,float> varying_tri_light_view; // triangle coordinates (clip coordinates), written by VS, read by FS + mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS + + ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) + :m_model(model), + m_light_dir_local(light_dir_local), + m_light_color(light_color), + m_modelView1(modelView), + m_lightModelView(lightModelView), + m_projectionMatrix(projectionMatrix), + m_modelMat(modelMat), + m_localScaling(localScaling), + m_colorRGBA(colorRGBA) + { + m_invModelMat = m_modelMat.invert_transpose(); + } + virtual Vec4f vertex(int iface, int nthvert) { + Vec2f uv = m_model->uv(iface, nthvert); + varying_uv.set_col(nthvert, uv); + varying_nrm.set_col(nthvert, proj<3>(m_invModelMat*embed<4>(m_model->normal(iface, nthvert), 0.f))); + Vec3f unScaledVert = m_model->vert(iface, nthvert); + Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0], + unScaledVert[1]*m_localScaling[1], + unScaledVert[2]*m_localScaling[2]); + Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert); + varying_tri.set_col(nthvert, gl_Vertex); + Vec4f gl_VertexLightView = m_projectionMatrix*m_lightModelView*embed<4>(scaledVert); + varying_tri_light_view.set_col(nthvert, gl_VertexLightView); + return gl_Vertex; + } + + virtual bool fragment(Vec3f bar, TGAColor &color) { + Vec4f p = varying_tri_light_view*bar; + float shadow = 1.0-p[2]/depth; + printf("shadow: %f\n", shadow); + + Vec3f bn = (varying_nrm*bar).normalize(); + Vec2f uv = varying_uv*bar; + + Vec3f reflection_direction = (bn * (bn * m_light_dir_local * 2.f) - m_light_dir_local).normalize(); + float specular = pow(b3Max(reflection_direction.z, 0.f), m_model->specular(uv)); + float diffuse = b3Max(0.f, bn * m_light_dir_local); + + float ambient_coefficient = 0.6; + float diffuse_coefficient = 0.35; + float specular_coefficient = 0.05; + + float intensity = ambient_coefficient + b3Min(diffuse * diffuse_coefficient + specular * specular_coefficient, 1.0f - ambient_coefficient); + + color = m_model->diffuse(uv) * intensity * shadow; + + //warning: bgra color is swapped to rgba to upload texture + color.bgra[0] *= m_colorRGBA[0]; + color.bgra[1] *= m_colorRGBA[1]; + color.bgra[2] *= m_colorRGBA[2]; + color.bgra[3] *= m_colorRGBA[3]; + + color.bgra[0] *= m_light_color[0]; + color.bgra[1] *= m_light_color[1]; + color.bgra[2] *= m_light_color[2]; + + return false; + + } +}; + TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer) :m_rgbColorBuffer(rgbColorBuffer), m_depthBuffer(depthBuffer), @@ -337,7 +419,8 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); //Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); - DepthShader shader(model, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling); + //DepthShader shader(model, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling); + ShadowShader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); //printf("Render %d triangles.\n",model->nfaces()); for (int i=0; infaces(); i++) From ca71b84913a6284787ee0341ff8b06d901251c78 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 21 Nov 2016 22:33:23 -0800 Subject: [PATCH 15/39] fix uninitialized m_lightColor (see ExampleBrowser/Rendering/TinyRenderer, Software was black. --- examples/TinyRenderer/TinyRenderer.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 76b9e4053..a9f9ed9c3 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -107,6 +107,7 @@ m_objectIndex(-1) Vec3f center(0,0,0); Vec3f up(0,0,1); m_lightDirWorld.setValue(0,0,0); + m_lightColor.setValue(1, 1, 1); m_localScaling.setValue(1,1,1); m_modelMatrix = Matrix::identity(); @@ -127,6 +128,7 @@ m_objectIndex(objectIndex) Vec3f center(0,0,0); Vec3f up(0,0,1); m_lightDirWorld.setValue(0,0,0); + m_lightColor.setValue(1, 1, 1); m_localScaling.setValue(1,1,1); m_modelMatrix = Matrix::identity(); From 0516d2ecaaceb5ad43d8612413c676961e8e223d Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Tue, 22 Nov 2016 10:11:04 -0800 Subject: [PATCH 16/39] allow getClosestPoints for btCompoundCollisionAlgorithm and btSphereTriangleCollisionAlgorithm add optional 'lightColor' arg to testrender.py script --- examples/pybullet/testrender.py | 3 ++- .../CollisionDispatch/SphereTriangleDetector.cpp | 2 +- .../CollisionDispatch/btCompoundCollisionAlgorithm.cpp | 3 +++ .../CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp | 2 +- 4 files changed, 7 insertions(+), 3 deletions(-) diff --git a/examples/pybullet/testrender.py b/examples/pybullet/testrender.py index 5935c388f..0d3475c84 100644 --- a/examples/pybullet/testrender.py +++ b/examples/pybullet/testrender.py @@ -19,6 +19,7 @@ pixelHeight = 240 nearPlane = 0.01 farPlane = 1000 lightDirection = [0,1,0] +lightColor = [1,1,1]#optional argument fov = 60 #img_arr = pybullet.renderImage(pixelWidth, pixelHeight) @@ -28,7 +29,7 @@ for pitch in range (0,360,10) : viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) aspect = pixelWidth / pixelHeight; projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); - img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection) + img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection,lightColor) w=img_arr[0] h=img_arr[1] rgb=img_arr[2] diff --git a/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp b/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp index 634017809..006cc65a2 100644 --- a/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp +++ b/src/BulletCollision/CollisionDispatch/SphereTriangleDetector.cpp @@ -100,7 +100,7 @@ bool SphereTriangleDetector::collide(const btVector3& sphereCenter,btVector3 &po btScalar radiusWithThreshold = radius + contactBreakingThreshold; btVector3 normal = (vertices[1]-vertices[0]).cross(vertices[2]-vertices[0]); - normal.normalize(); + normal.safeNormalize(); btVector3 p1ToCentre = sphereCenter - vertices[0]; btScalar distanceFromPlane = p1ToCentre.dot(normal); diff --git a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp index 1fc960df5..7f4dea1c6 100644 --- a/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btCompoundCollisionAlgorithm.cpp @@ -292,6 +292,9 @@ void btCompoundCollisionAlgorithm::processCollision (const btCollisionObjectWrap btTransform otherInCompoundSpace; otherInCompoundSpace = colObjWrap->getWorldTransform().inverse() * otherObjWrap->getWorldTransform(); otherObjWrap->getCollisionShape()->getAabb(otherInCompoundSpace,localAabbMin,localAabbMax); + btVector3 extraExtends(resultOut->m_closestPointDistanceThreshold, resultOut->m_closestPointDistanceThreshold, resultOut->m_closestPointDistanceThreshold); + localAabbMin -= extraExtends; + localAabbMax += extraExtends; const ATTRIBUTE_ALIGNED16(btDbvtVolume) bounds=btDbvtVolume::FromMM(localAabbMin,localAabbMax); //process all children, that overlap with the given AABB bounds diff --git a/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp b/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp index 280a4d355..86d4e7440 100644 --- a/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp +++ b/src/BulletCollision/CollisionDispatch/btSphereTriangleCollisionAlgorithm.cpp @@ -56,7 +56,7 @@ void btSphereTriangleCollisionAlgorithm::processCollision (const btCollisionObje /// report a contact. internally this will be kept persistent, and contact reduction is done resultOut->setPersistentManifold(m_manifoldPtr); - SphereTriangleDetector detector(sphere,triangle, m_manifoldPtr->getContactBreakingThreshold()); + SphereTriangleDetector detector(sphere,triangle, m_manifoldPtr->getContactBreakingThreshold()+ resultOut->m_closestPointDistanceThreshold); btDiscreteCollisionDetectorInterface::ClosestPointInput input; input.m_maximumDistanceSquared = btScalar(BT_LARGE_FLOAT);///@todo: tighter bounds From 29809a4471c73324642ae050cd54c76e0f0f9c5d Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Wed, 23 Nov 2016 13:00:26 -0800 Subject: [PATCH 17/39] Render depth buffer. --- .../SharedMemory/PhysicsClientExample.cpp | 20 +--- examples/SharedMemory/SharedMemoryPublic.h | 1 - examples/TinyRenderer/TinyRenderer.cpp | 91 +++++++++++++------ examples/TinyRenderer/our_gl.cpp | 20 +++- 4 files changed, 80 insertions(+), 52 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index b1bac89d0..3b60d3ce7 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -89,10 +89,10 @@ protected: virtual void resetCamera() { - float dist = 1; + float dist = 1.233281; float pitch = 193; float yaw = 25; - float targetPos[3]={0.008655,0.001998,0.679456};//-3,2.8,-2.5}; + float targetPos[3]={0.103042,-0.469102,0.631005};//-3,2.8,-2.5}; m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); } @@ -481,21 +481,6 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) } break; } - case CMD_UPDATE_LIGHT: - { - b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); - float viewMatrix[16]; - float projectionMatrix[16]; - m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); - m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); - - b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix); - b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight); - float lightDir[3] = {0.0,0.1,2.0}; - b3RequestCameraImageSetLightDirection(commandHandle, lightDir); - b3SubmitClientCommand(m_physicsClientHandle, commandHandle); - break; - } default: { b3Error("Unknown buttonId"); @@ -572,7 +557,6 @@ void PhysicsClientExample::createButtons() createButton("Load SDF",CMD_LOAD_SDF, isTrigger); createButton("Save World",CMD_SAVE_WORLD, isTrigger); createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger); - createButton("Update Light",CMD_UPDATE_LIGHT,isTrigger); createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger); createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger); createButton("Get Visual Shape Info",CMD_REQUEST_VISUAL_SHAPE_INFO, isTrigger); diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index 557bdba52..d6a8e246a 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -38,7 +38,6 @@ enum EnumSharedMemoryClientCommand CMD_REQUEST_AABB_OVERLAP, CMD_SAVE_WORLD, CMD_REQUEST_VISUAL_SHAPE_INFO, - CMD_UPDATE_LIGHT, CMD_UPDATE_VISUAL_SHAPE, CMD_LOAD_TEXTURE, CMD_USER_DEBUG_DRAW, diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 55241670b..cf71eb180 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -13,7 +13,8 @@ #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" -const float depth = 10.f; +b3AlignedObjectArray shadowbuffer; +Matrix viewportmat; struct Shader : public IShader { @@ -100,19 +101,17 @@ struct DepthShader : public IShader { Matrix& m_modelMat; Matrix m_invModelMat; - Matrix& m_modelView1; Matrix& m_projectionMatrix; Vec3f m_localScaling; Matrix& m_lightModelView; mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS - mat<4,3,float> varying_tri_light_view; // triangle coordinates (clip coordinates), written by VS, read by FS + mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - DepthShader(Model* model, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling) + DepthShader(Model* model, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling) :m_model(model), - m_modelView1(modelView), m_lightModelView(lightModelView), m_projectionMatrix(projectionMatrix), m_modelMat(modelMat), @@ -128,17 +127,14 @@ struct DepthShader : public IShader { Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0], unScaledVert[1]*m_localScaling[1], unScaledVert[2]*m_localScaling[2]); - Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert); + Vec4f gl_Vertex = m_projectionMatrix*m_lightModelView*embed<4>(scaledVert); varying_tri.set_col(nthvert, gl_Vertex); - Vec4f gl_VertexLightView = m_projectionMatrix*m_lightModelView*embed<4>(scaledVert); - varying_tri_light_view.set_col(nthvert, gl_VertexLightView); return gl_Vertex; } virtual bool fragment(Vec3f bar, TGAColor &color) { - Vec4f p = varying_tri_light_view*bar; - printf("coefficient: %f\n", 1.0-p[2]/depth); - color = TGAColor(255, 255, 255)*(1.0-p[2]/depth); + Vec4f p = varying_tri*bar; + color = TGAColor(255, 255, 255)*p[2]; return false; } }; @@ -157,12 +153,17 @@ struct ShadowShader : public IShader { Matrix& m_lightModelView; Vec4f m_colorRGBA; + int m_width; + int m_height; + + int m_index; + mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS - mat<4,3,float> varying_tri_light_view; // triangle coordinates (clip coordinates), written by VS, read by FS + mat<4,3,float> varying_tri_light_view; mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) + ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height) :m_model(model), m_light_dir_local(light_dir_local), m_light_color(light_color), @@ -171,7 +172,9 @@ struct ShadowShader : public IShader { m_projectionMatrix(projectionMatrix), m_modelMat(modelMat), m_localScaling(localScaling), - m_colorRGBA(colorRGBA) + m_colorRGBA(colorRGBA), + m_width(width), + m_height(height) { m_invModelMat = m_modelMat.invert_transpose(); } @@ -191,9 +194,15 @@ struct ShadowShader : public IShader { } virtual bool fragment(Vec3f bar, TGAColor &color) { - Vec4f p = varying_tri_light_view*bar; - float shadow = 1.0-p[2]/depth; - printf("shadow: %f\n", shadow); + Vec4f p = viewportmat*(varying_tri_light_view*bar); + p = p/p[3]; + float depth = p[2]; + int index_x = b3Min(m_width-1, int(p[0])); + index_x = b3Max(0, index_x); + int index_y = b3Min(m_height-1, int(p[1])); + index_y = b3Max(0, index_y); + int idx = index_x + index_y*m_width; // index in the shadowbuffer array + float shadow = 0.3+0.7*(shadowbuffer[idx]<-depth); // magic coeff to avoid z-fighting Vec3f bn = (varying_nrm*bar).normalize(); Vec2f uv = varying_uv*bar; @@ -401,37 +410,63 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) Model* model = renderData.m_model; if (0==model) return; - - renderData.m_viewportMatrix = viewport(0,0,width, height); b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; + TGAImage tempFrame(width, height, TGAImage::RGB); TGAImage& frame = renderData.m_rgbColorBuffer; - - + shadowbuffer.resize(zbuffer.size()); + for (int i = 0; i < shadowbuffer.size(); ++i) + { + shadowbuffer[i] = -1e30f; + } { - Matrix lightViewMatrix = lookat(Vec3f(0.0,0.1,2.0), Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); + Matrix lightViewMatrix = lookat(light_dir_local, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; + Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; + viewportmat = renderData.m_viewportMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - //Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); - //DepthShader shader(model, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling); - ShadowShader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); - - //printf("Render %d triangles.\n",model->nfaces()); + + + DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling); + for (int i=0; infaces(); i++) { - for (int j=0; j<3; j++) { shader.vertex(i, j); } triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); } + /* + ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA(), width, height); + + for (int i=0; infaces(); i++) + { + for (int j=0; j<3; j++) { + shadowShader.vertex(i, j); + } + triangle(shadowShader.varying_tri, shadowShader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + } + + Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); + + //printf("Render %d triangles.\n",model->nfaces()); + for (int i=0; infaces(); i++) + { + + for (int j=0; j<3; j++) { + shader.vertex(i, j); + } + triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + } + */ + } } diff --git a/examples/TinyRenderer/our_gl.cpp b/examples/TinyRenderer/our_gl.cpp index 21300945f..c2f529597 100644 --- a/examples/TinyRenderer/our_gl.cpp +++ b/examples/TinyRenderer/our_gl.cpp @@ -4,13 +4,11 @@ #include "our_gl.h" #include "Bullet3Common/b3MinMax.h" - - - IShader::~IShader() {} Matrix viewport(int x, int y, int w, int h) { + Matrix Viewport; Viewport = Matrix::identity(); Viewport[0][3] = x+w/2.f; @@ -20,6 +18,18 @@ Matrix viewport(int x, int y, int w, int h) Viewport[1][1] = h/2.f; Viewport[2][2] = 0; return Viewport; + + /* + Matrix Viewport; + Viewport = Matrix::identity(); + Viewport[0][3] = x+w/2.f; + Viewport[1][3] = y+h/2.f; + Viewport[2][3] = .5f; + Viewport[0][0] = w/2.f; + Viewport[1][1] = h/2.f; + Viewport[2][2] = .5f; + return Viewport; + */ } Matrix projection(float coeff) { @@ -75,6 +85,7 @@ Matrix lookat(Vec3f eye, Vec3f center, Vec3f up) { ModelView[3][3] = 1.f; return ModelView; + } Vec3f barycentric(Vec2f A, Vec2f B, Vec2f C, Vec2f P) { @@ -97,8 +108,7 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zbuffer, int* segmentationMaskBuffer, const Matrix& viewPortMatrix, int objectIndex) { mat<3,4,float> pts = (viewPortMatrix*clipc).transpose(); // transposed to ease access to each of the points - - + //we don't clip triangles that cross the near plane, just discard them instead of showing artifacts if (pts[0][3]<0 || pts[1][3] <0 || pts[2][3] <0) return; From 529274a3f4234bbd5657ee02907d7dd084b61ed5 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sun, 27 Nov 2016 15:32:55 -0800 Subject: [PATCH 18/39] Render shadow of torus with shadow buffer and index from triangle order. --- .../RenderingExamples/TinyRendererSetup.cpp | 4 ++ .../SharedMemory/PhysicsClientExample.cpp | 2 +- .../TinyRendererVisualShapeConverter.cpp | 7 +- examples/TinyRenderer/TinyRenderer.cpp | 72 +++++++++++++------ examples/TinyRenderer/TinyRenderer.h | 5 +- examples/TinyRenderer/main.cpp | 1 + examples/TinyRenderer/our_gl.cpp | 16 +++-- 7 files changed, 76 insertions(+), 31 deletions(-) diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index a38b13abd..84f7b0033 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -23,6 +23,7 @@ struct TinyRendererSetupInternalData TGAImage m_rgbColorBuffer; b3AlignedObjectArray m_depthBuffer; + b3AlignedObjectArray m_shadowBuffer; b3AlignedObjectArray m_segmentationMaskBuffer; @@ -53,6 +54,7 @@ struct TinyRendererSetupInternalData m_animateRenderer(0) { m_depthBuffer.resize(m_width*m_height); + m_shadowBuffer.resize(m_width*m_height); // m_segmentationMaskBuffer.resize(m_width*m_height); } @@ -188,6 +190,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui) TinyRenderObjectData* ob = new TinyRenderObjectData( m_internalData->m_rgbColorBuffer, m_internalData->m_depthBuffer, + m_internalData->m_shadowBuffer, &m_internalData->m_segmentationMaskBuffer, m_internalData->m_renderObjects.size()); @@ -328,6 +331,7 @@ void TinyRendererSetup::stepSimulation(float deltaTime) { m_internalData->m_rgbColorBuffer.set(x,y,clearColor); m_internalData->m_depthBuffer[x+y*m_internalData->m_width] = -1e30f; + m_internalData->m_shadowBuffer[x+y*m_internalData->m_width] = -1e30f; } } diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 3b60d3ce7..33849d923 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -242,7 +242,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) { case CMD_LOAD_URDF: { - b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf"); + b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "torus/torus.urdf"); //setting the initial position, orientation and other arguments are optional double startPosX = 0; static double startPosY = 0; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 34478bee7..53d19c503 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -72,6 +72,7 @@ struct TinyRendererVisualShapeConverterInternalData TGAImage m_rgbColorBuffer; b3AlignedObjectArray m_textures; b3AlignedObjectArray m_depthBuffer; + b3AlignedObjectArray m_shadowBuffer; b3AlignedObjectArray m_segmentationMaskBuffer; btVector3 m_lightDirection; bool m_hasLightDirection; @@ -89,6 +90,7 @@ struct TinyRendererVisualShapeConverterInternalData m_hasLightColor(false) { m_depthBuffer.resize(m_swWidth*m_swHeight); + m_shadowBuffer.resize(m_swWidth*m_swHeight); m_segmentationMaskBuffer.resize(m_swWidth*m_swHeight,-1); } @@ -552,7 +554,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const if (vertices.size() && indices.size()) { - TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId); + TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId); unsigned char* textureImage=0; int textureWidth=0; int textureHeight=0; @@ -658,6 +660,7 @@ void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor) { m_data->m_rgbColorBuffer.set(x,y,clearColor); m_data->m_depthBuffer[x+y*m_data->m_swWidth] = -1e30f; + m_data->m_shadowBuffer[x+y*m_data->m_swWidth] = -1e30f; m_data->m_segmentationMaskBuffer[x+y*m_data->m_swWidth] = -1; } } @@ -772,6 +775,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo for (int i=0;im_swWidth;i++) { btSwap(m_data->m_depthBuffer[l1+i],m_data->m_depthBuffer[l2+i]); + btSwap(m_data->m_shadowBuffer[l1+i],m_data->m_shadowBuffer[l2+i]); btSwap(m_data->m_segmentationMaskBuffer[l1+i],m_data->m_segmentationMaskBuffer[l2+i]); } } @@ -791,6 +795,7 @@ void TinyRendererVisualShapeConverter::setWidthAndHeight(int width, int height) m_data->m_swHeight = height; m_data->m_depthBuffer.resize(m_data->m_swWidth*m_data->m_swHeight); + m_data->m_shadowBuffer.resize(m_data->m_swWidth*m_data->m_swHeight); m_data->m_segmentationMaskBuffer.resize(m_data->m_swWidth*m_data->m_swHeight); m_data->m_rgbColorBuffer = TGAImage(width, height, TGAImage::RGB); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index cf71eb180..d41e6450f 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -13,8 +13,11 @@ #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" -b3AlignedObjectArray shadowbuffer; Matrix viewportmat; +float depth = 2.0; +int indexmap[10000000]; +int count = 0; +bool setindex = true; struct Shader : public IShader { @@ -134,7 +137,7 @@ struct DepthShader : public IShader { virtual bool fragment(Vec3f bar, TGAColor &color) { Vec4f p = varying_tri*bar; - color = TGAColor(255, 255, 255)*p[2]; + color = TGAColor(255, 255, 255)*(p[2]/depth); return false; } }; @@ -153,6 +156,8 @@ struct ShadowShader : public IShader { Matrix& m_lightModelView; Vec4f m_colorRGBA; + b3AlignedObjectArray& m_shadowBuffer; + int m_width; int m_height; @@ -163,7 +168,7 @@ struct ShadowShader : public IShader { mat<4,3,float> varying_tri_light_view; mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height) + ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray& shadowBuffer) :m_model(model), m_light_dir_local(light_dir_local), m_light_color(light_color), @@ -174,7 +179,8 @@ struct ShadowShader : public IShader { m_localScaling(localScaling), m_colorRGBA(colorRGBA), m_width(width), - m_height(height) + m_height(height), + m_shadowBuffer(shadowBuffer) { m_invModelMat = m_modelMat.invert_transpose(); } @@ -195,14 +201,18 @@ struct ShadowShader : public IShader { virtual bool fragment(Vec3f bar, TGAColor &color) { Vec4f p = viewportmat*(varying_tri_light_view*bar); - p = p/p[3]; float depth = p[2]; - int index_x = b3Min(m_width-1, int(p[0])); - index_x = b3Max(0, index_x); - int index_y = b3Min(m_height-1, int(p[1])); - index_y = b3Max(0, index_y); - int idx = index_x + index_y*m_width; // index in the shadowbuffer array - float shadow = 0.3+0.7*(shadowbuffer[idx]<-depth); // magic coeff to avoid z-fighting + //p = p/p[3]; + //int index_x = b3Min(m_width-1, int(p[0])); + //index_x = b3Max(0, index_x); + //int index_y = b3Min(m_height-1, int(p[1])); + //index_y = b3Max(0, index_y); + //int idx = index_x + index_y*m_width; // index in the shadowbuffer array + int idx = indexmap[count]; + float shadow = 0.8+0.2*(m_shadowBuffer[idx]<-depth+0.43); // magic coeff to avoid z-fighting + + //printf("count: %d, idx: %d\n", count, idx); + //printf("shadowbuffer: %f, depth: %f\n", m_shadowBuffer[idx], -depth+0.43); Vec3f bn = (varying_nrm*bar).normalize(); Vec2f uv = varying_uv*bar; @@ -234,9 +244,10 @@ struct ShadowShader : public IShader { } }; -TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer) +TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray&shadowBuffer) :m_rgbColorBuffer(rgbColorBuffer), m_depthBuffer(depthBuffer), +m_shadowBuffer(shadowBuffer), m_segmentationMaskBufferPtr(0), m_model(0), m_userData(0), @@ -254,9 +265,10 @@ m_objectIndex(-1) -TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer, b3AlignedObjectArray* segmentationMaskBuffer, int objectIndex) +TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer, b3AlignedObjectArray&shadowBuffer, b3AlignedObjectArray* segmentationMaskBuffer, int objectIndex) :m_rgbColorBuffer(rgbColorBuffer), m_depthBuffer(depthBuffer), +m_shadowBuffer(shadowBuffer), m_segmentationMaskBufferPtr(segmentationMaskBuffer), m_model(0), m_userData(0), @@ -414,18 +426,14 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) renderData.m_viewportMatrix = viewport(0,0,width, height); b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; + b3AlignedObjectArray& shadowbuffer = renderData.m_shadowBuffer; int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; TGAImage tempFrame(width, height, TGAImage::RGB); TGAImage& frame = renderData.m_rgbColorBuffer; - shadowbuffer.resize(zbuffer.size()); - for (int i = 0; i < shadowbuffer.size(); ++i) + { - shadowbuffer[i] = -1e30f; - } - - { - Matrix lightViewMatrix = lookat(light_dir_local, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); + Matrix lightViewMatrix = lookat(light_dir_local*depth, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; @@ -435,16 +443,31 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling); + setindex = true; + count = 0; + for (int i=0; infaces(); i++) { for (int j=0; j<3; j++) { shader.vertex(i, j); } - triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + triangle(shader.varying_tri, shader, tempFrame, &shadowbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + count++; } - /* - ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA(), width, height); + for (int k = 0; k < 76800; ++k) + { + if (shadowbuffer[k] > -1e30f+0.00001) + { + printf("[%d]: %f\n", k, shadowbuffer[k]); + } + } + + + ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); + + setindex = false; + count = 0; for (int i=0; infaces(); i++) { @@ -452,8 +475,11 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) shadowShader.vertex(i, j); } triangle(shadowShader.varying_tri, shadowShader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + count++; } + + /* Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); //printf("Render %d triangles.\n",model->nfaces()); diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index fcb8298bd..745667782 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -29,10 +29,11 @@ struct TinyRenderObjectData TGAImage& m_rgbColorBuffer; b3AlignedObjectArray& m_depthBuffer;//required, hence a reference + b3AlignedObjectArray& m_shadowBuffer; b3AlignedObjectArray* m_segmentationMaskBufferPtr;//optional, hence a pointer - TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer); - TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer, b3AlignedObjectArray* segmentationMaskBuffer,int objectIndex); + TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray&shadowBuffer); + TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray&shadowBuffer, b3AlignedObjectArray* segmentationMaskBuffer,int objectIndex); virtual ~TinyRenderObjectData(); void loadModel(const char* fileName); diff --git a/examples/TinyRenderer/main.cpp b/examples/TinyRenderer/main.cpp index 32f5e7edd..614b12d3a 100644 --- a/examples/TinyRenderer/main.cpp +++ b/examples/TinyRenderer/main.cpp @@ -147,6 +147,7 @@ int main(int argc, char* argv[]) renderData.m_rgbColorBuffer.set(x,y,color); renderData.m_depthBuffer[x+y*textureWidth] = -1e30f; + renderData.m_shadowBuffer[x+y*textureWidth] = -1e30f; } } diff --git a/examples/TinyRenderer/our_gl.cpp b/examples/TinyRenderer/our_gl.cpp index c2f529597..46c08dd45 100644 --- a/examples/TinyRenderer/our_gl.cpp +++ b/examples/TinyRenderer/our_gl.cpp @@ -4,11 +4,15 @@ #include "our_gl.h" #include "Bullet3Common/b3MinMax.h" +extern int indexmap[10000000]; +extern int count; +extern bool setindex; + IShader::~IShader() {} Matrix viewport(int x, int y, int w, int h) { - + /* Matrix Viewport; Viewport = Matrix::identity(); Viewport[0][3] = x+w/2.f; @@ -18,8 +22,8 @@ Matrix viewport(int x, int y, int w, int h) Viewport[1][1] = h/2.f; Viewport[2][2] = 0; return Viewport; + */ - /* Matrix Viewport; Viewport = Matrix::identity(); Viewport[0][3] = x+w/2.f; @@ -29,7 +33,7 @@ Matrix viewport(int x, int y, int w, int h) Viewport[1][1] = h/2.f; Viewport[2][2] = .5f; return Viewport; - */ + } Matrix projection(float coeff) { @@ -140,7 +144,11 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb Vec3f bc_clip = Vec3f(bc_screen.x/pts[0][3], bc_screen.y/pts[1][3], bc_screen.z/pts[2][3]); bc_clip = bc_clip/(bc_clip.x+bc_clip.y+bc_clip.z); float frag_depth = -1*(clipc[2]*bc_clip); - if (bc_screen.x<0 || bc_screen.y<0 || bc_screen.z<0 || + if (setindex) + { + indexmap[count] = P.x+P.y*image.get_width(); + } + if (bc_screen.x<0 || bc_screen.y<0 || bc_screen.z<0 || zbuffer[P.x+P.y*image.get_width()]>frag_depth) continue; bool discard = shader.fragment(bc_clip, color); From 583dc1cac713c610267d587b56bdc5f1b68c9348 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sun, 27 Nov 2016 15:34:01 -0800 Subject: [PATCH 19/39] Add torus. --- data/torus/torus.mtl | 10 + data/torus/torus.obj | 1446 +++++++++++++++++++++++++++++++++++++++++ data/torus/torus.urdf | 33 + 3 files changed, 1489 insertions(+) create mode 100644 data/torus/torus.mtl create mode 100644 data/torus/torus.obj create mode 100644 data/torus/torus.urdf diff --git a/data/torus/torus.mtl b/data/torus/torus.mtl new file mode 100644 index 000000000..70d3ba1da --- /dev/null +++ b/data/torus/torus.mtl @@ -0,0 +1,10 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 diff --git a/data/torus/torus.obj b/data/torus/torus.obj new file mode 100644 index 000000000..4aafd8fce --- /dev/null +++ b/data/torus/torus.obj @@ -0,0 +1,1446 @@ +# Blender v2.77 (sub 0) OBJ File: '' +# www.blender.org +mtllib torus.mtl +o Torus +v 1.269537 0.006289 0.009606 +v 1.236043 0.131289 0.009606 +v 1.144537 0.222796 0.009606 +v 1.019537 0.256289 0.009606 +v 0.894537 0.222796 0.009606 +v 0.803031 0.131289 0.009606 +v 0.769537 0.006289 0.009606 +v 0.803031 -0.118711 0.009606 +v 0.894537 -0.210217 0.009606 +v 1.019537 -0.243711 0.009606 +v 1.144537 -0.210217 0.009606 +v 1.236043 -0.118711 0.009606 +v 1.258843 0.006289 -0.153552 +v 1.225636 0.131289 -0.149180 +v 1.134912 0.222796 -0.137236 +v 1.010982 0.256289 -0.120920 +v 0.887051 0.222796 -0.104605 +v 0.796328 0.131289 -0.092661 +v 0.763121 0.006289 -0.088289 +v 0.796328 -0.118711 -0.092661 +v 0.887051 -0.210217 -0.104605 +v 1.010982 -0.243711 -0.120920 +v 1.134912 -0.210217 -0.137236 +v 1.225636 -0.118711 -0.149180 +v 1.226944 0.006289 -0.313918 +v 1.194592 0.131289 -0.305249 +v 1.106204 0.222796 -0.281566 +v 0.985463 0.256289 -0.249213 +v 0.864722 0.222796 -0.216861 +v 0.776334 0.131289 -0.193177 +v 0.743981 0.006289 -0.184509 +v 0.776334 -0.118711 -0.193177 +v 0.864722 -0.210217 -0.216861 +v 0.985463 -0.243711 -0.249213 +v 1.106204 -0.210217 -0.281566 +v 1.194592 -0.118711 -0.305249 +v 1.174387 0.006289 -0.468749 +v 1.143442 0.131289 -0.455931 +v 1.058902 0.222796 -0.420913 +v 0.943417 0.256289 -0.373078 +v 0.827932 0.222796 -0.325242 +v 0.743391 0.131289 -0.290224 +v 0.712447 0.006289 -0.277407 +v 0.743391 -0.118711 -0.290224 +v 0.827932 -0.210217 -0.325242 +v 0.943417 -0.243711 -0.373078 +v 1.058902 -0.210217 -0.420913 +v 1.143442 -0.118711 -0.455931 +v 1.102069 0.006289 -0.615394 +v 1.073062 0.131289 -0.598648 +v 0.993815 0.222796 -0.552894 +v 0.885562 0.256289 -0.490394 +v 0.777309 0.222796 -0.427894 +v 0.698062 0.131289 -0.382141 +v 0.669056 0.006289 -0.365394 +v 0.698062 -0.118711 -0.382141 +v 0.777309 -0.210217 -0.427894 +v 0.885562 -0.243711 -0.490394 +v 0.993815 -0.210217 -0.552894 +v 1.073062 -0.118711 -0.598648 +v 1.011229 0.006289 -0.751346 +v 0.984656 0.131289 -0.730956 +v 0.912059 0.222796 -0.675251 +v 0.812890 0.256289 -0.599156 +v 0.713721 0.222796 -0.523061 +v 0.641124 0.131289 -0.467355 +v 0.614552 0.006289 -0.446965 +v 0.641124 -0.118711 -0.467355 +v 0.713721 -0.210217 -0.523061 +v 0.812890 -0.243711 -0.599156 +v 0.912059 -0.210217 -0.675251 +v 0.984656 -0.118711 -0.730956 +v 0.903420 0.006289 -0.874278 +v 0.879737 0.131289 -0.850594 +v 0.815032 0.222796 -0.785889 +v 0.726644 0.256289 -0.697501 +v 0.638255 0.222796 -0.609113 +v 0.573551 0.131289 -0.544408 +v 0.549867 0.006289 -0.520724 +v 0.573551 -0.118711 -0.544408 +v 0.638255 -0.210217 -0.609113 +v 0.726644 -0.243711 -0.697501 +v 0.815032 -0.210217 -0.785889 +v 0.879737 -0.118711 -0.850594 +v 0.780489 0.006289 -0.982086 +v 0.760099 0.131289 -0.955514 +v 0.704394 0.222796 -0.882917 +v 0.628298 0.256289 -0.783747 +v 0.552203 0.222796 -0.684578 +v 0.496498 0.131289 -0.611982 +v 0.476108 0.006289 -0.585409 +v 0.496498 -0.118711 -0.611982 +v 0.552203 -0.210217 -0.684578 +v 0.628298 -0.243711 -0.783747 +v 0.704394 -0.210217 -0.882917 +v 0.760099 -0.118711 -0.955514 +v 0.644537 0.006289 -1.072926 +v 0.627790 0.131289 -1.043920 +v 0.582037 0.222796 -0.964673 +v 0.519537 0.256289 -0.856420 +v 0.457037 0.222796 -0.748167 +v 0.411284 0.131289 -0.668920 +v 0.394537 0.006289 -0.639913 +v 0.411284 -0.118711 -0.668920 +v 0.457037 -0.210217 -0.748167 +v 0.519537 -0.243711 -0.856420 +v 0.582037 -0.210217 -0.964673 +v 0.627790 -0.118711 -1.043920 +v 0.497891 0.006289 -1.145244 +v 0.485074 0.131289 -1.114299 +v 0.450056 0.222796 -1.029759 +v 0.402221 0.256289 -0.914274 +v 0.354385 0.222796 -0.798789 +v 0.319367 0.131289 -0.714248 +v 0.306550 0.006289 -0.683304 +v 0.319367 -0.118711 -0.714248 +v 0.354385 -0.210217 -0.798789 +v 0.402221 -0.243711 -0.914274 +v 0.450056 -0.210217 -1.029759 +v 0.485074 -0.118711 -1.114299 +v 0.343061 0.006289 -1.197802 +v 0.334392 0.131289 -1.165449 +v 0.310708 0.222796 -1.077061 +v 0.278356 0.256289 -0.956320 +v 0.246004 0.222796 -0.835579 +v 0.222320 0.131289 -0.747191 +v 0.213651 0.006289 -0.714839 +v 0.222320 -0.118711 -0.747191 +v 0.246004 -0.210217 -0.835579 +v 0.278356 -0.243711 -0.956320 +v 0.310708 -0.210217 -1.077061 +v 0.334392 -0.118711 -1.165449 +v 0.182694 0.006289 -1.229700 +v 0.178323 0.131289 -1.196493 +v 0.166379 0.222796 -1.105770 +v 0.150063 0.256289 -0.981839 +v 0.133747 0.222796 -0.857909 +v 0.121803 0.131289 -0.767185 +v 0.117431 0.006289 -0.733978 +v 0.121803 -0.118711 -0.767185 +v 0.133747 -0.210217 -0.857909 +v 0.150063 -0.243711 -0.981839 +v 0.166379 -0.210217 -1.105770 +v 0.178323 -0.118711 -1.196493 +v 0.019537 0.006289 -1.240394 +v 0.019537 0.131289 -1.206901 +v 0.019537 0.222796 -1.115394 +v 0.019537 0.256289 -0.990394 +v 0.019537 0.222796 -0.865394 +v 0.019537 0.131289 -0.773888 +v 0.019537 0.006289 -0.740394 +v 0.019537 -0.118711 -0.773888 +v 0.019537 -0.210217 -0.865394 +v 0.019537 -0.243711 -0.990394 +v 0.019537 -0.210217 -1.115394 +v 0.019537 -0.118711 -1.206901 +v -0.143621 0.006289 -1.229700 +v -0.139249 0.131289 -1.196493 +v -0.127305 0.222796 -1.105770 +v -0.110989 0.256289 -0.981839 +v -0.094674 0.222796 -0.857909 +v -0.082730 0.131289 -0.767185 +v -0.078358 0.006289 -0.733978 +v -0.082730 -0.118711 -0.767185 +v -0.094674 -0.210217 -0.857909 +v -0.110989 -0.243711 -0.981839 +v -0.127305 -0.210217 -1.105770 +v -0.139249 -0.118711 -1.196493 +v -0.303987 0.006289 -1.197802 +v -0.295318 0.131289 -1.165449 +v -0.271634 0.222796 -1.077061 +v -0.239282 0.256289 -0.956320 +v -0.206930 0.222796 -0.835580 +v -0.183246 0.131289 -0.747191 +v -0.174577 0.006289 -0.714839 +v -0.183246 -0.118711 -0.747191 +v -0.206930 -0.210217 -0.835580 +v -0.239282 -0.243711 -0.956320 +v -0.271634 -0.210217 -1.077061 +v -0.295318 -0.118711 -1.165449 +v -0.458818 0.006289 -1.145244 +v -0.446000 0.131289 -1.114300 +v -0.410982 0.222796 -1.029759 +v -0.363147 0.256289 -0.914274 +v -0.315311 0.222796 -0.798789 +v -0.280293 0.131289 -0.714248 +v -0.267476 0.006289 -0.683304 +v -0.280293 -0.118711 -0.714248 +v -0.315311 -0.210217 -0.798789 +v -0.363147 -0.243711 -0.914274 +v -0.410982 -0.210217 -1.029759 +v -0.446000 -0.118711 -1.114300 +v -0.605463 0.006289 -1.072926 +v -0.588716 0.131289 -1.043920 +v -0.542963 0.222796 -0.964673 +v -0.480463 0.256289 -0.856420 +v -0.417963 0.222796 -0.748167 +v -0.372210 0.131289 -0.668920 +v -0.355463 0.006289 -0.639913 +v -0.372210 -0.118711 -0.668920 +v -0.417963 -0.210217 -0.748167 +v -0.480463 -0.243711 -0.856420 +v -0.542963 -0.210217 -0.964673 +v -0.588716 -0.118711 -1.043920 +v -0.741415 0.006289 -0.982086 +v -0.721025 0.131289 -0.955514 +v -0.665320 0.222796 -0.882917 +v -0.589225 0.256289 -0.783748 +v -0.513129 0.222796 -0.684578 +v -0.457424 0.131289 -0.611982 +v -0.437034 0.006289 -0.585409 +v -0.457424 -0.118711 -0.611982 +v -0.513129 -0.210217 -0.684578 +v -0.589225 -0.243711 -0.783748 +v -0.665320 -0.210217 -0.882917 +v -0.721025 -0.118711 -0.955514 +v -0.864347 0.006289 -0.874277 +v -0.840663 0.131289 -0.850594 +v -0.775958 0.222796 -0.785889 +v -0.687570 0.256289 -0.697501 +v -0.599182 0.222796 -0.609113 +v -0.534477 0.131289 -0.544408 +v -0.510793 0.006289 -0.520724 +v -0.534477 -0.118711 -0.544408 +v -0.599182 -0.210217 -0.609113 +v -0.687570 -0.243711 -0.697501 +v -0.775958 -0.210217 -0.785889 +v -0.840663 -0.118711 -0.850594 +v -0.972155 0.006289 -0.751346 +v -0.945583 0.131289 -0.730956 +v -0.872986 0.222796 -0.675251 +v -0.773816 0.256289 -0.599156 +v -0.674647 0.222796 -0.523061 +v -0.602050 0.131289 -0.467355 +v -0.575478 0.006289 -0.446965 +v -0.602050 -0.118711 -0.467355 +v -0.674647 -0.210217 -0.523061 +v -0.773816 -0.243711 -0.599156 +v -0.872986 -0.210217 -0.675251 +v -0.945583 -0.118711 -0.730956 +v -1.062995 0.006289 -0.615395 +v -1.033988 0.131289 -0.598648 +v -0.954742 0.222796 -0.552895 +v -0.846488 0.256289 -0.490395 +v -0.738235 0.222796 -0.427895 +v -0.658988 0.131289 -0.382141 +v -0.629982 0.006289 -0.365395 +v -0.658988 -0.118711 -0.382141 +v -0.738235 -0.210217 -0.427895 +v -0.846488 -0.243711 -0.490395 +v -0.954742 -0.210217 -0.552895 +v -1.033988 -0.118711 -0.598648 +v -1.135312 0.006289 -0.468749 +v -1.104368 0.131289 -0.455931 +v -1.019827 0.222796 -0.420913 +v -0.904343 0.256289 -0.373078 +v -0.788858 0.222796 -0.325242 +v -0.704317 0.131289 -0.290224 +v -0.673373 0.006289 -0.277407 +v -0.704317 -0.118711 -0.290224 +v -0.788858 -0.210217 -0.325242 +v -0.904343 -0.243711 -0.373078 +v -1.019827 -0.210217 -0.420913 +v -1.104368 -0.118711 -0.455931 +v -1.187871 0.006289 -0.313918 +v -1.155518 0.131289 -0.305249 +v -1.067130 0.222796 -0.281566 +v -0.946389 0.256289 -0.249213 +v -0.825648 0.222796 -0.216861 +v -0.737260 0.131289 -0.193177 +v -0.704908 0.006289 -0.184508 +v -0.737260 -0.118711 -0.193177 +v -0.825648 -0.210217 -0.216861 +v -0.946389 -0.243711 -0.249213 +v -1.067130 -0.210217 -0.281566 +v -1.155518 -0.118711 -0.305249 +v -1.219769 0.006289 -0.153552 +v -1.186562 0.131289 -0.149180 +v -1.095839 0.222796 -0.137236 +v -0.971908 0.256289 -0.120921 +v -0.847977 0.222796 -0.104605 +v -0.757254 0.131289 -0.092661 +v -0.724047 0.006289 -0.088289 +v -0.757254 -0.118711 -0.092661 +v -0.847977 -0.210217 -0.104605 +v -0.971908 -0.243711 -0.120921 +v -1.095839 -0.210217 -0.137236 +v -1.186562 -0.118711 -0.149180 +v -1.230463 0.006289 0.009606 +v -1.196970 0.131289 0.009606 +v -1.105463 0.222796 0.009606 +v -0.980463 0.256289 0.009606 +v -0.855463 0.222796 0.009606 +v -0.763957 0.131289 0.009606 +v -0.730463 0.006289 0.009606 +v -0.763957 -0.118711 0.009606 +v -0.855463 -0.210217 0.009606 +v -0.980463 -0.243711 0.009606 +v -1.105463 -0.210217 0.009606 +v -1.196970 -0.118711 0.009606 +v -1.219769 0.006289 0.172764 +v -1.186562 0.131289 0.168392 +v -1.095839 0.222796 0.156448 +v -0.971908 0.256289 0.140132 +v -0.847977 0.222796 0.123816 +v -0.757254 0.131289 0.111872 +v -0.724047 0.006289 0.107500 +v -0.757254 -0.118711 0.111872 +v -0.847977 -0.210217 0.123816 +v -0.971908 -0.243711 0.140132 +v -1.095839 -0.210217 0.156448 +v -1.186562 -0.118711 0.168392 +v -1.187871 0.006289 0.333129 +v -1.155518 0.131289 0.324461 +v -1.067130 0.222796 0.300777 +v -0.946389 0.256289 0.268425 +v -0.825648 0.222796 0.236072 +v -0.737260 0.131289 0.212389 +v -0.704908 0.006289 0.203720 +v -0.737260 -0.118711 0.212389 +v -0.825648 -0.210217 0.236072 +v -0.946389 -0.243711 0.268425 +v -1.067130 -0.210217 0.300777 +v -1.155518 -0.118711 0.324461 +v -1.135313 0.006289 0.487960 +v -1.104369 0.131289 0.475142 +v -1.019828 0.222796 0.440124 +v -0.904343 0.256289 0.392289 +v -0.788858 0.222796 0.344453 +v -0.704317 0.131289 0.309435 +v -0.673373 0.006289 0.296618 +v -0.704317 -0.118711 0.309435 +v -0.788858 -0.210217 0.344453 +v -0.904343 -0.243711 0.392289 +v -1.019828 -0.210217 0.440124 +v -1.104369 -0.118711 0.475142 +v -1.062995 0.006289 0.634606 +v -1.033989 0.131289 0.617859 +v -0.954742 0.222796 0.572106 +v -0.846489 0.256289 0.509606 +v -0.738235 0.222796 0.447106 +v -0.658989 0.131289 0.401352 +v -0.629982 0.006289 0.384606 +v -0.658989 -0.118711 0.401352 +v -0.738235 -0.210217 0.447106 +v -0.846489 -0.243711 0.509606 +v -0.954742 -0.210217 0.572106 +v -1.033989 -0.118711 0.617859 +v -0.972155 0.006289 0.770558 +v -0.945583 0.131289 0.750168 +v -0.872986 0.222796 0.694462 +v -0.773816 0.256289 0.618367 +v -0.674647 0.222796 0.542272 +v -0.602050 0.131289 0.486566 +v -0.575478 0.006289 0.466177 +v -0.602050 -0.118711 0.486566 +v -0.674647 -0.210217 0.542272 +v -0.773816 -0.243711 0.618367 +v -0.872986 -0.210217 0.694462 +v -0.945583 -0.118711 0.750168 +v -0.864347 0.006289 0.893489 +v -0.840663 0.131289 0.869805 +v -0.775958 0.222796 0.805101 +v -0.687570 0.256289 0.716712 +v -0.599182 0.222796 0.628324 +v -0.534477 0.131289 0.563619 +v -0.510793 0.006289 0.539936 +v -0.534477 -0.118711 0.563619 +v -0.599182 -0.210217 0.628324 +v -0.687570 -0.243711 0.716712 +v -0.775958 -0.210217 0.805101 +v -0.840663 -0.118711 0.869805 +v -0.741416 0.006289 1.001297 +v -0.721026 0.131289 0.974725 +v -0.665320 0.222796 0.902128 +v -0.589225 0.256289 0.802959 +v -0.513130 0.222796 0.703790 +v -0.457424 0.131289 0.631193 +v -0.437034 0.006289 0.604621 +v -0.457424 -0.118711 0.631193 +v -0.513130 -0.210217 0.703790 +v -0.589225 -0.243711 0.802959 +v -0.665320 -0.210217 0.902128 +v -0.721026 -0.118711 0.974725 +v -0.605463 0.006289 1.092138 +v -0.588716 0.131289 1.063131 +v -0.542963 0.222796 0.983884 +v -0.480463 0.256289 0.875631 +v -0.417963 0.222796 0.767378 +v -0.372210 0.131289 0.688131 +v -0.355463 0.006289 0.659125 +v -0.372210 -0.118711 0.688131 +v -0.417963 -0.210217 0.767378 +v -0.480463 -0.243711 0.875631 +v -0.542963 -0.210217 0.983884 +v -0.588716 -0.118711 1.063131 +v -0.458818 0.006289 1.164455 +v -0.446000 0.131289 1.133511 +v -0.410982 0.222796 1.048970 +v -0.363147 0.256289 0.933485 +v -0.315311 0.222796 0.818000 +v -0.280293 0.131289 0.733459 +v -0.267476 0.006289 0.702515 +v -0.280293 -0.118711 0.733459 +v -0.315311 -0.210217 0.818000 +v -0.363147 -0.243711 0.933485 +v -0.410982 -0.210217 1.048970 +v -0.446000 -0.118711 1.133511 +v -0.303987 0.006289 1.217013 +v -0.295318 0.131289 1.184660 +v -0.271635 0.222796 1.096272 +v -0.239282 0.256289 0.975531 +v -0.206930 0.222796 0.854791 +v -0.183246 0.131289 0.766402 +v -0.174578 0.006289 0.734050 +v -0.183246 -0.118711 0.766402 +v -0.206930 -0.210217 0.854791 +v -0.239282 -0.243711 0.975531 +v -0.271635 -0.210217 1.096272 +v -0.295318 -0.118711 1.184660 +v -0.143622 0.006289 1.248912 +v -0.139250 0.131289 1.215704 +v -0.127306 0.222796 1.124981 +v -0.110990 0.256289 1.001050 +v -0.094674 0.222796 0.877120 +v -0.082730 0.131289 0.786396 +v -0.078358 0.006289 0.753189 +v -0.082730 -0.118711 0.786396 +v -0.094674 -0.210217 0.877120 +v -0.110990 -0.243711 1.001050 +v -0.127306 -0.210217 1.124981 +v -0.139250 -0.118711 1.215704 +v 0.019537 0.006289 1.259606 +v 0.019537 0.131289 1.226112 +v 0.019537 0.222796 1.134606 +v 0.019537 0.256289 1.009606 +v 0.019537 0.222796 0.884606 +v 0.019537 0.131289 0.793099 +v 0.019537 0.006289 0.759606 +v 0.019537 -0.118711 0.793099 +v 0.019537 -0.210217 0.884606 +v 0.019537 -0.243711 1.009606 +v 0.019537 -0.210217 1.134606 +v 0.019537 -0.118711 1.226112 +v 0.182694 0.006289 1.248912 +v 0.178323 0.131289 1.215705 +v 0.166379 0.222796 1.124981 +v 0.150063 0.256289 1.001051 +v 0.133747 0.222796 0.877120 +v 0.121803 0.131289 0.786396 +v 0.117431 0.006289 0.753189 +v 0.121803 -0.118711 0.786396 +v 0.133747 -0.210217 0.877120 +v 0.150063 -0.243711 1.001051 +v 0.166379 -0.210217 1.124981 +v 0.178323 -0.118711 1.215705 +v 0.343060 0.006289 1.217013 +v 0.334391 0.131289 1.184661 +v 0.310708 0.222796 1.096272 +v 0.278356 0.256289 0.975532 +v 0.246003 0.222796 0.854791 +v 0.222320 0.131289 0.766403 +v 0.213651 0.006289 0.734050 +v 0.222320 -0.118711 0.766403 +v 0.246003 -0.210217 0.854791 +v 0.278356 -0.243711 0.975532 +v 0.310708 -0.210217 1.096272 +v 0.334391 -0.118711 1.184661 +v 0.497891 0.006289 1.164455 +v 0.485074 0.131289 1.133511 +v 0.450056 0.222796 1.048970 +v 0.402221 0.256289 0.933485 +v 0.354385 0.222796 0.818000 +v 0.319367 0.131289 0.733459 +v 0.306550 0.006289 0.702515 +v 0.319367 -0.118711 0.733459 +v 0.354385 -0.210217 0.818000 +v 0.402221 -0.243711 0.933485 +v 0.450056 -0.210217 1.048970 +v 0.485074 -0.118711 1.133511 +v 0.644537 0.006289 1.092137 +v 0.627790 0.131289 1.063131 +v 0.582037 0.222796 0.983884 +v 0.519537 0.256289 0.875631 +v 0.457037 0.222796 0.767378 +v 0.411284 0.131289 0.688131 +v 0.394537 0.006289 0.659125 +v 0.411284 -0.118711 0.688131 +v 0.457037 -0.210217 0.767378 +v 0.519537 -0.243711 0.875631 +v 0.582037 -0.210217 0.983884 +v 0.627790 -0.118711 1.063131 +v 0.780488 0.006289 1.001298 +v 0.760099 0.131289 0.974725 +v 0.704393 0.222796 0.902128 +v 0.628298 0.256289 0.802959 +v 0.552203 0.222796 0.703790 +v 0.496497 0.131289 0.631193 +v 0.476108 0.006289 0.604621 +v 0.496497 -0.118711 0.631193 +v 0.552203 -0.210217 0.703790 +v 0.628298 -0.243711 0.802959 +v 0.704393 -0.210217 0.902128 +v 0.760099 -0.118711 0.974725 +v 0.903420 0.006289 0.893490 +v 0.879736 0.131289 0.869806 +v 0.815032 0.222796 0.805101 +v 0.726643 0.256289 0.716713 +v 0.638255 0.222796 0.628325 +v 0.573550 0.131289 0.563620 +v 0.549867 0.006289 0.539936 +v 0.573550 -0.118711 0.563620 +v 0.638255 -0.210217 0.628325 +v 0.726643 -0.243711 0.716713 +v 0.815032 -0.210217 0.805101 +v 0.879736 -0.118711 0.869806 +v 1.011229 0.006289 0.770557 +v 0.984656 0.131289 0.750168 +v 0.912059 0.222796 0.694462 +v 0.812890 0.256289 0.618367 +v 0.713721 0.222796 0.542272 +v 0.641124 0.131289 0.486566 +v 0.614552 0.006289 0.466177 +v 0.641124 -0.118711 0.486566 +v 0.713721 -0.210217 0.542272 +v 0.812890 -0.243711 0.618367 +v 0.912059 -0.210217 0.694462 +v 0.984656 -0.118711 0.750168 +v 1.102069 0.006289 0.634606 +v 1.073062 0.131289 0.617859 +v 0.993815 0.222796 0.572106 +v 0.885562 0.256289 0.509606 +v 0.777309 0.222796 0.447106 +v 0.698062 0.131289 0.401353 +v 0.669056 0.006289 0.384606 +v 0.698062 -0.118711 0.401353 +v 0.777309 -0.210217 0.447106 +v 0.885562 -0.243711 0.509606 +v 0.993815 -0.210217 0.572106 +v 1.073062 -0.118711 0.617859 +v 1.174386 0.006289 0.487960 +v 1.143442 0.131289 0.475143 +v 1.058901 0.222796 0.440125 +v 0.943416 0.256289 0.392290 +v 0.827931 0.222796 0.344454 +v 0.743391 0.131289 0.309436 +v 0.712446 0.006289 0.296619 +v 0.743391 -0.118711 0.309436 +v 0.827931 -0.210217 0.344454 +v 0.943416 -0.243711 0.392290 +v 1.058901 -0.210217 0.440125 +v 1.143442 -0.118711 0.475143 +v 1.226944 0.006289 0.333129 +v 1.194592 0.131289 0.324460 +v 1.106204 0.222796 0.300777 +v 0.985463 0.256289 0.268424 +v 0.864722 0.222796 0.236072 +v 0.776334 0.131289 0.212389 +v 0.743981 0.006289 0.203720 +v 0.776334 -0.118711 0.212389 +v 0.864722 -0.210217 0.236072 +v 0.985463 -0.243711 0.268424 +v 1.106204 -0.210217 0.300777 +v 1.194592 -0.118711 0.324460 +v 1.258843 0.006289 0.172763 +v 1.225636 0.131289 0.168392 +v 1.134912 0.222796 0.156448 +v 1.010982 0.256289 0.140132 +v 0.887051 0.222796 0.123816 +v 0.796328 0.131289 0.111872 +v 0.763121 0.006289 0.107500 +v 0.796328 -0.118711 0.111872 +v 0.887051 -0.210217 0.123816 +v 1.010982 -0.243711 0.140132 +v 1.134912 -0.210217 0.156448 +v 1.225636 -0.118711 0.168392 +vn 0.9640 0.2583 -0.0632 +vn 0.7063 0.7063 -0.0463 +vn 0.2588 0.9658 -0.0170 +vn -0.2588 0.9658 0.0170 +vn -0.7063 0.7063 0.0463 +vn -0.9640 0.2583 0.0632 +vn -0.9640 -0.2583 0.0632 +vn -0.7063 -0.7063 0.0463 +vn -0.2588 -0.9658 0.0170 +vn 0.2588 -0.9658 -0.0170 +vn 0.7063 -0.7063 -0.0463 +vn 0.9640 -0.2583 -0.0632 +vn 0.9475 0.2583 -0.1885 +vn 0.6943 0.7063 -0.1381 +vn 0.2544 0.9658 -0.0506 +vn -0.2544 0.9658 0.0506 +vn -0.6943 0.7063 0.1381 +vn -0.9475 0.2583 0.1885 +vn -0.9475 -0.2583 0.1885 +vn -0.6943 -0.7063 0.1381 +vn -0.2544 -0.9658 0.0506 +vn 0.2544 -0.9658 -0.0506 +vn 0.6943 -0.7063 -0.1381 +vn 0.9475 -0.2583 -0.1885 +vn 0.9148 0.2583 -0.3105 +vn 0.6703 0.7063 -0.2275 +vn 0.2456 0.9658 -0.0834 +vn -0.2456 0.9658 0.0834 +vn -0.6703 0.7063 0.2275 +vn -0.9148 0.2583 0.3105 +vn -0.9148 -0.2583 0.3105 +vn -0.6703 -0.7063 0.2275 +vn -0.2456 -0.9658 0.0834 +vn 0.2456 -0.9658 -0.0834 +vn 0.6703 -0.7063 -0.2275 +vn 0.9148 -0.2583 -0.3105 +vn 0.8664 0.2583 -0.4273 +vn 0.6349 0.7063 -0.3131 +vn 0.2326 0.9658 -0.1147 +vn -0.2326 0.9658 0.1147 +vn -0.6349 0.7063 0.3131 +vn -0.8664 0.2583 0.4273 +vn -0.8664 -0.2583 0.4273 +vn -0.6349 -0.7063 0.3131 +vn -0.2326 -0.9658 0.1147 +vn 0.2326 -0.9658 -0.1147 +vn 0.6349 -0.7063 -0.3131 +vn 0.8664 -0.2583 -0.4273 +vn 0.8033 0.2583 -0.5367 +vn 0.5886 0.7063 -0.3933 +vn 0.2156 0.9658 -0.1441 +vn -0.2156 0.9658 0.1441 +vn -0.5886 0.7063 0.3933 +vn -0.8033 0.2583 0.5367 +vn -0.8033 -0.2583 0.5367 +vn -0.5886 -0.7063 0.3933 +vn -0.2156 -0.9658 0.1441 +vn 0.2156 -0.9658 -0.1441 +vn 0.5886 -0.7063 -0.3933 +vn 0.8033 -0.2583 -0.5367 +vn 0.7263 0.2583 -0.6370 +vn 0.5322 0.7063 -0.4667 +vn 0.1950 0.9658 -0.1710 +vn -0.1950 0.9658 0.1710 +vn -0.5322 0.7063 0.4667 +vn -0.7263 0.2583 0.6370 +vn -0.7263 -0.2583 0.6370 +vn -0.5322 -0.7063 0.4667 +vn -0.1950 -0.9658 0.1710 +vn 0.1950 -0.9658 -0.1710 +vn 0.5322 -0.7063 -0.4667 +vn 0.7263 -0.2583 -0.6370 +vn 0.6370 0.2583 -0.7263 +vn 0.4667 0.7063 -0.5322 +vn 0.1710 0.9658 -0.1950 +vn -0.1710 0.9658 0.1950 +vn -0.4667 0.7063 0.5322 +vn -0.6370 0.2583 0.7263 +vn -0.6370 -0.2583 0.7263 +vn -0.4667 -0.7063 0.5322 +vn -0.1710 -0.9658 0.1950 +vn 0.1710 -0.9658 -0.1950 +vn 0.4667 -0.7063 -0.5322 +vn 0.6370 -0.2583 -0.7263 +vn 0.5367 0.2583 -0.8033 +vn 0.3933 0.7063 -0.5886 +vn 0.1441 0.9658 -0.2156 +vn -0.1441 0.9658 0.2156 +vn -0.3933 0.7063 0.5886 +vn -0.5367 0.2583 0.8033 +vn -0.5367 -0.2583 0.8033 +vn -0.3933 -0.7063 0.5886 +vn -0.1441 -0.9658 0.2156 +vn 0.1441 -0.9658 -0.2156 +vn 0.3933 -0.7063 -0.5886 +vn 0.5367 -0.2583 -0.8033 +vn 0.4273 0.2583 -0.8664 +vn 0.3131 0.7063 -0.6349 +vn 0.1147 0.9658 -0.2326 +vn -0.1147 0.9658 0.2326 +vn -0.3131 0.7063 0.6349 +vn -0.4273 0.2583 0.8664 +vn -0.4273 -0.2583 0.8664 +vn -0.3131 -0.7063 0.6349 +vn -0.1147 -0.9658 0.2326 +vn 0.1147 -0.9658 -0.2326 +vn 0.3131 -0.7063 -0.6349 +vn 0.4273 -0.2583 -0.8664 +vn 0.3105 0.2583 -0.9148 +vn 0.2275 0.7063 -0.6703 +vn 0.0834 0.9658 -0.2456 +vn -0.0834 0.9658 0.2456 +vn -0.2275 0.7063 0.6703 +vn -0.3105 0.2583 0.9148 +vn -0.3105 -0.2583 0.9148 +vn -0.2275 -0.7063 0.6703 +vn -0.0834 -0.9658 0.2456 +vn 0.0834 -0.9658 -0.2456 +vn 0.2275 -0.7063 -0.6703 +vn 0.3105 -0.2583 -0.9148 +vn 0.1885 0.2583 -0.9475 +vn 0.1381 0.7063 -0.6943 +vn 0.0506 0.9658 -0.2544 +vn -0.0506 0.9658 0.2544 +vn -0.1381 0.7063 0.6943 +vn -0.1885 0.2583 0.9475 +vn -0.1885 -0.2583 0.9475 +vn -0.1381 -0.7063 0.6943 +vn -0.0506 -0.9658 0.2544 +vn 0.0506 -0.9658 -0.2544 +vn 0.1381 -0.7063 -0.6943 +vn 0.1885 -0.2583 -0.9475 +vn 0.0632 0.2583 -0.9640 +vn 0.0463 0.7063 -0.7063 +vn 0.0170 0.9658 -0.2588 +vn -0.0170 0.9658 0.2588 +vn -0.0463 0.7063 0.7063 +vn -0.0632 0.2583 0.9640 +vn -0.0632 -0.2583 0.9640 +vn -0.0463 -0.7063 0.7063 +vn -0.0170 -0.9658 0.2588 +vn 0.0170 -0.9658 -0.2588 +vn 0.0463 -0.7063 -0.7063 +vn 0.0632 -0.2583 -0.9640 +vn -0.0632 0.2583 -0.9640 +vn -0.0463 0.7063 -0.7063 +vn -0.0170 0.9658 -0.2588 +vn 0.0170 0.9658 0.2588 +vn 0.0463 0.7063 0.7063 +vn 0.0632 0.2583 0.9640 +vn 0.0632 -0.2583 0.9640 +vn 0.0463 -0.7063 0.7063 +vn 0.0170 -0.9658 0.2588 +vn -0.0170 -0.9658 -0.2588 +vn -0.0463 -0.7063 -0.7063 +vn -0.0632 -0.2583 -0.9640 +vn -0.1885 0.2583 -0.9475 +vn -0.1381 0.7063 -0.6943 +vn -0.0506 0.9658 -0.2544 +vn 0.0506 0.9658 0.2544 +vn 0.1381 0.7063 0.6943 +vn 0.1885 0.2583 0.9475 +vn 0.1885 -0.2583 0.9475 +vn 0.1381 -0.7063 0.6943 +vn 0.0506 -0.9658 0.2544 +vn -0.0506 -0.9658 -0.2544 +vn -0.1381 -0.7063 -0.6943 +vn -0.1885 -0.2583 -0.9475 +vn -0.3105 0.2583 -0.9148 +vn -0.2275 0.7063 -0.6703 +vn -0.0834 0.9658 -0.2456 +vn 0.0834 0.9658 0.2456 +vn 0.2275 0.7063 0.6703 +vn 0.3105 0.2583 0.9148 +vn 0.3105 -0.2583 0.9148 +vn 0.2275 -0.7063 0.6703 +vn 0.0834 -0.9658 0.2456 +vn -0.0834 -0.9658 -0.2456 +vn -0.2275 -0.7063 -0.6703 +vn -0.3105 -0.2583 -0.9148 +vn -0.4273 0.2583 -0.8664 +vn -0.3131 0.7063 -0.6349 +vn -0.1147 0.9658 -0.2326 +vn 0.1147 0.9658 0.2326 +vn 0.3131 0.7063 0.6349 +vn 0.4273 0.2583 0.8664 +vn 0.4273 -0.2583 0.8664 +vn 0.3131 -0.7063 0.6349 +vn 0.1147 -0.9658 0.2326 +vn -0.1147 -0.9658 -0.2326 +vn -0.3131 -0.7063 -0.6349 +vn -0.4273 -0.2583 -0.8664 +vn -0.5367 0.2583 -0.8033 +vn -0.3933 0.7063 -0.5886 +vn -0.1441 0.9658 -0.2156 +vn 0.1441 0.9658 0.2156 +vn 0.3933 0.7063 0.5886 +vn 0.5367 0.2583 0.8033 +vn 0.5367 -0.2583 0.8033 +vn 0.3933 -0.7063 0.5886 +vn 0.1441 -0.9658 0.2156 +vn -0.1441 -0.9658 -0.2156 +vn -0.3933 -0.7063 -0.5886 +vn -0.5367 -0.2583 -0.8033 +vn -0.6370 0.2583 -0.7263 +vn -0.4667 0.7063 -0.5322 +vn -0.1710 0.9658 -0.1950 +vn 0.1710 0.9658 0.1950 +vn 0.4667 0.7063 0.5322 +vn 0.6370 0.2583 0.7263 +vn 0.6370 -0.2583 0.7263 +vn 0.4667 -0.7063 0.5322 +vn 0.1710 -0.9658 0.1950 +vn -0.1710 -0.9658 -0.1950 +vn -0.4667 -0.7063 -0.5322 +vn -0.6370 -0.2583 -0.7263 +vn -0.7263 0.2583 -0.6370 +vn -0.5322 0.7063 -0.4667 +vn -0.1950 0.9658 -0.1710 +vn 0.1950 0.9658 0.1710 +vn 0.5322 0.7063 0.4667 +vn 0.7263 0.2583 0.6370 +vn 0.7263 -0.2583 0.6370 +vn 0.5322 -0.7063 0.4667 +vn 0.1950 -0.9658 0.1710 +vn -0.1950 -0.9658 -0.1710 +vn -0.5322 -0.7063 -0.4667 +vn -0.7263 -0.2583 -0.6370 +vn -0.8033 0.2583 -0.5367 +vn -0.5886 0.7063 -0.3933 +vn -0.2156 0.9658 -0.1441 +vn 0.2156 0.9658 0.1441 +vn 0.5886 0.7063 0.3933 +vn 0.8033 0.2583 0.5367 +vn 0.8033 -0.2583 0.5367 +vn 0.5886 -0.7063 0.3933 +vn 0.2156 -0.9658 0.1441 +vn -0.2156 -0.9658 -0.1441 +vn -0.5886 -0.7063 -0.3933 +vn -0.8033 -0.2583 -0.5367 +vn -0.8664 0.2583 -0.4273 +vn -0.6349 0.7063 -0.3131 +vn -0.2326 0.9658 -0.1147 +vn 0.2326 0.9658 0.1147 +vn 0.6349 0.7063 0.3131 +vn 0.8664 0.2583 0.4273 +vn 0.8664 -0.2583 0.4273 +vn 0.6349 -0.7063 0.3131 +vn 0.2326 -0.9658 0.1147 +vn -0.2326 -0.9658 -0.1147 +vn -0.6349 -0.7063 -0.3131 +vn -0.8664 -0.2583 -0.4273 +vn -0.9148 0.2583 -0.3105 +vn -0.6703 0.7063 -0.2275 +vn -0.2456 0.9658 -0.0834 +vn 0.2456 0.9658 0.0834 +vn 0.6703 0.7063 0.2275 +vn 0.9148 0.2583 0.3105 +vn 0.9148 -0.2583 0.3105 +vn 0.6703 -0.7063 0.2275 +vn 0.2456 -0.9658 0.0834 +vn -0.2456 -0.9658 -0.0834 +vn -0.6703 -0.7063 -0.2275 +vn -0.9148 -0.2583 -0.3105 +vn -0.9475 0.2583 -0.1885 +vn -0.6943 0.7063 -0.1381 +vn -0.2544 0.9658 -0.0506 +vn 0.2544 0.9658 0.0506 +vn 0.6943 0.7063 0.1381 +vn 0.9475 0.2583 0.1885 +vn 0.9475 -0.2583 0.1885 +vn 0.6943 -0.7063 0.1381 +vn 0.2544 -0.9658 0.0506 +vn -0.2544 -0.9658 -0.0506 +vn -0.6943 -0.7063 -0.1381 +vn -0.9475 -0.2583 -0.1885 +vn -0.9640 0.2583 -0.0632 +vn -0.7063 0.7063 -0.0463 +vn -0.2588 0.9658 -0.0170 +vn 0.2588 0.9658 0.0170 +vn 0.7063 0.7063 0.0463 +vn 0.9640 0.2583 0.0632 +vn 0.9640 -0.2583 0.0632 +vn 0.7063 -0.7063 0.0463 +vn 0.2588 -0.9658 0.0170 +vn -0.2588 -0.9658 -0.0170 +vn -0.7063 -0.7063 -0.0463 +vn -0.9640 -0.2583 -0.0632 +usemtl None +s off +f 1//1 13//1 14//1 2//1 +f 2//2 14//2 15//2 3//2 +f 3//3 15//3 16//3 4//3 +f 4//4 16//4 17//4 5//4 +f 5//5 17//5 18//5 6//5 +f 6//6 18//6 19//6 7//6 +f 7//7 19//7 20//7 8//7 +f 8//8 20//8 21//8 9//8 +f 9//9 21//9 22//9 10//9 +f 10//10 22//10 23//10 11//10 +f 11//11 23//11 24//11 12//11 +f 1//12 12//12 24//12 13//12 +f 13//13 25//13 26//13 14//13 +f 14//14 26//14 27//14 15//14 +f 15//15 27//15 28//15 16//15 +f 16//16 28//16 29//16 17//16 +f 17//17 29//17 30//17 18//17 +f 18//18 30//18 31//18 19//18 +f 19//19 31//19 32//19 20//19 +f 20//20 32//20 33//20 21//20 +f 21//21 33//21 34//21 22//21 +f 22//22 34//22 35//22 23//22 +f 23//23 35//23 36//23 24//23 +f 24//24 36//24 25//24 13//24 +f 25//25 37//25 38//25 26//25 +f 26//26 38//26 39//26 27//26 +f 27//27 39//27 40//27 28//27 +f 28//28 40//28 41//28 29//28 +f 29//29 41//29 42//29 30//29 +f 30//30 42//30 43//30 31//30 +f 31//31 43//31 44//31 32//31 +f 32//32 44//32 45//32 33//32 +f 33//33 45//33 46//33 34//33 +f 34//34 46//34 47//34 35//34 +f 35//35 47//35 48//35 36//35 +f 36//36 48//36 37//36 25//36 +f 37//37 49//37 50//37 38//37 +f 38//38 50//38 51//38 39//38 +f 39//39 51//39 52//39 40//39 +f 40//40 52//40 53//40 41//40 +f 41//41 53//41 54//41 42//41 +f 42//42 54//42 55//42 43//42 +f 43//43 55//43 56//43 44//43 +f 44//44 56//44 57//44 45//44 +f 45//45 57//45 58//45 46//45 +f 46//46 58//46 59//46 47//46 +f 47//47 59//47 60//47 48//47 +f 48//48 60//48 49//48 37//48 +f 49//49 61//49 62//49 50//49 +f 50//50 62//50 63//50 51//50 +f 51//51 63//51 64//51 52//51 +f 52//52 64//52 65//52 53//52 +f 53//53 65//53 66//53 54//53 +f 54//54 66//54 67//54 55//54 +f 55//55 67//55 68//55 56//55 +f 56//56 68//56 69//56 57//56 +f 57//57 69//57 70//57 58//57 +f 58//58 70//58 71//58 59//58 +f 59//59 71//59 72//59 60//59 +f 60//60 72//60 61//60 49//60 +f 61//61 73//61 74//61 62//61 +f 62//62 74//62 75//62 63//62 +f 63//63 75//63 76//63 64//63 +f 64//64 76//64 77//64 65//64 +f 65//65 77//65 78//65 66//65 +f 66//66 78//66 79//66 67//66 +f 67//67 79//67 80//67 68//67 +f 68//68 80//68 81//68 69//68 +f 69//69 81//69 82//69 70//69 +f 70//70 82//70 83//70 71//70 +f 71//71 83//71 84//71 72//71 +f 72//72 84//72 73//72 61//72 +f 73//73 85//73 86//73 74//73 +f 74//74 86//74 87//74 75//74 +f 75//75 87//75 88//75 76//75 +f 76//76 88//76 89//76 77//76 +f 77//77 89//77 90//77 78//77 +f 78//78 90//78 91//78 79//78 +f 79//79 91//79 92//79 80//79 +f 80//80 92//80 93//80 81//80 +f 81//81 93//81 94//81 82//81 +f 82//82 94//82 95//82 83//82 +f 83//83 95//83 96//83 84//83 +f 84//84 96//84 85//84 73//84 +f 85//85 97//85 98//85 86//85 +f 86//86 98//86 99//86 87//86 +f 87//87 99//87 100//87 88//87 +f 88//88 100//88 101//88 89//88 +f 89//89 101//89 102//89 90//89 +f 90//90 102//90 103//90 91//90 +f 91//91 103//91 104//91 92//91 +f 92//92 104//92 105//92 93//92 +f 93//93 105//93 106//93 94//93 +f 94//94 106//94 107//94 95//94 +f 95//95 107//95 108//95 96//95 +f 96//96 108//96 97//96 85//96 +f 97//97 109//97 110//97 98//97 +f 98//98 110//98 111//98 99//98 +f 99//99 111//99 112//99 100//99 +f 100//100 112//100 113//100 101//100 +f 101//101 113//101 114//101 102//101 +f 102//102 114//102 115//102 103//102 +f 103//103 115//103 116//103 104//103 +f 104//104 116//104 117//104 105//104 +f 105//105 117//105 118//105 106//105 +f 106//106 118//106 119//106 107//106 +f 107//107 119//107 120//107 108//107 +f 108//108 120//108 109//108 97//108 +f 109//109 121//109 122//109 110//109 +f 110//110 122//110 123//110 111//110 +f 111//111 123//111 124//111 112//111 +f 112//112 124//112 125//112 113//112 +f 113//113 125//113 126//113 114//113 +f 114//114 126//114 127//114 115//114 +f 115//115 127//115 128//115 116//115 +f 116//116 128//116 129//116 117//116 +f 117//117 129//117 130//117 118//117 +f 118//118 130//118 131//118 119//118 +f 119//119 131//119 132//119 120//119 +f 120//120 132//120 121//120 109//120 +f 121//121 133//121 134//121 122//121 +f 122//122 134//122 135//122 123//122 +f 123//123 135//123 136//123 124//123 +f 124//124 136//124 137//124 125//124 +f 125//125 137//125 138//125 126//125 +f 126//126 138//126 139//126 127//126 +f 127//127 139//127 140//127 128//127 +f 128//128 140//128 141//128 129//128 +f 129//129 141//129 142//129 130//129 +f 130//130 142//130 143//130 131//130 +f 131//131 143//131 144//131 132//131 +f 132//132 144//132 133//132 121//132 +f 133//133 145//133 146//133 134//133 +f 134//134 146//134 147//134 135//134 +f 135//135 147//135 148//135 136//135 +f 136//136 148//136 149//136 137//136 +f 137//137 149//137 150//137 138//137 +f 138//138 150//138 151//138 139//138 +f 139//139 151//139 152//139 140//139 +f 140//140 152//140 153//140 141//140 +f 141//141 153//141 154//141 142//141 +f 142//142 154//142 155//142 143//142 +f 143//143 155//143 156//143 144//143 +f 144//144 156//144 145//144 133//144 +f 145//145 157//145 158//145 146//145 +f 146//146 158//146 159//146 147//146 +f 147//147 159//147 160//147 148//147 +f 148//148 160//148 161//148 149//148 +f 149//149 161//149 162//149 150//149 +f 150//150 162//150 163//150 151//150 +f 151//151 163//151 164//151 152//151 +f 152//152 164//152 165//152 153//152 +f 153//153 165//153 166//153 154//153 +f 154//154 166//154 167//154 155//154 +f 155//155 167//155 168//155 156//155 +f 156//156 168//156 157//156 145//156 +f 157//157 169//157 170//157 158//157 +f 158//158 170//158 171//158 159//158 +f 159//159 171//159 172//159 160//159 +f 160//160 172//160 173//160 161//160 +f 161//161 173//161 174//161 162//161 +f 162//162 174//162 175//162 163//162 +f 163//163 175//163 176//163 164//163 +f 164//164 176//164 177//164 165//164 +f 165//165 177//165 178//165 166//165 +f 166//166 178//166 179//166 167//166 +f 167//167 179//167 180//167 168//167 +f 168//168 180//168 169//168 157//168 +f 169//169 181//169 182//169 170//169 +f 170//170 182//170 183//170 171//170 +f 171//171 183//171 184//171 172//171 +f 172//172 184//172 185//172 173//172 +f 173//173 185//173 186//173 174//173 +f 174//174 186//174 187//174 175//174 +f 175//175 187//175 188//175 176//175 +f 176//176 188//176 189//176 177//176 +f 177//177 189//177 190//177 178//177 +f 178//178 190//178 191//178 179//178 +f 179//179 191//179 192//179 180//179 +f 180//180 192//180 181//180 169//180 +f 181//181 193//181 194//181 182//181 +f 182//182 194//182 195//182 183//182 +f 183//183 195//183 196//183 184//183 +f 184//184 196//184 197//184 185//184 +f 185//185 197//185 198//185 186//185 +f 186//186 198//186 199//186 187//186 +f 187//187 199//187 200//187 188//187 +f 188//188 200//188 201//188 189//188 +f 189//189 201//189 202//189 190//189 +f 190//190 202//190 203//190 191//190 +f 191//191 203//191 204//191 192//191 +f 192//192 204//192 193//192 181//192 +f 193//193 205//193 206//193 194//193 +f 194//194 206//194 207//194 195//194 +f 195//195 207//195 208//195 196//195 +f 196//196 208//196 209//196 197//196 +f 197//197 209//197 210//197 198//197 +f 198//198 210//198 211//198 199//198 +f 199//199 211//199 212//199 200//199 +f 200//200 212//200 213//200 201//200 +f 201//201 213//201 214//201 202//201 +f 202//202 214//202 215//202 203//202 +f 203//203 215//203 216//203 204//203 +f 204//204 216//204 205//204 193//204 +f 205//205 217//205 218//205 206//205 +f 206//206 218//206 219//206 207//206 +f 207//207 219//207 220//207 208//207 +f 208//208 220//208 221//208 209//208 +f 209//209 221//209 222//209 210//209 +f 210//210 222//210 223//210 211//210 +f 211//211 223//211 224//211 212//211 +f 212//212 224//212 225//212 213//212 +f 213//213 225//213 226//213 214//213 +f 214//214 226//214 227//214 215//214 +f 215//215 227//215 228//215 216//215 +f 216//216 228//216 217//216 205//216 +f 217//217 229//217 230//217 218//217 +f 218//218 230//218 231//218 219//218 +f 219//219 231//219 232//219 220//219 +f 220//220 232//220 233//220 221//220 +f 221//221 233//221 234//221 222//221 +f 222//222 234//222 235//222 223//222 +f 223//223 235//223 236//223 224//223 +f 224//224 236//224 237//224 225//224 +f 225//225 237//225 238//225 226//225 +f 226//226 238//226 239//226 227//226 +f 227//227 239//227 240//227 228//227 +f 228//228 240//228 229//228 217//228 +f 229//229 241//229 242//229 230//229 +f 230//230 242//230 243//230 231//230 +f 231//231 243//231 244//231 232//231 +f 232//232 244//232 245//232 233//232 +f 233//233 245//233 246//233 234//233 +f 234//234 246//234 247//234 235//234 +f 235//235 247//235 248//235 236//235 +f 236//236 248//236 249//236 237//236 +f 237//237 249//237 250//237 238//237 +f 238//238 250//238 251//238 239//238 +f 239//239 251//239 252//239 240//239 +f 240//240 252//240 241//240 229//240 +f 241//241 253//241 254//241 242//241 +f 242//242 254//242 255//242 243//242 +f 243//243 255//243 256//243 244//243 +f 244//244 256//244 257//244 245//244 +f 245//245 257//245 258//245 246//245 +f 246//246 258//246 259//246 247//246 +f 247//247 259//247 260//247 248//247 +f 248//248 260//248 261//248 249//248 +f 249//249 261//249 262//249 250//249 +f 250//250 262//250 263//250 251//250 +f 251//251 263//251 264//251 252//251 +f 252//252 264//252 253//252 241//252 +f 253//253 265//253 266//253 254//253 +f 254//254 266//254 267//254 255//254 +f 255//255 267//255 268//255 256//255 +f 256//256 268//256 269//256 257//256 +f 257//257 269//257 270//257 258//257 +f 258//258 270//258 271//258 259//258 +f 259//259 271//259 272//259 260//259 +f 260//260 272//260 273//260 261//260 +f 261//261 273//261 274//261 262//261 +f 262//262 274//262 275//262 263//262 +f 263//263 275//263 276//263 264//263 +f 264//264 276//264 265//264 253//264 +f 265//265 277//265 278//265 266//265 +f 266//266 278//266 279//266 267//266 +f 267//267 279//267 280//267 268//267 +f 268//268 280//268 281//268 269//268 +f 269//269 281//269 282//269 270//269 +f 270//270 282//270 283//270 271//270 +f 271//271 283//271 284//271 272//271 +f 272//272 284//272 285//272 273//272 +f 273//273 285//273 286//273 274//273 +f 274//274 286//274 287//274 275//274 +f 275//275 287//275 288//275 276//275 +f 276//276 288//276 277//276 265//276 +f 277//277 289//277 290//277 278//277 +f 278//278 290//278 291//278 279//278 +f 279//279 291//279 292//279 280//279 +f 280//280 292//280 293//280 281//280 +f 281//281 293//281 294//281 282//281 +f 282//282 294//282 295//282 283//282 +f 283//283 295//283 296//283 284//283 +f 284//284 296//284 297//284 285//284 +f 285//285 297//285 298//285 286//285 +f 286//286 298//286 299//286 287//286 +f 287//287 299//287 300//287 288//287 +f 288//288 300//288 289//288 277//288 +f 289//6 301//6 302//6 290//6 +f 290//5 302//5 303//5 291//5 +f 291//4 303//4 304//4 292//4 +f 292//3 304//3 305//3 293//3 +f 293//2 305//2 306//2 294//2 +f 294//1 306//1 307//1 295//1 +f 295//12 307//12 308//12 296//12 +f 296//11 308//11 309//11 297//11 +f 297//10 309//10 310//10 298//10 +f 298//9 310//9 311//9 299//9 +f 299//8 311//8 312//8 300//8 +f 300//7 312//7 301//7 289//7 +f 301//18 313//18 314//18 302//18 +f 302//17 314//17 315//17 303//17 +f 303//16 315//16 316//16 304//16 +f 304//15 316//15 317//15 305//15 +f 305//14 317//14 318//14 306//14 +f 306//13 318//13 319//13 307//13 +f 307//24 319//24 320//24 308//24 +f 308//23 320//23 321//23 309//23 +f 309//22 321//22 322//22 310//22 +f 310//21 322//21 323//21 311//21 +f 311//20 323//20 324//20 312//20 +f 312//19 324//19 313//19 301//19 +f 313//30 325//30 326//30 314//30 +f 314//29 326//29 327//29 315//29 +f 315//28 327//28 328//28 316//28 +f 316//27 328//27 329//27 317//27 +f 317//26 329//26 330//26 318//26 +f 318//25 330//25 331//25 319//25 +f 319//36 331//36 332//36 320//36 +f 320//35 332//35 333//35 321//35 +f 321//34 333//34 334//34 322//34 +f 322//33 334//33 335//33 323//33 +f 323//32 335//32 336//32 324//32 +f 324//31 336//31 325//31 313//31 +f 325//42 337//42 338//42 326//42 +f 326//41 338//41 339//41 327//41 +f 327//40 339//40 340//40 328//40 +f 328//39 340//39 341//39 329//39 +f 329//38 341//38 342//38 330//38 +f 330//37 342//37 343//37 331//37 +f 331//48 343//48 344//48 332//48 +f 332//47 344//47 345//47 333//47 +f 333//46 345//46 346//46 334//46 +f 334//45 346//45 347//45 335//45 +f 335//44 347//44 348//44 336//44 +f 336//43 348//43 337//43 325//43 +f 337//54 349//54 350//54 338//54 +f 338//53 350//53 351//53 339//53 +f 339//52 351//52 352//52 340//52 +f 340//51 352//51 353//51 341//51 +f 341//50 353//50 354//50 342//50 +f 342//49 354//49 355//49 343//49 +f 343//60 355//60 356//60 344//60 +f 344//59 356//59 357//59 345//59 +f 345//58 357//58 358//58 346//58 +f 346//57 358//57 359//57 347//57 +f 347//56 359//56 360//56 348//56 +f 348//55 360//55 349//55 337//55 +f 349//66 361//66 362//66 350//66 +f 350//65 362//65 363//65 351//65 +f 351//64 363//64 364//64 352//64 +f 352//63 364//63 365//63 353//63 +f 353//62 365//62 366//62 354//62 +f 354//61 366//61 367//61 355//61 +f 355//72 367//72 368//72 356//72 +f 356//71 368//71 369//71 357//71 +f 357//70 369//70 370//70 358//70 +f 358//69 370//69 371//69 359//69 +f 359//68 371//68 372//68 360//68 +f 360//67 372//67 361//67 349//67 +f 361//78 373//78 374//78 362//78 +f 362//77 374//77 375//77 363//77 +f 363//76 375//76 376//76 364//76 +f 364//75 376//75 377//75 365//75 +f 365//74 377//74 378//74 366//74 +f 366//73 378//73 379//73 367//73 +f 367//84 379//84 380//84 368//84 +f 368//83 380//83 381//83 369//83 +f 369//82 381//82 382//82 370//82 +f 370//81 382//81 383//81 371//81 +f 371//80 383//80 384//80 372//80 +f 372//79 384//79 373//79 361//79 +f 373//90 385//90 386//90 374//90 +f 374//89 386//89 387//89 375//89 +f 375//88 387//88 388//88 376//88 +f 376//87 388//87 389//87 377//87 +f 377//86 389//86 390//86 378//86 +f 378//85 390//85 391//85 379//85 +f 379//96 391//96 392//96 380//96 +f 380//95 392//95 393//95 381//95 +f 381//94 393//94 394//94 382//94 +f 382//93 394//93 395//93 383//93 +f 383//92 395//92 396//92 384//92 +f 384//91 396//91 385//91 373//91 +f 385//102 397//102 398//102 386//102 +f 386//101 398//101 399//101 387//101 +f 387//100 399//100 400//100 388//100 +f 388//99 400//99 401//99 389//99 +f 389//98 401//98 402//98 390//98 +f 390//97 402//97 403//97 391//97 +f 391//108 403//108 404//108 392//108 +f 392//107 404//107 405//107 393//107 +f 393//106 405//106 406//106 394//106 +f 394//105 406//105 407//105 395//105 +f 395//104 407//104 408//104 396//104 +f 396//103 408//103 397//103 385//103 +f 397//114 409//114 410//114 398//114 +f 398//113 410//113 411//113 399//113 +f 399//112 411//112 412//112 400//112 +f 400//111 412//111 413//111 401//111 +f 401//110 413//110 414//110 402//110 +f 402//109 414//109 415//109 403//109 +f 403//120 415//120 416//120 404//120 +f 404//119 416//119 417//119 405//119 +f 405//118 417//118 418//118 406//118 +f 406//117 418//117 419//117 407//117 +f 407//116 419//116 420//116 408//116 +f 408//115 420//115 409//115 397//115 +f 409//126 421//126 422//126 410//126 +f 410//125 422//125 423//125 411//125 +f 411//124 423//124 424//124 412//124 +f 412//123 424//123 425//123 413//123 +f 413//122 425//122 426//122 414//122 +f 414//121 426//121 427//121 415//121 +f 415//132 427//132 428//132 416//132 +f 416//131 428//131 429//131 417//131 +f 417//130 429//130 430//130 418//130 +f 418//129 430//129 431//129 419//129 +f 419//128 431//128 432//128 420//128 +f 420//127 432//127 421//127 409//127 +f 421//138 433//138 434//138 422//138 +f 422//137 434//137 435//137 423//137 +f 423//136 435//136 436//136 424//136 +f 424//135 436//135 437//135 425//135 +f 425//134 437//134 438//134 426//134 +f 426//133 438//133 439//133 427//133 +f 427//144 439//144 440//144 428//144 +f 428//143 440//143 441//143 429//143 +f 429//142 441//142 442//142 430//142 +f 430//141 442//141 443//141 431//141 +f 431//140 443//140 444//140 432//140 +f 432//139 444//139 433//139 421//139 +f 433//150 445//150 446//150 434//150 +f 434//149 446//149 447//149 435//149 +f 435//148 447//148 448//148 436//148 +f 436//147 448//147 449//147 437//147 +f 437//146 449//146 450//146 438//146 +f 438//145 450//145 451//145 439//145 +f 439//156 451//156 452//156 440//156 +f 440//155 452//155 453//155 441//155 +f 441//154 453//154 454//154 442//154 +f 442//153 454//153 455//153 443//153 +f 443//152 455//152 456//152 444//152 +f 444//151 456//151 445//151 433//151 +f 445//162 457//162 458//162 446//162 +f 446//161 458//161 459//161 447//161 +f 447//160 459//160 460//160 448//160 +f 448//159 460//159 461//159 449//159 +f 449//158 461//158 462//158 450//158 +f 450//157 462//157 463//157 451//157 +f 451//168 463//168 464//168 452//168 +f 452//167 464//167 465//167 453//167 +f 453//166 465//166 466//166 454//166 +f 454//165 466//165 467//165 455//165 +f 455//164 467//164 468//164 456//164 +f 456//163 468//163 457//163 445//163 +f 457//174 469//174 470//174 458//174 +f 458//173 470//173 471//173 459//173 +f 459//172 471//172 472//172 460//172 +f 460//171 472//171 473//171 461//171 +f 461//170 473//170 474//170 462//170 +f 462//169 474//169 475//169 463//169 +f 463//180 475//180 476//180 464//180 +f 464//179 476//179 477//179 465//179 +f 465//178 477//178 478//178 466//178 +f 466//177 478//177 479//177 467//177 +f 467//176 479//176 480//176 468//176 +f 468//175 480//175 469//175 457//175 +f 469//186 481//186 482//186 470//186 +f 470//185 482//185 483//185 471//185 +f 471//184 483//184 484//184 472//184 +f 472//183 484//183 485//183 473//183 +f 473//182 485//182 486//182 474//182 +f 474//181 486//181 487//181 475//181 +f 475//192 487//192 488//192 476//192 +f 476//191 488//191 489//191 477//191 +f 477//190 489//190 490//190 478//190 +f 478//189 490//189 491//189 479//189 +f 479//188 491//188 492//188 480//188 +f 480//187 492//187 481//187 469//187 +f 481//198 493//198 494//198 482//198 +f 482//197 494//197 495//197 483//197 +f 483//196 495//196 496//196 484//196 +f 484//195 496//195 497//195 485//195 +f 485//194 497//194 498//194 486//194 +f 486//193 498//193 499//193 487//193 +f 487//204 499//204 500//204 488//204 +f 488//203 500//203 501//203 489//203 +f 489//202 501//202 502//202 490//202 +f 490//201 502//201 503//201 491//201 +f 491//200 503//200 504//200 492//200 +f 492//199 504//199 493//199 481//199 +f 493//210 505//210 506//210 494//210 +f 494//209 506//209 507//209 495//209 +f 495//208 507//208 508//208 496//208 +f 496//207 508//207 509//207 497//207 +f 497//206 509//206 510//206 498//206 +f 498//205 510//205 511//205 499//205 +f 499//216 511//216 512//216 500//216 +f 500//215 512//215 513//215 501//215 +f 501//214 513//214 514//214 502//214 +f 502//213 514//213 515//213 503//213 +f 503//212 515//212 516//212 504//212 +f 504//211 516//211 505//211 493//211 +f 505//222 517//222 518//222 506//222 +f 506//221 518//221 519//221 507//221 +f 507//220 519//220 520//220 508//220 +f 508//219 520//219 521//219 509//219 +f 509//218 521//218 522//218 510//218 +f 510//217 522//217 523//217 511//217 +f 511//228 523//228 524//228 512//228 +f 512//227 524//227 525//227 513//227 +f 513//226 525//226 526//226 514//226 +f 514//225 526//225 527//225 515//225 +f 515//224 527//224 528//224 516//224 +f 516//223 528//223 517//223 505//223 +f 517//234 529//234 530//234 518//234 +f 518//233 530//233 531//233 519//233 +f 519//232 531//232 532//232 520//232 +f 520//231 532//231 533//231 521//231 +f 521//230 533//230 534//230 522//230 +f 522//229 534//229 535//229 523//229 +f 523//240 535//240 536//240 524//240 +f 524//239 536//239 537//239 525//239 +f 525//238 537//238 538//238 526//238 +f 526//237 538//237 539//237 527//237 +f 527//236 539//236 540//236 528//236 +f 528//235 540//235 529//235 517//235 +f 529//246 541//246 542//246 530//246 +f 530//245 542//245 543//245 531//245 +f 531//244 543//244 544//244 532//244 +f 532//243 544//243 545//243 533//243 +f 533//242 545//242 546//242 534//242 +f 534//241 546//241 547//241 535//241 +f 535//252 547//252 548//252 536//252 +f 536//251 548//251 549//251 537//251 +f 537//250 549//250 550//250 538//250 +f 538//249 550//249 551//249 539//249 +f 539//248 551//248 552//248 540//248 +f 540//247 552//247 541//247 529//247 +f 541//258 553//258 554//258 542//258 +f 542//257 554//257 555//257 543//257 +f 543//256 555//256 556//256 544//256 +f 544//255 556//255 557//255 545//255 +f 545//254 557//254 558//254 546//254 +f 546//253 558//253 559//253 547//253 +f 547//264 559//264 560//264 548//264 +f 548//263 560//263 561//263 549//263 +f 549//262 561//262 562//262 550//262 +f 550//261 562//261 563//261 551//261 +f 551//260 563//260 564//260 552//260 +f 552//259 564//259 553//259 541//259 +f 553//270 565//270 566//270 554//270 +f 554//269 566//269 567//269 555//269 +f 555//268 567//268 568//268 556//268 +f 556//267 568//267 569//267 557//267 +f 557//266 569//266 570//266 558//266 +f 558//265 570//265 571//265 559//265 +f 559//276 571//276 572//276 560//276 +f 560//275 572//275 573//275 561//275 +f 561//274 573//274 574//274 562//274 +f 562//273 574//273 575//273 563//273 +f 563//272 575//272 576//272 564//272 +f 564//271 576//271 565//271 553//271 +f 565//282 1//282 2//282 566//282 +f 566//281 2//281 3//281 567//281 +f 567//280 3//280 4//280 568//280 +f 568//279 4//279 5//279 569//279 +f 569//278 5//278 6//278 570//278 +f 570//277 6//277 7//277 571//277 +f 571//288 7//288 8//288 572//288 +f 572//287 8//287 9//287 573//287 +f 573//286 9//286 10//286 574//286 +f 574//285 10//285 11//285 575//285 +f 575//284 11//284 12//284 576//284 +f 576//283 12//283 1//283 565//283 diff --git a/data/torus/torus.urdf b/data/torus/torus.urdf new file mode 100644 index 000000000..57dc51c06 --- /dev/null +++ b/data/torus/torus.urdf @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 0bc4e0a4c31bad9eac7ef275d7ec74bd3cccef7a Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sun, 27 Nov 2016 16:53:15 -0800 Subject: [PATCH 20/39] Render multiple objects with shadow. --- data/torus/plane_only.mtl | 10 + data/torus/plane_only.obj | 7913 ++++++++++++++ data/torus/torus_only.mtl | 12 + data/torus/torus_only.obj | 1474 +++ data/torus/torus_with_plane.mtl | 10 + data/torus/torus_with_plane.obj | 9384 +++++++++++++++++ data/torus/torus_with_plane.urdf | 33 + data/torus/torus_with_separate_plane.urdf | 48 + .../SharedMemory/PhysicsClientExample.cpp | 2 +- .../TinyRendererVisualShapeConverter.cpp | 47 +- examples/TinyRenderer/TinyRenderer.cpp | 114 +- examples/TinyRenderer/TinyRenderer.h | 2 + 12 files changed, 19039 insertions(+), 10 deletions(-) create mode 100644 data/torus/plane_only.mtl create mode 100644 data/torus/plane_only.obj create mode 100644 data/torus/torus_only.mtl create mode 100644 data/torus/torus_only.obj create mode 100644 data/torus/torus_with_plane.mtl create mode 100644 data/torus/torus_with_plane.obj create mode 100644 data/torus/torus_with_plane.urdf create mode 100644 data/torus/torus_with_separate_plane.urdf diff --git a/data/torus/plane_only.mtl b/data/torus/plane_only.mtl new file mode 100644 index 000000000..70d3ba1da --- /dev/null +++ b/data/torus/plane_only.mtl @@ -0,0 +1,10 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 diff --git a/data/torus/plane_only.obj b/data/torus/plane_only.obj new file mode 100644 index 000000000..893742a69 --- /dev/null +++ b/data/torus/plane_only.obj @@ -0,0 +1,7913 @@ +# Blender v2.77 (sub 0) OBJ File: '' +# www.blender.org +mtllib plane_only.mtl +o Plane +v -2.312398 -6.126618 0.566384 +v 6.032325 -2.575601 0.280679 +v -5.874205 2.203907 0.074895 +v 2.470518 5.754926 -0.210810 +v -5.804365 2.040563 0.084532 +v -5.734526 1.877220 0.094169 +v -5.664686 1.713876 0.103806 +v -5.594847 1.550532 0.113443 +v -5.525007 1.387189 0.123080 +v -5.455168 1.223845 0.132717 +v -5.385328 1.060502 0.142354 +v -5.315490 0.897157 0.151991 +v -5.245650 0.733814 0.161628 +v -5.175811 0.570470 0.171265 +v -5.105971 0.407127 0.180902 +v -5.036132 0.243783 0.190539 +v -4.966292 0.080439 0.200176 +v -4.896453 -0.082904 0.209813 +v -4.826613 -0.246248 0.219450 +v -4.756775 -0.409592 0.229087 +v -4.686935 -0.572935 0.238724 +v -4.617096 -0.736279 0.248362 +v -4.547256 -0.899623 0.257998 +v -4.477417 -1.062966 0.267636 +v -4.407578 -1.226310 0.277273 +v -4.337738 -1.389654 0.286910 +v -4.267900 -1.552997 0.296547 +v -4.198060 -1.716341 0.306184 +v -4.128221 -1.879685 0.315821 +v -4.058381 -2.043028 0.325458 +v -3.988542 -2.206372 0.335095 +v -3.918703 -2.369716 0.344732 +v -3.848863 -2.533059 0.354369 +v -3.779024 -2.696403 0.364006 +v -3.709185 -2.859747 0.373643 +v -3.639345 -3.023091 0.383280 +v -3.569506 -3.186434 0.392917 +v -3.499667 -3.349777 0.402554 +v -3.429827 -3.513121 0.412191 +v -3.359988 -3.676465 0.421829 +v -3.290149 -3.839808 0.431465 +v -3.220309 -4.003152 0.441103 +v -3.150470 -4.166496 0.450740 +v -3.080631 -4.329839 0.460377 +v -3.010791 -4.493183 0.470014 +v -2.940952 -4.656527 0.479651 +v -2.871112 -4.819870 0.489288 +v -2.801273 -4.983214 0.498925 +v -2.731434 -5.146557 0.508562 +v -2.661594 -5.309901 0.518199 +v -2.591755 -5.473244 0.527836 +v -2.521916 -5.636589 0.537473 +v -2.452076 -5.799932 0.547110 +v -2.382237 -5.963276 0.556747 +v -2.148776 -6.056991 0.560782 +v -1.985154 -5.987363 0.555180 +v -1.821532 -5.917735 0.549578 +v -1.657910 -5.848107 0.543976 +v -1.494288 -5.778480 0.538374 +v -1.330665 -5.708852 0.532772 +v -1.167043 -5.639224 0.527170 +v -1.003422 -5.569596 0.521568 +v -0.839799 -5.499969 0.515965 +v -0.676177 -5.430341 0.510363 +v -0.512555 -5.360713 0.504761 +v -0.348933 -5.291085 0.499159 +v -0.185311 -5.221457 0.493557 +v -0.021689 -5.151829 0.487955 +v 0.141933 -5.082201 0.482353 +v 0.305555 -5.012573 0.476751 +v 0.469177 -4.942945 0.471149 +v 0.632799 -4.873318 0.465547 +v 0.796421 -4.803690 0.459945 +v 0.960043 -4.734062 0.454343 +v 1.123665 -4.664434 0.448741 +v 1.287287 -4.594807 0.443139 +v 1.450909 -4.525179 0.437537 +v 1.614531 -4.455551 0.431935 +v 1.778153 -4.385922 0.426333 +v 1.941775 -4.316295 0.420731 +v 2.105397 -4.246667 0.415129 +v 2.269019 -4.177039 0.409527 +v 2.432641 -4.107412 0.403924 +v 2.596263 -4.037785 0.398322 +v 2.759885 -3.968157 0.392720 +v 2.923507 -3.898529 0.387118 +v 3.087129 -3.828902 0.381516 +v 3.250751 -3.759273 0.375914 +v 3.414372 -3.689645 0.370312 +v 3.577994 -3.620018 0.364710 +v 3.741616 -3.550390 0.359108 +v 3.905239 -3.480762 0.353506 +v 4.068861 -3.411134 0.347904 +v 4.232483 -3.341506 0.342302 +v 4.396105 -3.271878 0.336700 +v 4.559727 -3.202251 0.331098 +v 4.723349 -3.132623 0.325496 +v 4.886971 -3.062995 0.319894 +v 5.050592 -2.993367 0.314292 +v 5.214214 -2.923740 0.308690 +v 5.377837 -2.854112 0.303087 +v 5.541458 -2.784484 0.297485 +v 5.705081 -2.714856 0.291883 +v 5.868702 -2.645229 0.286281 +v 5.962485 -2.412257 0.271042 +v 5.892646 -2.248913 0.261405 +v 5.822806 -2.085569 0.251768 +v 5.752967 -1.922226 0.242131 +v 5.683127 -1.758882 0.232494 +v 5.613288 -1.595538 0.222857 +v 5.543449 -1.432195 0.213220 +v 5.473610 -1.268851 0.203583 +v 5.403770 -1.105507 0.193946 +v 5.333931 -0.942164 0.184309 +v 5.264091 -0.778820 0.174672 +v 5.194252 -0.615476 0.165035 +v 5.124413 -0.452132 0.155398 +v 5.054573 -0.288789 0.145761 +v 4.984735 -0.125445 0.136124 +v 4.914895 0.037898 0.126487 +v 4.845056 0.201242 0.116849 +v 4.775216 0.364586 0.107213 +v 4.705377 0.527929 0.097575 +v 4.635537 0.691273 0.087938 +v 4.565698 0.854617 0.078301 +v 4.495859 1.017960 0.068664 +v 4.426020 1.181304 0.059027 +v 4.356180 1.344648 0.049390 +v 4.286341 1.507991 0.039753 +v 4.216501 1.671335 0.030116 +v 4.146662 1.834678 0.020479 +v 4.076822 1.998022 0.010842 +v 4.006983 2.161365 0.001205 +v 3.937144 2.324709 -0.008432 +v 3.867305 2.488053 -0.018069 +v 3.797465 2.651397 -0.027706 +v 3.727626 2.814740 -0.037343 +v 3.657787 2.978083 -0.046980 +v 3.587947 3.141428 -0.056617 +v 3.518108 3.304771 -0.066254 +v 3.448268 3.468114 -0.075891 +v 3.378429 3.631458 -0.085528 +v 3.308590 3.794802 -0.095165 +v 3.238750 3.958145 -0.104803 +v 3.168911 4.121490 -0.114440 +v 3.099072 4.284833 -0.124077 +v 3.029233 4.448177 -0.133714 +v 2.959393 4.611520 -0.143351 +v 2.889554 4.774864 -0.152988 +v 2.819715 4.938208 -0.162625 +v 2.749875 5.101552 -0.172262 +v 2.680036 5.264896 -0.181899 +v 2.610196 5.428238 -0.191536 +v 2.540357 5.591582 -0.201173 +v 2.306895 5.685298 -0.205208 +v 2.143273 5.615670 -0.199606 +v 1.979651 5.546042 -0.194004 +v 1.816030 5.476415 -0.188402 +v 1.652407 5.406787 -0.182800 +v 1.488786 5.337159 -0.177198 +v 1.325163 5.267531 -0.171596 +v 1.161541 5.197904 -0.165994 +v 0.997919 5.128276 -0.160392 +v 0.834297 5.058648 -0.154789 +v 0.670675 4.989020 -0.149187 +v 0.507053 4.919393 -0.143585 +v 0.343431 4.849765 -0.137983 +v 0.179809 4.780137 -0.132381 +v 0.016187 4.710509 -0.126779 +v -0.147435 4.640882 -0.121177 +v -0.311057 4.571253 -0.115575 +v -0.474679 4.501625 -0.109973 +v -0.638301 4.431997 -0.104371 +v -0.801923 4.362370 -0.098769 +v -0.965545 4.292742 -0.093167 +v -1.129167 4.223114 -0.087565 +v -1.292789 4.153486 -0.081963 +v -1.456411 4.083858 -0.076361 +v -1.620033 4.014231 -0.070759 +v -1.783655 3.944603 -0.065157 +v -1.947277 3.874975 -0.059554 +v -2.110899 3.805346 -0.053952 +v -2.274521 3.735718 -0.048350 +v -2.438143 3.666091 -0.042748 +v -2.601765 3.596463 -0.037146 +v -2.765387 3.526835 -0.031544 +v -2.929009 3.457207 -0.025942 +v -3.092631 3.387580 -0.020340 +v -3.256253 3.317952 -0.014738 +v -3.419875 3.248324 -0.009136 +v -3.583497 3.178696 -0.003534 +v -3.747118 3.109069 0.002068 +v -3.910740 3.039441 0.007670 +v -4.074363 2.969813 0.013272 +v -4.237985 2.900185 0.018874 +v -4.401607 2.830558 0.024476 +v -4.565228 2.760930 0.030078 +v -4.728850 2.691302 0.035680 +v -4.892472 2.621674 0.041282 +v -5.056094 2.552047 0.046885 +v -5.219716 2.482419 0.052487 +v -5.383339 2.412791 0.058089 +v -5.546961 2.343162 0.063691 +v -5.710583 2.273535 0.069293 +v -5.640743 2.110191 0.078930 +v -5.407282 2.016475 0.082965 +v -5.173820 1.922760 0.087000 +v -4.940358 1.829044 0.091035 +v -4.706897 1.735328 0.095070 +v -4.473435 1.641612 0.099105 +v -4.239974 1.547897 0.103140 +v -4.006513 1.454180 0.107175 +v -3.773051 1.360465 0.111210 +v -3.539590 1.266749 0.115245 +v -3.306129 1.173033 0.119280 +v -3.072667 1.079317 0.123315 +v -2.839206 0.985601 0.127350 +v -2.605745 0.891885 0.131385 +v -2.372283 0.798169 0.135420 +v -2.138822 0.704454 0.139455 +v -1.905361 0.610738 0.143490 +v -1.671899 0.517022 0.147525 +v -1.438438 0.423306 0.151560 +v -1.204977 0.329590 0.155595 +v -0.971515 0.235874 0.159630 +v -0.738054 0.142159 0.163665 +v -0.504593 0.048443 0.167700 +v -0.271131 -0.045273 0.171735 +v -0.037670 -0.138989 0.175770 +v 0.195791 -0.232705 0.179805 +v 0.429253 -0.326421 0.183840 +v 0.662714 -0.420136 0.187875 +v 0.896175 -0.513852 0.191910 +v 1.129637 -0.607568 0.195945 +v 1.363098 -0.701284 0.199980 +v 1.596559 -0.795000 0.204015 +v 1.830021 -0.888716 0.208049 +v 2.063482 -0.982431 0.212084 +v 2.296943 -1.076147 0.216119 +v 2.530405 -1.169863 0.220154 +v 2.763866 -1.263579 0.224189 +v 2.997327 -1.357295 0.228224 +v 3.230788 -1.451011 0.232259 +v 3.464250 -1.544726 0.236294 +v 3.697711 -1.638442 0.240329 +v 3.931173 -1.732158 0.244364 +v 4.164635 -1.825874 0.248399 +v 4.398096 -1.919590 0.252434 +v 4.631557 -2.013306 0.256469 +v 4.865018 -2.107021 0.260504 +v 5.098479 -2.200737 0.264539 +v 5.331941 -2.294453 0.268574 +v 5.565402 -2.388169 0.272609 +v 5.798862 -2.481885 0.276644 +v -5.477121 2.179819 0.073328 +v -5.243659 2.086103 0.077363 +v -5.313498 2.249447 0.067726 +v -5.010198 1.992388 0.081398 +v -5.080037 2.155731 0.071761 +v -5.149877 2.319074 0.062124 +v -4.776736 1.898672 0.085433 +v -4.846576 2.062015 0.075796 +v -4.916415 2.225359 0.066159 +v -4.986255 2.388702 0.056522 +v -4.543275 1.804956 0.089468 +v -4.613114 1.968299 0.079831 +v -4.682954 2.131643 0.070194 +v -4.752793 2.294986 0.060557 +v -4.822633 2.458330 0.050920 +v -4.309813 1.711240 0.093503 +v -4.379653 1.874583 0.083866 +v -4.449492 2.037927 0.074229 +v -4.519332 2.201271 0.064592 +v -4.589171 2.364614 0.054955 +v -4.659011 2.527958 0.045318 +v -4.076352 1.617524 0.097538 +v -4.146192 1.780868 0.087901 +v -4.216031 1.944211 0.078264 +v -4.285871 2.107555 0.068627 +v -4.355710 2.270899 0.058990 +v -4.425550 2.434242 0.049352 +v -4.495389 2.597585 0.039715 +v -3.842891 1.523808 0.101573 +v -3.912730 1.687152 0.091936 +v -3.982570 1.850495 0.082299 +v -4.052409 2.013839 0.072662 +v -4.122249 2.177183 0.063025 +v -4.192088 2.340526 0.053387 +v -4.261928 2.503870 0.043751 +v -4.331767 2.667213 0.034113 +v -3.609429 1.430092 0.105608 +v -3.679269 1.593436 0.095971 +v -3.749108 1.756780 0.086334 +v -3.818948 1.920124 0.076697 +v -3.888787 2.083467 0.067060 +v -3.958627 2.246810 0.057422 +v -4.028465 2.410154 0.047786 +v -4.098306 2.573498 0.038148 +v -4.168145 2.736841 0.028511 +v -3.375968 1.336377 0.109643 +v -3.445807 1.499720 0.100006 +v -3.515647 1.663064 0.090369 +v -3.585486 1.826408 0.080732 +v -3.655326 1.989751 0.071095 +v -3.725165 2.153095 0.061457 +v -3.795005 2.316438 0.051821 +v -3.864844 2.479782 0.042183 +v -3.934684 2.643125 0.032546 +v -4.004523 2.806469 0.022909 +v -3.142507 1.242661 0.113678 +v -3.212346 1.406005 0.104041 +v -3.282185 1.569348 0.094404 +v -3.352025 1.732692 0.084767 +v -3.421864 1.896036 0.075130 +v -3.491704 2.059379 0.065492 +v -3.561543 2.222723 0.055856 +v -3.631382 2.386066 0.046218 +v -3.701222 2.549410 0.036581 +v -3.771061 2.712753 0.026944 +v -3.840901 2.876097 0.017307 +v -2.909045 1.148945 0.117713 +v -2.978885 1.312288 0.108076 +v -3.048724 1.475632 0.098439 +v -3.118563 1.638976 0.088801 +v -3.188403 1.802320 0.079165 +v -3.258242 1.965663 0.069527 +v -3.328082 2.129007 0.059891 +v -3.397921 2.292350 0.050253 +v -3.467761 2.455694 0.040616 +v -3.537600 2.619037 0.030979 +v -3.607439 2.782381 0.021342 +v -3.677279 2.945725 0.011705 +v -2.675584 1.055229 0.121748 +v -2.745423 1.218573 0.112111 +v -2.815263 1.381916 0.102473 +v -2.885102 1.545260 0.092836 +v -2.954941 1.708604 0.083200 +v -3.024781 1.871947 0.073562 +v -3.094620 2.035291 0.063925 +v -3.164460 2.198635 0.054288 +v -3.234299 2.361978 0.044651 +v -3.304139 2.525321 0.035014 +v -3.373978 2.688665 0.025377 +v -3.443818 2.852009 0.015740 +v -3.513657 3.015353 0.006103 +v -2.442123 0.961513 0.125782 +v -2.511962 1.124857 0.116146 +v -2.581802 1.288201 0.106508 +v -2.651641 1.451544 0.096871 +v -2.721480 1.614888 0.087234 +v -2.791320 1.778232 0.077597 +v -2.861159 1.941575 0.067960 +v -2.930999 2.104919 0.058323 +v -3.000838 2.268262 0.048686 +v -3.070677 2.431606 0.039049 +v -3.140517 2.594950 0.029412 +v -3.210356 2.758293 0.019775 +v -3.280196 2.921637 0.010138 +v -3.350035 3.084981 0.000501 +v -2.208661 0.867797 0.129817 +v -2.278501 1.031141 0.120181 +v -2.348340 1.194485 0.110543 +v -2.418180 1.357828 0.100906 +v -2.488019 1.521172 0.091269 +v -2.557858 1.684516 0.081632 +v -2.627698 1.847859 0.071995 +v -2.697537 2.011203 0.062358 +v -2.767377 2.174546 0.052721 +v -2.837216 2.337890 0.043084 +v -2.907056 2.501234 0.033447 +v -2.976895 2.664578 0.023810 +v -3.046734 2.827921 0.014173 +v -3.116574 2.991265 0.004536 +v -3.186413 3.154608 -0.005101 +v -1.975200 0.774081 0.133852 +v -2.045039 0.937425 0.124216 +v -2.114879 1.100769 0.114578 +v -2.184718 1.264112 0.104941 +v -2.254558 1.427456 0.095304 +v -2.324397 1.590800 0.085667 +v -2.394237 1.754144 0.076030 +v -2.464076 1.917487 0.066393 +v -2.533916 2.080831 0.056756 +v -2.603755 2.244174 0.047119 +v -2.673594 2.407518 0.037482 +v -2.743433 2.570862 0.027845 +v -2.813273 2.734205 0.018208 +v -2.883112 2.897548 0.008571 +v -2.952952 3.060892 -0.001066 +v -3.022791 3.224236 -0.010703 +v -1.741739 0.680366 0.137887 +v -1.811578 0.843709 0.128251 +v -1.881418 1.007053 0.118613 +v -1.951257 1.170397 0.108976 +v -2.021096 1.333740 0.099339 +v -2.090936 1.497084 0.089702 +v -2.160775 1.660428 0.080065 +v -2.230615 1.823772 0.070428 +v -2.300454 1.987115 0.060791 +v -2.370294 2.150458 0.051154 +v -2.440133 2.313802 0.041517 +v -2.509972 2.477146 0.031880 +v -2.579812 2.640490 0.022243 +v -2.649651 2.803833 0.012606 +v -2.719491 2.967177 0.002969 +v -2.789330 3.130521 -0.006668 +v -2.859169 3.293864 -0.016305 +v -1.508277 0.586650 0.141922 +v -1.578117 0.749993 0.132286 +v -1.647956 0.913337 0.122648 +v -1.717796 1.076681 0.113011 +v -1.787635 1.240025 0.103374 +v -1.857474 1.403368 0.093737 +v -1.927314 1.566712 0.084100 +v -1.997153 1.730055 0.074463 +v -2.066993 1.893399 0.064826 +v -2.136832 2.056743 0.055189 +v -2.206672 2.220086 0.045552 +v -2.276511 2.383430 0.035915 +v -2.346350 2.546774 0.026278 +v -2.416190 2.710117 0.016641 +v -2.486029 2.873461 0.007004 +v -2.555869 3.036804 -0.002633 +v -2.625708 3.200148 -0.012270 +v -2.695547 3.363492 -0.021907 +v -1.274816 0.492934 0.145957 +v -1.344656 0.656278 0.136321 +v -1.414495 0.819621 0.126683 +v -1.484334 0.982965 0.117046 +v -1.554174 1.146308 0.107409 +v -1.624013 1.309652 0.097772 +v -1.693853 1.472996 0.088135 +v -1.763692 1.636340 0.078498 +v -1.833531 1.799683 0.068861 +v -1.903371 1.963027 0.059224 +v -1.973210 2.126370 0.049587 +v -2.043050 2.289714 0.039950 +v -2.112889 2.453058 0.030313 +v -2.182729 2.616402 0.020676 +v -2.252568 2.779745 0.011039 +v -2.322407 2.943089 0.001402 +v -2.392247 3.106432 -0.008235 +v -2.462086 3.269776 -0.017872 +v -2.531925 3.433120 -0.027509 +v -1.041355 0.399218 0.149992 +v -1.111194 0.562562 0.140356 +v -1.181034 0.725905 0.130718 +v -1.250873 0.889249 0.121081 +v -1.320712 1.052593 0.111444 +v -1.390552 1.215936 0.101807 +v -1.460391 1.379280 0.092170 +v -1.530231 1.542624 0.082533 +v -1.600070 1.705968 0.072896 +v -1.669910 1.869311 0.063259 +v -1.739749 2.032655 0.053622 +v -1.809589 2.195998 0.043985 +v -1.879428 2.359342 0.034348 +v -1.949267 2.522686 0.024711 +v -2.019107 2.686029 0.015074 +v -2.088946 2.849373 0.005437 +v -2.158785 3.012717 -0.004200 +v -2.228625 3.176060 -0.013837 +v -2.298464 3.339404 -0.023474 +v -2.368304 3.502747 -0.033111 +v -0.807893 0.305502 0.154027 +v -0.877733 0.468846 0.144391 +v -0.947572 0.632190 0.134753 +v -1.017412 0.795533 0.125116 +v -1.087251 0.958877 0.115479 +v -1.157091 1.122221 0.105842 +v -1.226930 1.285564 0.096205 +v -1.296769 1.448908 0.086568 +v -1.366609 1.612251 0.076931 +v -1.436448 1.775595 0.067294 +v -1.506288 1.938939 0.057657 +v -1.576127 2.102283 0.048020 +v -1.645967 2.265626 0.038383 +v -1.715806 2.428969 0.028746 +v -1.785645 2.592313 0.019109 +v -1.855485 2.755657 0.009472 +v -1.925324 2.919001 -0.000165 +v -1.995163 3.082345 -0.009802 +v -2.065003 3.245688 -0.019439 +v -2.134842 3.409032 -0.029076 +v -2.204681 3.572375 -0.038713 +v -0.574432 0.211786 0.158062 +v -0.644271 0.375130 0.148426 +v -0.714111 0.538474 0.138788 +v -0.783950 0.701817 0.129151 +v -0.853790 0.865161 0.119514 +v -0.923629 1.028505 0.109877 +v -0.993469 1.191848 0.100240 +v -1.063308 1.355192 0.090603 +v -1.133147 1.518536 0.080966 +v -1.202987 1.681879 0.071329 +v -1.272826 1.845223 0.061692 +v -1.342666 2.008567 0.052055 +v -1.412505 2.171911 0.042418 +v -1.482344 2.335254 0.032781 +v -1.552184 2.498598 0.023144 +v -1.622023 2.661941 0.013507 +v -1.691863 2.825285 0.003870 +v -1.761702 2.988628 -0.005767 +v -1.831541 3.151972 -0.015404 +v -1.901381 3.315316 -0.025041 +v -1.971220 3.478660 -0.034678 +v -2.041059 3.642003 -0.044315 +v -0.340971 0.118071 0.162097 +v -0.410810 0.281414 0.152461 +v -0.480650 0.444758 0.142823 +v -0.550489 0.608102 0.133186 +v -0.620328 0.771445 0.123549 +v -0.690168 0.934789 0.113912 +v -0.760007 1.098133 0.104275 +v -0.829847 1.261476 0.094638 +v -0.899686 1.424820 0.085001 +v -0.969525 1.588164 0.075364 +v -1.039365 1.751507 0.065727 +v -1.109204 1.914851 0.056090 +v -1.179044 2.078194 0.046453 +v -1.248883 2.241538 0.036816 +v -1.318722 2.404882 0.027179 +v -1.388562 2.568226 0.017542 +v -1.458401 2.731569 0.007905 +v -1.528241 2.894913 -0.001732 +v -1.598080 3.058257 -0.011369 +v -1.667919 3.221600 -0.021006 +v -1.737759 3.384944 -0.030643 +v -1.807598 3.548288 -0.040280 +v -1.877437 3.711631 -0.049917 +v -0.107509 0.024355 0.166132 +v -0.177349 0.187698 0.156495 +v -0.247188 0.351042 0.146858 +v -0.317028 0.514386 0.137221 +v -0.386867 0.677729 0.127584 +v -0.456706 0.841073 0.117947 +v -0.526546 1.004417 0.108310 +v -0.596385 1.167760 0.098673 +v -0.666225 1.331104 0.089036 +v -0.736064 1.494448 0.079399 +v -0.805903 1.657791 0.069762 +v -0.875743 1.821135 0.060125 +v -0.945582 1.984479 0.050488 +v -1.015422 2.147822 0.040851 +v -1.085261 2.311166 0.031214 +v -1.155100 2.474510 0.021577 +v -1.224940 2.637853 0.011940 +v -1.294779 2.801197 0.002303 +v -1.364619 2.964541 -0.007334 +v -1.434458 3.127884 -0.016971 +v -1.504297 3.291228 -0.026608 +v -1.574137 3.454572 -0.036245 +v -1.643976 3.617915 -0.045882 +v -1.713815 3.781258 -0.055519 +v 0.125952 -0.069361 0.170167 +v 0.056113 0.093983 0.160530 +v -0.013727 0.257326 0.150893 +v -0.083566 0.420670 0.141256 +v -0.153406 0.584014 0.131619 +v -0.223245 0.747357 0.121982 +v -0.293084 0.910701 0.112345 +v -0.362924 1.074044 0.102708 +v -0.432763 1.237388 0.093071 +v -0.502603 1.400732 0.083434 +v -0.572442 1.564076 0.073797 +v -0.642281 1.727419 0.064160 +v -0.712121 1.890763 0.054523 +v -0.781960 2.054106 0.044886 +v -0.851800 2.217450 0.035249 +v -0.921639 2.380794 0.025612 +v -0.991478 2.544138 0.015975 +v -1.061318 2.707481 0.006338 +v -1.131157 2.870825 -0.003299 +v -1.200997 3.034168 -0.012936 +v -1.270836 3.197512 -0.022573 +v -1.340675 3.360856 -0.032210 +v -1.410515 3.524200 -0.041847 +v -1.480354 3.687543 -0.051485 +v -1.550194 3.850887 -0.061122 +v 0.359413 -0.163077 0.174202 +v 0.289574 0.000267 0.164565 +v 0.219735 0.163610 0.154928 +v 0.149895 0.326954 0.145291 +v 0.080056 0.490298 0.135654 +v 0.010216 0.653641 0.126017 +v -0.059623 0.816985 0.116380 +v -0.129462 0.980329 0.106743 +v -0.199302 1.143672 0.097106 +v -0.269141 1.307016 0.087469 +v -0.338981 1.470360 0.077832 +v -0.408820 1.633703 0.068195 +v -0.478659 1.797047 0.058558 +v -0.548499 1.960391 0.048921 +v -0.618338 2.123734 0.039284 +v -0.688178 2.287078 0.029647 +v -0.758017 2.450422 0.020010 +v -0.827856 2.613765 0.010373 +v -0.897696 2.777109 0.000736 +v -0.967535 2.940452 -0.008901 +v -1.037375 3.103796 -0.018538 +v -1.107214 3.267140 -0.028175 +v -1.177053 3.430484 -0.037812 +v -1.246893 3.593827 -0.047450 +v -1.316732 3.757171 -0.057087 +v -1.386572 3.920515 -0.066724 +v 0.592875 -0.256793 0.178237 +v 0.523035 -0.093449 0.168600 +v 0.453196 0.069894 0.158963 +v 0.383356 0.233238 0.149326 +v 0.313517 0.396582 0.139689 +v 0.243678 0.559926 0.130052 +v 0.173838 0.723269 0.120415 +v 0.103999 0.886613 0.110778 +v 0.034160 1.049956 0.101141 +v -0.035680 1.213300 0.091504 +v -0.105519 1.376644 0.081867 +v -0.175359 1.539987 0.072230 +v -0.245198 1.703331 0.062593 +v -0.315037 1.866675 0.052956 +v -0.384877 2.030019 0.043319 +v -0.454716 2.193362 0.033682 +v -0.524556 2.356706 0.024045 +v -0.594395 2.520050 0.014408 +v -0.664234 2.683393 0.004771 +v -0.734074 2.846737 -0.004866 +v -0.803913 3.010080 -0.014503 +v -0.873753 3.173424 -0.024140 +v -0.943592 3.336768 -0.033778 +v -1.013431 3.500112 -0.043415 +v -1.083271 3.663455 -0.053052 +v -1.153110 3.826799 -0.062689 +v -1.222950 3.990143 -0.072326 +v 0.826336 -0.350509 0.182272 +v 0.756497 -0.187165 0.172635 +v 0.686657 -0.023821 0.162998 +v 0.616818 0.139522 0.153361 +v 0.546978 0.302866 0.143724 +v 0.477139 0.466210 0.134087 +v 0.407299 0.629553 0.124450 +v 0.337460 0.792897 0.114813 +v 0.267621 0.956241 0.105176 +v 0.197781 1.119584 0.095539 +v 0.127942 1.282928 0.085902 +v 0.058103 1.446272 0.076265 +v -0.011737 1.609615 0.066628 +v -0.081576 1.772959 0.056991 +v -0.151416 1.936302 0.047354 +v -0.221255 2.099646 0.037717 +v -0.291094 2.262990 0.028080 +v -0.360934 2.426333 0.018443 +v -0.430773 2.589677 0.008806 +v -0.500613 2.753021 -0.000831 +v -0.570452 2.916364 -0.010468 +v -0.640291 3.079708 -0.020105 +v -0.710131 3.243052 -0.029743 +v -0.779970 3.406395 -0.039380 +v -0.849809 3.569739 -0.049017 +v -0.919649 3.733083 -0.058654 +v -0.989488 3.896427 -0.068291 +v -1.059328 4.059771 -0.077928 +v 1.059797 -0.444224 0.186307 +v 0.989958 -0.280881 0.176670 +v 0.920118 -0.117537 0.167033 +v 0.850279 0.045806 0.157396 +v 0.780440 0.209150 0.147759 +v 0.710600 0.372494 0.138122 +v 0.640761 0.535838 0.128485 +v 0.570921 0.699181 0.118848 +v 0.501082 0.862525 0.109211 +v 0.431243 1.025868 0.099574 +v 0.361403 1.189212 0.089937 +v 0.291564 1.352556 0.080300 +v 0.221724 1.515899 0.070663 +v 0.151885 1.679243 0.061026 +v 0.082046 1.842587 0.051389 +v 0.012206 2.005930 0.041752 +v -0.057633 2.169274 0.032115 +v -0.127473 2.332618 0.022478 +v -0.197312 2.495961 0.012841 +v -0.267151 2.659305 0.003203 +v -0.336991 2.822649 -0.006433 +v -0.406830 2.985992 -0.016070 +v -0.476670 3.149336 -0.025708 +v -0.546509 3.312680 -0.035345 +v -0.616348 3.476023 -0.044982 +v -0.686188 3.639367 -0.054619 +v -0.756027 3.802711 -0.064256 +v -0.825866 3.966055 -0.073893 +v -0.895706 4.129398 -0.083530 +v 1.293259 -0.537940 0.190342 +v 1.223419 -0.374597 0.180705 +v 1.153580 -0.211253 0.171068 +v 1.083740 -0.047909 0.161431 +v 1.013901 0.115434 0.151794 +v 0.944062 0.278778 0.142157 +v 0.874222 0.442122 0.132520 +v 0.804383 0.605465 0.122883 +v 0.734543 0.768809 0.113246 +v 0.664704 0.932153 0.103609 +v 0.594865 1.095496 0.093972 +v 0.525025 1.258840 0.084335 +v 0.455186 1.422184 0.074698 +v 0.385347 1.585527 0.065061 +v 0.315507 1.748871 0.055424 +v 0.245668 1.912214 0.045787 +v 0.175828 2.075558 0.036150 +v 0.105989 2.238902 0.026513 +v 0.036150 2.402245 0.016876 +v -0.033690 2.565589 0.007238 +v -0.103529 2.728933 -0.002398 +v -0.173369 2.892277 -0.012035 +v -0.243208 3.055620 -0.021673 +v -0.313048 3.218964 -0.031310 +v -0.382887 3.382308 -0.040947 +v -0.452726 3.545651 -0.050584 +v -0.522565 3.708995 -0.060221 +v -0.592405 3.872339 -0.069858 +v -0.662244 4.035683 -0.079495 +v -0.732084 4.199026 -0.089132 +v 1.526720 -0.631656 0.194377 +v 1.456881 -0.468312 0.184740 +v 1.387041 -0.304969 0.175103 +v 1.317202 -0.141625 0.165466 +v 1.247363 0.021719 0.155829 +v 1.177523 0.185062 0.146192 +v 1.107684 0.348406 0.136555 +v 1.037845 0.511750 0.126918 +v 0.968005 0.675093 0.117281 +v 0.898166 0.838437 0.107644 +v 0.828327 1.001781 0.098007 +v 0.758487 1.165124 0.088370 +v 0.688648 1.328468 0.078733 +v 0.618808 1.491812 0.069096 +v 0.548969 1.655155 0.059459 +v 0.479130 1.818499 0.049822 +v 0.409290 1.981842 0.040185 +v 0.339451 2.145186 0.030548 +v 0.269611 2.308530 0.020911 +v 0.199772 2.471873 0.011274 +v 0.129933 2.635217 0.001636 +v 0.060093 2.798561 -0.008000 +v -0.009746 2.961904 -0.017638 +v -0.079586 3.125248 -0.027275 +v -0.149425 3.288592 -0.036912 +v -0.219265 3.451936 -0.046549 +v -0.289104 3.615279 -0.056186 +v -0.358943 3.778623 -0.065823 +v -0.428783 3.941966 -0.075460 +v -0.498622 4.105311 -0.085097 +v -0.568462 4.268654 -0.094734 +v 1.760181 -0.725372 0.198412 +v 1.690342 -0.562028 0.188775 +v 1.620502 -0.398685 0.179138 +v 1.550663 -0.235341 0.169501 +v 1.480824 -0.071997 0.159864 +v 1.410985 0.091346 0.150227 +v 1.341145 0.254690 0.140590 +v 1.271306 0.418034 0.130953 +v 1.201466 0.581377 0.121316 +v 1.131627 0.744721 0.111679 +v 1.061788 0.908065 0.102042 +v 0.991948 1.071408 0.092405 +v 0.922109 1.234752 0.082768 +v 0.852270 1.398096 0.073131 +v 0.782430 1.561439 0.063494 +v 0.712591 1.724783 0.053857 +v 0.642752 1.888126 0.044220 +v 0.572912 2.051470 0.034583 +v 0.503073 2.214814 0.024946 +v 0.433233 2.378157 0.015309 +v 0.363394 2.541501 0.005672 +v 0.293555 2.704845 -0.003965 +v 0.223715 2.868189 -0.013603 +v 0.153876 3.031532 -0.023240 +v 0.084036 3.194876 -0.032877 +v 0.014197 3.358220 -0.042514 +v -0.055643 3.521563 -0.052151 +v -0.125482 3.684907 -0.061788 +v -0.195321 3.848251 -0.071425 +v -0.265161 4.011594 -0.081062 +v -0.335000 4.174939 -0.090699 +v -0.404840 4.338282 -0.100336 +v 1.993642 -0.819088 0.202447 +v 1.923803 -0.655744 0.192810 +v 1.853964 -0.492400 0.183173 +v 1.784124 -0.329057 0.173536 +v 1.714285 -0.165713 0.163899 +v 1.644446 -0.002369 0.154262 +v 1.574606 0.160974 0.144625 +v 1.504767 0.324318 0.134988 +v 1.434928 0.487662 0.125351 +v 1.365088 0.651005 0.115714 +v 1.295249 0.814349 0.106077 +v 1.225410 0.977692 0.096440 +v 1.155570 1.141036 0.086803 +v 1.085731 1.304380 0.077166 +v 1.015892 1.467724 0.067529 +v 0.946052 1.631067 0.057892 +v 0.876213 1.794411 0.048255 +v 0.806373 1.957754 0.038618 +v 0.736534 2.121098 0.028981 +v 0.666695 2.284442 0.019344 +v 0.596855 2.447785 0.009706 +v 0.527016 2.611129 0.000069 +v 0.457176 2.774473 -0.009568 +v 0.387337 2.937817 -0.019205 +v 0.317498 3.101161 -0.028842 +v 0.247658 3.264504 -0.038479 +v 0.177819 3.427847 -0.048116 +v 0.107979 3.591191 -0.057753 +v 0.038140 3.754535 -0.067390 +v -0.031699 3.917878 -0.077027 +v -0.101539 4.081222 -0.086664 +v -0.171378 4.244566 -0.096301 +v -0.241217 4.407909 -0.105938 +v 2.227104 -0.912804 0.206482 +v 2.157264 -0.749460 0.196845 +v 2.087425 -0.586116 0.187208 +v 2.017586 -0.422773 0.177571 +v 1.947746 -0.259429 0.167934 +v 1.877907 -0.096085 0.158297 +v 1.808068 0.067258 0.148660 +v 1.738228 0.230602 0.139023 +v 1.668389 0.393946 0.129386 +v 1.598550 0.557289 0.119749 +v 1.528710 0.720633 0.110112 +v 1.458871 0.883977 0.100475 +v 1.389032 1.047320 0.090838 +v 1.319192 1.210664 0.081201 +v 1.249353 1.374008 0.071564 +v 1.179514 1.537351 0.061927 +v 1.109674 1.700695 0.052290 +v 1.039835 1.864038 0.042653 +v 0.969995 2.027382 0.033016 +v 0.900156 2.190726 0.023379 +v 0.830317 2.354070 0.013741 +v 0.760477 2.517413 0.004105 +v 0.690638 2.680757 -0.005533 +v 0.620798 2.844100 -0.015170 +v 0.550959 3.007444 -0.024807 +v 0.481119 3.170788 -0.034444 +v 0.411280 3.334132 -0.044081 +v 0.341441 3.497475 -0.053718 +v 0.271601 3.660819 -0.063355 +v 0.201762 3.824162 -0.072992 +v 0.131922 3.987506 -0.082629 +v 0.062083 4.150850 -0.092266 +v -0.007756 4.314194 -0.101903 +v -0.077596 4.477537 -0.111540 +v 2.460565 -1.006519 0.210517 +v 2.390726 -0.843176 0.200880 +v 2.320886 -0.679832 0.191243 +v 2.251047 -0.516488 0.181606 +v 2.181208 -0.353145 0.171969 +v 2.111368 -0.189801 0.162332 +v 2.041529 -0.026457 0.152695 +v 1.971690 0.136886 0.143058 +v 1.901850 0.300230 0.133421 +v 1.832011 0.463574 0.123784 +v 1.762172 0.626917 0.114147 +v 1.692332 0.790261 0.104510 +v 1.622493 0.953604 0.094873 +v 1.552653 1.116948 0.085236 +v 1.482814 1.280292 0.075599 +v 1.412975 1.443635 0.065962 +v 1.343135 1.606979 0.056325 +v 1.273296 1.770323 0.046688 +v 1.203457 1.933666 0.037051 +v 1.133617 2.097010 0.027414 +v 1.063778 2.260354 0.017776 +v 0.993939 2.423697 0.008140 +v 0.924099 2.587041 -0.001498 +v 0.854260 2.750385 -0.011135 +v 0.784420 2.913728 -0.020772 +v 0.714581 3.077072 -0.030409 +v 0.644741 3.240416 -0.040046 +v 0.574902 3.403759 -0.049683 +v 0.505063 3.567103 -0.059320 +v 0.435223 3.730447 -0.068957 +v 0.365384 3.893790 -0.078594 +v 0.295545 4.057134 -0.088231 +v 0.225705 4.220478 -0.097868 +v 0.155866 4.383822 -0.107505 +v 0.086026 4.547165 -0.117142 +v 2.694026 -1.100235 0.214552 +v 2.624187 -0.936891 0.204915 +v 2.554348 -0.773548 0.195278 +v 2.484508 -0.610204 0.185641 +v 2.414669 -0.446860 0.176004 +v 2.344830 -0.283517 0.166367 +v 2.274990 -0.120173 0.156730 +v 2.205151 0.043171 0.147093 +v 2.135312 0.206514 0.137456 +v 2.065472 0.369858 0.127819 +v 1.995633 0.533202 0.118182 +v 1.925793 0.696545 0.108545 +v 1.855954 0.859889 0.098908 +v 1.786115 1.023233 0.089271 +v 1.716275 1.186576 0.079634 +v 1.646436 1.349920 0.069997 +v 1.576597 1.513264 0.060360 +v 1.506757 1.676607 0.050723 +v 1.436918 1.839951 0.041086 +v 1.367079 2.003294 0.031449 +v 1.297239 2.166638 0.021811 +v 1.227400 2.329982 0.012175 +v 1.157561 2.493325 0.002537 +v 1.087721 2.656669 -0.007100 +v 1.017882 2.820013 -0.016737 +v 0.948043 2.983356 -0.026374 +v 0.878203 3.146700 -0.036011 +v 0.808364 3.310044 -0.045648 +v 0.738524 3.473387 -0.055285 +v 0.668685 3.636731 -0.064922 +v 0.598846 3.800074 -0.074559 +v 0.529006 3.963418 -0.084196 +v 0.459167 4.126763 -0.093833 +v 0.389327 4.290105 -0.103470 +v 0.319488 4.453450 -0.113107 +v 0.249648 4.616793 -0.122744 +v 2.927488 -1.193951 0.218587 +v 2.857649 -1.030607 0.208950 +v 2.787809 -0.867264 0.199313 +v 2.717970 -0.703920 0.189676 +v 2.648130 -0.540576 0.180039 +v 2.578291 -0.377233 0.170402 +v 2.508452 -0.213889 0.160765 +v 2.438612 -0.050545 0.151128 +v 2.368773 0.112799 0.141491 +v 2.298934 0.276142 0.131854 +v 2.229095 0.439486 0.122217 +v 2.159255 0.602829 0.112580 +v 2.089416 0.766173 0.102943 +v 2.019576 0.929517 0.093306 +v 1.949737 1.092860 0.083669 +v 1.879898 1.256204 0.074032 +v 1.810058 1.419548 0.064395 +v 1.740219 1.582891 0.054758 +v 1.670380 1.746235 0.045121 +v 1.600540 1.909578 0.035484 +v 1.530701 2.072922 0.025846 +v 1.460862 2.236266 0.016210 +v 1.391022 2.399609 0.006572 +v 1.321183 2.562953 -0.003065 +v 1.251343 2.726297 -0.012702 +v 1.181504 2.889640 -0.022339 +v 1.111665 3.052984 -0.031976 +v 1.041825 3.216328 -0.041613 +v 0.971986 3.379672 -0.051250 +v 0.902147 3.543015 -0.060887 +v 0.832307 3.706359 -0.070524 +v 0.762468 3.869703 -0.080161 +v 0.692628 4.033046 -0.089798 +v 0.622789 4.196391 -0.099435 +v 0.552949 4.359733 -0.109072 +v 0.483110 4.523077 -0.118709 +v 0.413270 4.686420 -0.128346 +v 3.160949 -1.287667 0.222622 +v 3.091110 -1.124323 0.212985 +v 3.021271 -0.960980 0.203348 +v 2.951431 -0.797636 0.193711 +v 2.881592 -0.634292 0.184074 +v 2.811752 -0.470948 0.174437 +v 2.741913 -0.307605 0.164800 +v 2.672074 -0.144261 0.155163 +v 2.602234 0.019083 0.145526 +v 2.532395 0.182426 0.135889 +v 2.462556 0.345770 0.126252 +v 2.392716 0.509114 0.116615 +v 2.322877 0.672457 0.106978 +v 2.253038 0.835801 0.097341 +v 2.183198 0.999145 0.087704 +v 2.113359 1.162488 0.078067 +v 2.043519 1.325832 0.068430 +v 1.973680 1.489176 0.058793 +v 1.903841 1.652519 0.049156 +v 1.834001 1.815863 0.039519 +v 1.764162 1.979206 0.029881 +v 1.694323 2.142550 0.020245 +v 1.624483 2.305894 0.010607 +v 1.554644 2.469237 0.000970 +v 1.484805 2.632581 -0.008667 +v 1.414965 2.795925 -0.018304 +v 1.345126 2.959268 -0.027941 +v 1.275287 3.122612 -0.037578 +v 1.205447 3.285956 -0.047215 +v 1.135608 3.449299 -0.056852 +v 1.065768 3.612643 -0.066489 +v 0.995929 3.775987 -0.076126 +v 0.926090 3.939330 -0.085763 +v 0.856250 4.102675 -0.095400 +v 0.786411 4.266018 -0.105037 +v 0.716572 4.429361 -0.114674 +v 0.646732 4.592705 -0.124311 +v 0.576893 4.756048 -0.133948 +v 3.394411 -1.381383 0.226657 +v 3.324571 -1.218039 0.217020 +v 3.254732 -1.054695 0.207383 +v 3.184893 -0.891352 0.197746 +v 3.115053 -0.728008 0.188109 +v 3.045214 -0.564664 0.178472 +v 2.975374 -0.401321 0.168835 +v 2.905535 -0.237977 0.159198 +v 2.835696 -0.074633 0.149561 +v 2.765857 0.088711 0.139924 +v 2.696017 0.252054 0.130287 +v 2.626178 0.415398 0.120650 +v 2.556339 0.578741 0.111013 +v 2.486499 0.742085 0.101376 +v 2.416660 0.905429 0.091739 +v 2.346820 1.068772 0.082102 +v 2.276981 1.232116 0.072465 +v 2.207142 1.395460 0.062828 +v 2.137302 1.558803 0.053190 +v 2.067463 1.722147 0.043554 +v 1.997624 1.885490 0.033916 +v 1.927784 2.048834 0.024279 +v 1.857945 2.212178 0.014642 +v 1.788106 2.375521 0.005005 +v 1.718266 2.538865 -0.004632 +v 1.648427 2.702209 -0.014269 +v 1.578587 2.865552 -0.023906 +v 1.508748 3.028896 -0.033543 +v 1.438909 3.192240 -0.043180 +v 1.369069 3.355584 -0.052817 +v 1.299230 3.518927 -0.062454 +v 1.229391 3.682271 -0.072091 +v 1.159551 3.845615 -0.081728 +v 1.089712 4.008958 -0.091365 +v 1.019872 4.172303 -0.101002 +v 0.950033 4.335646 -0.110639 +v 0.880193 4.498990 -0.120276 +v 0.810354 4.662333 -0.129913 +v 0.740515 4.825676 -0.139550 +v 3.627872 -1.475098 0.230692 +v 3.558033 -1.311755 0.221055 +v 3.488194 -1.148411 0.211418 +v 3.418354 -0.985067 0.201781 +v 3.348515 -0.821724 0.192144 +v 3.278676 -0.658380 0.182507 +v 3.208836 -0.495036 0.172870 +v 3.138997 -0.331693 0.163233 +v 3.069157 -0.168349 0.153596 +v 2.999318 -0.005005 0.143959 +v 2.929479 0.158338 0.134322 +v 2.859639 0.321682 0.124685 +v 2.789800 0.485026 0.115048 +v 2.719961 0.648369 0.105411 +v 2.650121 0.811713 0.095774 +v 2.580282 0.975057 0.086137 +v 2.510442 1.138400 0.076500 +v 2.440603 1.301744 0.066863 +v 2.370764 1.465088 0.057225 +v 2.300925 1.628431 0.047589 +v 2.231085 1.791775 0.037951 +v 2.161246 1.955118 0.028314 +v 2.091406 2.118462 0.018677 +v 2.021567 2.281806 0.009040 +v 1.951728 2.445150 -0.000597 +v 1.881888 2.608493 -0.010234 +v 1.812049 2.771837 -0.019871 +v 1.742210 2.935180 -0.029508 +v 1.672370 3.098524 -0.039145 +v 1.602531 3.261868 -0.048782 +v 1.532691 3.425211 -0.058419 +v 1.462852 3.588555 -0.068056 +v 1.393013 3.751899 -0.077693 +v 1.323173 3.915242 -0.087330 +v 1.253334 4.078587 -0.096967 +v 1.183494 4.241930 -0.106604 +v 1.113655 4.405274 -0.116241 +v 1.043816 4.568617 -0.125878 +v 0.973976 4.731961 -0.135515 +v 0.904137 4.895304 -0.145152 +v 3.861333 -1.568815 0.234727 +v 3.791494 -1.405471 0.225090 +v 3.721655 -1.242127 0.215453 +v 3.651815 -1.078783 0.205816 +v 3.581976 -0.915440 0.196179 +v 3.512137 -0.752096 0.186542 +v 3.442297 -0.588752 0.176905 +v 3.372458 -0.425409 0.167268 +v 3.302619 -0.262065 0.157631 +v 3.232779 -0.098721 0.147994 +v 3.162940 0.064623 0.138357 +v 3.093101 0.227966 0.128720 +v 3.023261 0.391310 0.119083 +v 2.953422 0.554654 0.109446 +v 2.883583 0.717997 0.099809 +v 2.813743 0.881341 0.090172 +v 2.743904 1.044684 0.080535 +v 2.674064 1.208028 0.070898 +v 2.604225 1.371372 0.061260 +v 2.534386 1.534715 0.051624 +v 2.464546 1.698059 0.041986 +v 2.394707 1.861402 0.032349 +v 2.324868 2.024746 0.022712 +v 2.255028 2.188090 0.013075 +v 2.185189 2.351433 0.003438 +v 2.115350 2.514777 -0.006199 +v 2.045510 2.678120 -0.015836 +v 1.975671 2.841465 -0.025473 +v 1.905831 3.004808 -0.035110 +v 1.835992 3.168152 -0.044747 +v 1.766153 3.331496 -0.054384 +v 1.696313 3.494839 -0.064021 +v 1.626474 3.658183 -0.073658 +v 1.556635 3.821527 -0.083295 +v 1.486795 3.984870 -0.092932 +v 1.416956 4.148214 -0.102569 +v 1.347116 4.311558 -0.112206 +v 1.277277 4.474902 -0.121843 +v 1.207438 4.638245 -0.131480 +v 1.137598 4.801589 -0.141117 +v 1.067759 4.964931 -0.150754 +v 4.094795 -1.662530 0.238762 +v 4.024956 -1.499186 0.229125 +v 3.955116 -1.335843 0.219488 +v 3.885277 -1.172499 0.209851 +v 3.815438 -1.009155 0.200214 +v 3.745598 -0.845812 0.190577 +v 3.675759 -0.682468 0.180940 +v 3.605919 -0.519124 0.171303 +v 3.536080 -0.355781 0.161666 +v 3.466241 -0.192437 0.152029 +v 3.396401 -0.029093 0.142392 +v 3.326562 0.134250 0.132755 +v 3.256723 0.297594 0.123118 +v 3.186883 0.460938 0.113481 +v 3.117044 0.624281 0.103844 +v 3.047205 0.787625 0.094207 +v 2.977365 0.950969 0.084570 +v 2.907526 1.114312 0.074933 +v 2.837687 1.277656 0.065295 +v 2.767847 1.440999 0.055659 +v 2.698008 1.604343 0.046021 +v 2.628169 1.767687 0.036384 +v 2.558329 1.931030 0.026747 +v 2.488490 2.094374 0.017110 +v 2.418651 2.257718 0.007473 +v 2.348811 2.421061 -0.002164 +v 2.278972 2.584405 -0.011801 +v 2.209132 2.747748 -0.021438 +v 2.139293 2.911092 -0.031075 +v 2.069454 3.074436 -0.040712 +v 1.999614 3.237780 -0.050349 +v 1.929775 3.401124 -0.059986 +v 1.859936 3.564467 -0.069623 +v 1.790096 3.727811 -0.079260 +v 1.720257 3.891155 -0.088897 +v 1.650417 4.054498 -0.098534 +v 1.580578 4.217842 -0.108171 +v 1.510738 4.381186 -0.117808 +v 1.440899 4.544529 -0.127445 +v 1.371060 4.707873 -0.137082 +v 1.301220 4.871216 -0.146720 +v 1.231381 5.034559 -0.156357 +v 4.328257 -1.756246 0.242797 +v 4.258417 -1.592903 0.233160 +v 4.188578 -1.429559 0.223523 +v 4.118738 -1.266215 0.213886 +v 4.048899 -1.102871 0.204249 +v 3.979060 -0.939528 0.194612 +v 3.909220 -0.776184 0.184975 +v 3.839381 -0.612840 0.175338 +v 3.769542 -0.449497 0.165701 +v 3.699702 -0.286153 0.156064 +v 3.629863 -0.122809 0.146427 +v 3.560024 0.040535 0.136790 +v 3.490184 0.203878 0.127153 +v 3.420345 0.367222 0.117516 +v 3.350505 0.530566 0.107879 +v 3.280666 0.693909 0.098242 +v 3.210827 0.857253 0.088605 +v 3.140987 1.020596 0.078968 +v 3.071148 1.183940 0.069330 +v 3.001309 1.347284 0.059694 +v 2.931469 1.510627 0.050056 +v 2.861630 1.673971 0.040419 +v 2.791791 1.837314 0.030782 +v 2.721951 2.000658 0.021145 +v 2.652112 2.164002 0.011508 +v 2.582273 2.327345 0.001871 +v 2.512433 2.490689 -0.007766 +v 2.442594 2.654033 -0.017403 +v 2.372755 2.817376 -0.027040 +v 2.302915 2.980720 -0.036677 +v 2.233076 3.144064 -0.046314 +v 2.163237 3.307407 -0.055951 +v 2.093397 3.470751 -0.065588 +v 2.023558 3.634095 -0.075225 +v 1.953718 3.797439 -0.084862 +v 1.883879 3.960782 -0.094499 +v 1.814040 4.124126 -0.104136 +v 1.744200 4.287470 -0.113773 +v 1.674361 4.450814 -0.123410 +v 1.604521 4.614157 -0.133048 +v 1.534682 4.777501 -0.142685 +v 1.464842 4.940844 -0.152322 +v 1.395003 5.104187 -0.161959 +v 4.561718 -1.849962 0.246832 +v 4.491879 -1.686618 0.237195 +v 4.422039 -1.523275 0.227558 +v 4.352200 -1.359931 0.217921 +v 4.282360 -1.196587 0.208284 +v 4.212521 -1.033243 0.198647 +v 4.142681 -0.869900 0.189010 +v 4.072842 -0.706556 0.179373 +v 4.003003 -0.543212 0.169736 +v 3.933163 -0.379869 0.160099 +v 3.863324 -0.216525 0.150462 +v 3.793484 -0.053181 0.140825 +v 3.723645 0.110162 0.131188 +v 3.653806 0.273506 0.121551 +v 3.583966 0.436850 0.111914 +v 3.514127 0.600194 0.102277 +v 3.444288 0.763537 0.092639 +v 3.374448 0.926881 0.083003 +v 3.304609 1.090224 0.073365 +v 3.234770 1.253568 0.063729 +v 3.164930 1.416912 0.054091 +v 3.095091 1.580255 0.044454 +v 3.025252 1.743599 0.034817 +v 2.955412 1.906943 0.025180 +v 2.885573 2.070286 0.015543 +v 2.815734 2.233629 0.005906 +v 2.745894 2.396973 -0.003731 +v 2.676055 2.560317 -0.013368 +v 2.606216 2.723661 -0.023005 +v 2.536376 2.887004 -0.032642 +v 2.466537 3.050348 -0.042279 +v 2.396698 3.213691 -0.051916 +v 2.326858 3.377035 -0.061553 +v 2.257019 3.540379 -0.071190 +v 2.187180 3.703722 -0.080827 +v 2.117340 3.867067 -0.090464 +v 2.047501 4.030410 -0.100101 +v 1.977661 4.193754 -0.109738 +v 1.907822 4.357098 -0.119375 +v 1.837982 4.520442 -0.129013 +v 1.768143 4.683785 -0.138650 +v 1.698304 4.847129 -0.148287 +v 1.628464 5.010472 -0.157924 +v 1.558625 5.173815 -0.167561 +v 4.795178 -1.943678 0.250867 +v 4.725339 -1.780334 0.241230 +v 4.655500 -1.616990 0.231593 +v 4.585661 -1.453647 0.221956 +v 4.515821 -1.290303 0.212319 +v 4.445982 -1.126959 0.202682 +v 4.376143 -0.963615 0.193045 +v 4.306303 -0.800272 0.183408 +v 4.236464 -0.636928 0.173771 +v 4.166625 -0.473584 0.164134 +v 4.096786 -0.310241 0.154497 +v 4.026946 -0.146897 0.144860 +v 3.957106 0.016446 0.135223 +v 3.887267 0.179790 0.125586 +v 3.817428 0.343134 0.115949 +v 3.747588 0.506478 0.106312 +v 3.677749 0.669821 0.096674 +v 3.607910 0.833165 0.087038 +v 3.538070 0.996508 0.077400 +v 3.468231 1.159852 0.067763 +v 3.398391 1.323196 0.058126 +v 3.328552 1.486539 0.048489 +v 3.258713 1.649883 0.038852 +v 3.188874 1.813227 0.029215 +v 3.119034 1.976570 0.019578 +v 3.049195 2.139914 0.009941 +v 2.979356 2.303257 0.000304 +v 2.909516 2.466601 -0.009333 +v 2.839677 2.629944 -0.018970 +v 2.769838 2.793288 -0.028607 +v 2.699998 2.956631 -0.038244 +v 2.630159 3.119976 -0.047881 +v 2.560319 3.283319 -0.057518 +v 2.490480 3.446663 -0.067155 +v 2.420641 3.610007 -0.076792 +v 2.350801 3.773350 -0.086429 +v 2.280962 3.936694 -0.096066 +v 2.211123 4.100038 -0.105703 +v 2.141283 4.263381 -0.115340 +v 2.071444 4.426725 -0.124978 +v 2.001605 4.590069 -0.134615 +v 1.931765 4.753413 -0.144252 +v 1.861926 4.916757 -0.153889 +v 1.792086 5.080100 -0.163526 +v 1.722247 5.243443 -0.173163 +v 5.028641 -2.037393 0.254902 +v 4.958801 -1.874050 0.245265 +v 4.888962 -1.710706 0.235628 +v 4.819122 -1.547362 0.225991 +v 4.749283 -1.384019 0.216354 +v 4.679443 -1.220675 0.206717 +v 4.609604 -1.057331 0.197080 +v 4.539764 -0.893988 0.187443 +v 4.469925 -0.730644 0.177806 +v 4.400086 -0.567300 0.168169 +v 4.330247 -0.403957 0.158532 +v 4.260407 -0.240613 0.148895 +v 4.190568 -0.077269 0.139258 +v 4.120728 0.086074 0.129621 +v 4.050889 0.249418 0.119984 +v 3.981050 0.412762 0.110347 +v 3.911211 0.576105 0.100709 +v 3.841371 0.739449 0.091073 +v 3.771532 0.902793 0.081435 +v 3.701692 1.066136 0.071798 +v 3.631853 1.229480 0.062161 +v 3.562014 1.392824 0.052524 +v 3.492174 1.556167 0.042887 +v 3.422335 1.719511 0.033250 +v 3.352496 1.882854 0.023613 +v 3.282656 2.046198 0.013976 +v 3.212817 2.209542 0.004339 +v 3.142978 2.372885 -0.005298 +v 3.073138 2.536229 -0.014935 +v 3.003299 2.699573 -0.024572 +v 2.933460 2.862916 -0.034209 +v 2.863620 3.026260 -0.043846 +v 2.793781 3.189603 -0.053483 +v 2.723942 3.352947 -0.063120 +v 2.654102 3.516291 -0.072757 +v 2.584263 3.679635 -0.082394 +v 2.514423 3.842979 -0.092031 +v 2.444584 4.006322 -0.101668 +v 2.374745 4.169666 -0.111305 +v 2.304905 4.333009 -0.120943 +v 2.235066 4.496353 -0.130580 +v 2.165227 4.659697 -0.140217 +v 2.095387 4.823040 -0.149854 +v 2.025548 4.986385 -0.159491 +v 1.955708 5.149727 -0.169128 +v 1.885869 5.313070 -0.178765 +v 5.262101 -2.131109 0.258937 +v 5.192262 -1.967766 0.249300 +v 5.122422 -1.804422 0.239663 +v 5.052583 -1.641078 0.230026 +v 4.982744 -1.477734 0.220389 +v 4.912905 -1.314391 0.210752 +v 4.843065 -1.151047 0.201115 +v 4.773226 -0.987703 0.191478 +v 4.703386 -0.824360 0.181841 +v 4.633547 -0.661016 0.172204 +v 4.563707 -0.497672 0.162567 +v 4.493869 -0.334329 0.152930 +v 4.424029 -0.170985 0.143293 +v 4.354190 -0.007642 0.133656 +v 4.284350 0.155702 0.124019 +v 4.214511 0.319046 0.114382 +v 4.144671 0.482390 0.104744 +v 4.074832 0.645733 0.095108 +v 4.004992 0.809077 0.085470 +v 3.935153 0.972420 0.075833 +v 3.865314 1.135764 0.066196 +v 3.795475 1.299108 0.056559 +v 3.725635 1.462451 0.046922 +v 3.655796 1.625795 0.037285 +v 3.585957 1.789138 0.027648 +v 3.516117 1.952482 0.018011 +v 3.446278 2.115826 0.008374 +v 3.376439 2.279169 -0.001263 +v 3.306599 2.442513 -0.010900 +v 3.236760 2.605856 -0.020537 +v 3.166921 2.769200 -0.030174 +v 3.097081 2.932544 -0.039811 +v 3.027242 3.095887 -0.049448 +v 2.957403 3.259231 -0.059085 +v 2.887563 3.422575 -0.068722 +v 2.817724 3.585918 -0.078359 +v 2.747885 3.749262 -0.087996 +v 2.678045 3.912606 -0.097633 +v 2.608206 4.075950 -0.107270 +v 2.538366 4.239294 -0.116908 +v 2.468527 4.402637 -0.126545 +v 2.398688 4.565981 -0.136182 +v 2.328848 4.729325 -0.145819 +v 2.259009 4.892668 -0.155456 +v 2.189170 5.056013 -0.165093 +v 2.119330 5.219355 -0.174730 +v 2.049491 5.382698 -0.184367 +v 5.495563 -2.224826 0.262972 +v 5.425723 -2.061481 0.253335 +v 5.355885 -1.898138 0.243698 +v 5.286045 -1.734794 0.234061 +v 5.216206 -1.571451 0.224424 +v 5.146366 -1.408107 0.214787 +v 5.076527 -1.244763 0.205150 +v 5.006687 -1.081420 0.195513 +v 4.936848 -0.918076 0.185876 +v 4.867008 -0.754732 0.176239 +v 4.797169 -0.591388 0.166602 +v 4.727330 -0.428045 0.156965 +v 4.657491 -0.264701 0.147328 +v 4.587651 -0.101357 0.137691 +v 4.517812 0.061986 0.128054 +v 4.447972 0.225330 0.118417 +v 4.378133 0.388674 0.108779 +v 4.308293 0.552017 0.099143 +v 4.238455 0.715361 0.089505 +v 4.168615 0.878705 0.079868 +v 4.098776 1.042048 0.070231 +v 4.028936 1.205392 0.060594 +v 3.959097 1.368735 0.050957 +v 3.889257 1.532079 0.041320 +v 3.819418 1.695423 0.031683 +v 3.749579 1.858766 0.022046 +v 3.679739 2.022110 0.012409 +v 3.609900 2.185454 0.002772 +v 3.540061 2.348797 -0.006865 +v 3.470222 2.512141 -0.016502 +v 3.400382 2.675484 -0.026139 +v 3.330543 2.838828 -0.035776 +v 3.260704 3.002172 -0.045413 +v 3.190864 3.165515 -0.055050 +v 3.121025 3.328859 -0.064687 +v 3.051185 3.492203 -0.074324 +v 2.981346 3.655546 -0.083961 +v 2.911507 3.818890 -0.093598 +v 2.841667 3.982234 -0.103236 +v 2.771828 4.145578 -0.112873 +v 2.701989 4.308921 -0.122510 +v 2.632149 4.472265 -0.132147 +v 2.562310 4.635609 -0.141784 +v 2.492471 4.798953 -0.151421 +v 2.422631 4.962296 -0.161058 +v 2.352792 5.125640 -0.170695 +v 2.282953 5.288983 -0.180332 +v 2.213113 5.452327 -0.189969 +v 5.729023 -2.318541 0.267007 +v 5.659184 -2.155197 0.257370 +v 5.589345 -1.991854 0.247733 +v 5.519506 -1.828510 0.238096 +v 5.449666 -1.665166 0.228459 +v 5.379827 -1.501822 0.218822 +v 5.309987 -1.338479 0.209185 +v 5.240148 -1.175135 0.199548 +v 5.170308 -1.011791 0.189911 +v 5.100470 -0.848448 0.180274 +v 5.030630 -0.685104 0.170637 +v 4.960791 -0.521760 0.161000 +v 4.890951 -0.358416 0.151363 +v 4.821112 -0.195073 0.141726 +v 4.751272 -0.031729 0.132089 +v 4.681433 0.131614 0.122452 +v 4.611594 0.294958 0.112814 +v 4.541755 0.458302 0.103178 +v 4.471915 0.621645 0.093540 +v 4.402076 0.784989 0.083903 +v 4.332236 0.948332 0.074266 +v 4.262397 1.111676 0.064629 +v 4.192557 1.275020 0.054992 +v 4.122719 1.438363 0.045355 +v 4.052879 1.601707 0.035718 +v 3.983040 1.765051 0.026081 +v 3.913200 1.928394 0.016444 +v 3.843361 2.091738 0.006807 +v 3.773521 2.255081 -0.002830 +v 3.703682 2.418425 -0.012467 +v 3.633843 2.581769 -0.022104 +v 3.564003 2.745112 -0.031741 +v 3.494164 2.908456 -0.041378 +v 3.424325 3.071799 -0.051015 +v 3.354486 3.235143 -0.060652 +v 3.284646 3.398487 -0.070289 +v 3.214807 3.561830 -0.079926 +v 3.144968 3.725174 -0.089563 +v 3.075128 3.888518 -0.099200 +v 3.005289 4.051861 -0.108838 +v 2.935449 4.215206 -0.118475 +v 2.865610 4.378549 -0.128112 +v 2.795771 4.541893 -0.137749 +v 2.725931 4.705236 -0.147386 +v 2.656092 4.868580 -0.157023 +v 2.586253 5.031924 -0.166660 +v 2.516413 5.195268 -0.176297 +v 2.446574 5.358611 -0.185934 +v 2.376735 5.521955 -0.195571 +v -2.218616 -5.893647 0.551145 +v -2.054993 -5.824019 0.545543 +v -2.288455 -5.730304 0.541508 +v -1.891371 -5.754392 0.539941 +v -2.124833 -5.660676 0.535906 +v -2.358294 -5.566959 0.531871 +v -1.727749 -5.684764 0.534339 +v -1.961210 -5.591048 0.530304 +v -2.194672 -5.497332 0.526269 +v -2.428133 -5.403617 0.522234 +v -1.564127 -5.615136 0.528737 +v -1.797588 -5.521420 0.524702 +v -2.031050 -5.427704 0.520667 +v -2.264511 -5.333989 0.516632 +v -2.497972 -5.240272 0.512597 +v -1.400505 -5.545508 0.523135 +v -1.633966 -5.451793 0.519100 +v -1.867428 -5.358076 0.515065 +v -2.100889 -5.264361 0.511030 +v -2.334351 -5.170644 0.506995 +v -2.567812 -5.076930 0.502960 +v -1.236883 -5.475881 0.517533 +v -1.470344 -5.382164 0.513498 +v -1.703806 -5.288448 0.509463 +v -1.937267 -5.194733 0.505428 +v -2.170728 -5.101017 0.501393 +v -2.404190 -5.007302 0.497358 +v -2.637651 -4.913586 0.493323 +v -1.073261 -5.406252 0.511930 +v -1.306722 -5.312536 0.507895 +v -1.540184 -5.218821 0.503860 +v -1.773645 -5.125105 0.499825 +v -2.007106 -5.031389 0.495791 +v -2.240568 -4.937673 0.491756 +v -2.474029 -4.843958 0.487721 +v -2.707490 -4.750243 0.483686 +v -0.909639 -5.336624 0.506329 +v -1.143100 -5.242908 0.502294 +v -1.376562 -5.149193 0.498259 +v -1.610023 -5.055477 0.494224 +v -1.843484 -4.961761 0.490189 +v -2.076945 -4.868045 0.486154 +v -2.310407 -4.774330 0.482119 +v -2.543869 -4.680614 0.478084 +v -2.777330 -4.586899 0.474049 +v -0.746017 -5.266996 0.500726 +v -0.979478 -5.173281 0.496691 +v -1.212940 -5.079565 0.492656 +v -1.446401 -4.985850 0.488621 +v -1.679862 -4.892134 0.484586 +v -1.913324 -4.798418 0.480551 +v -2.146785 -4.704702 0.476516 +v -2.380247 -4.610986 0.472481 +v -2.613708 -4.517271 0.468446 +v -2.847169 -4.423555 0.464411 +v -0.582395 -5.197369 0.495124 +v -0.815856 -5.103653 0.491089 +v -1.049317 -5.009937 0.487054 +v -1.282779 -4.916221 0.483019 +v -1.516240 -4.822505 0.478984 +v -1.749701 -4.728789 0.474949 +v -1.983163 -4.635074 0.470914 +v -2.216624 -4.541358 0.466880 +v -2.450086 -4.447642 0.462845 +v -2.683547 -4.353927 0.458810 +v -2.917009 -4.260211 0.454775 +v -0.418772 -5.127741 0.489522 +v -0.652234 -5.034025 0.485487 +v -0.885695 -4.940310 0.481452 +v -1.119157 -4.846593 0.477417 +v -1.352618 -4.752878 0.473382 +v -1.586080 -4.659162 0.469347 +v -1.819541 -4.565446 0.465312 +v -2.053002 -4.471730 0.461277 +v -2.286463 -4.378014 0.457242 +v -2.519925 -4.284298 0.453207 +v -2.753386 -4.190583 0.449172 +v -2.986848 -4.096868 0.445138 +v -0.255151 -5.058113 0.483920 +v -0.488612 -4.964397 0.479885 +v -0.722073 -4.870682 0.475850 +v -0.955535 -4.776966 0.471815 +v -1.188996 -4.683250 0.467780 +v -1.422458 -4.589534 0.463745 +v -1.655919 -4.495819 0.459710 +v -1.889380 -4.402102 0.455675 +v -2.122842 -4.308386 0.451640 +v -2.356303 -4.214671 0.447605 +v -2.589765 -4.120955 0.443570 +v -2.823226 -4.027239 0.439535 +v -3.056687 -3.933524 0.435500 +v -0.091529 -4.988485 0.478318 +v -0.324990 -4.894770 0.474283 +v -0.558451 -4.801054 0.470248 +v -0.791913 -4.707338 0.466213 +v -1.025374 -4.613622 0.462178 +v -1.258836 -4.519907 0.458143 +v -1.492297 -4.426191 0.454108 +v -1.725758 -4.332475 0.450073 +v -1.959220 -4.238759 0.446038 +v -2.192681 -4.145043 0.442003 +v -2.426142 -4.051328 0.437968 +v -2.659604 -3.957612 0.433933 +v -2.893065 -3.863896 0.429899 +v -3.126527 -3.770180 0.425864 +v 0.072093 -4.918858 0.472716 +v -0.161368 -4.825142 0.468681 +v -0.394830 -4.731426 0.464646 +v -0.628291 -4.637710 0.460611 +v -0.861752 -4.543994 0.456576 +v -1.095214 -4.450279 0.452541 +v -1.328675 -4.356562 0.448506 +v -1.562136 -4.262847 0.444471 +v -1.795598 -4.169131 0.440436 +v -2.029059 -4.075416 0.436401 +v -2.262521 -3.981699 0.432366 +v -2.495982 -3.887984 0.428331 +v -2.729443 -3.794269 0.424296 +v -2.962905 -3.700552 0.420261 +v -3.196366 -3.606837 0.416226 +v 0.235715 -4.849230 0.467114 +v 0.002254 -4.755514 0.463079 +v -0.231208 -4.661798 0.459044 +v -0.464669 -4.568082 0.455009 +v -0.698130 -4.474367 0.450974 +v -0.931592 -4.380651 0.446939 +v -1.165053 -4.286934 0.442904 +v -1.398514 -4.193219 0.438869 +v -1.631976 -4.099504 0.434834 +v -1.865437 -4.005788 0.430799 +v -2.098898 -3.912072 0.426764 +v -2.332360 -3.818356 0.422729 +v -2.565821 -3.724640 0.418694 +v -2.799283 -3.630925 0.414659 +v -3.032744 -3.537209 0.410624 +v -3.266205 -3.443493 0.406589 +v 0.399337 -4.779602 0.461512 +v 0.165876 -4.685886 0.457477 +v -0.067586 -4.592171 0.453442 +v -0.301047 -4.498455 0.449407 +v -0.534508 -4.404739 0.445372 +v -0.767970 -4.311023 0.441337 +v -1.001431 -4.217307 0.437302 +v -1.234892 -4.123591 0.433267 +v -1.468354 -4.029876 0.429232 +v -1.701815 -3.936160 0.425197 +v -1.935277 -3.842444 0.421162 +v -2.168738 -3.748729 0.417127 +v -2.402199 -3.655013 0.413092 +v -2.635661 -3.561297 0.409057 +v -2.869122 -3.467582 0.405022 +v -3.102583 -3.373866 0.400987 +v -3.336045 -3.280150 0.396952 +v 0.562959 -4.709974 0.455910 +v 0.329498 -4.616258 0.451875 +v 0.096036 -4.522543 0.447840 +v -0.137425 -4.428827 0.443805 +v -0.370887 -4.335111 0.439770 +v -0.604348 -4.241395 0.435735 +v -0.837809 -4.147679 0.431700 +v -1.071271 -4.053964 0.427665 +v -1.304732 -3.960248 0.423630 +v -1.538193 -3.866532 0.419595 +v -1.771655 -3.772816 0.415560 +v -2.005116 -3.679101 0.411525 +v -2.238577 -3.585385 0.407490 +v -2.472039 -3.491669 0.403455 +v -2.705500 -3.397954 0.399420 +v -2.938962 -3.304238 0.395385 +v -3.172423 -3.210522 0.391350 +v -3.405884 -3.116806 0.387315 +v 0.726581 -4.640347 0.450308 +v 0.493120 -4.546630 0.446273 +v 0.259658 -4.452915 0.442238 +v 0.026197 -4.359199 0.438203 +v -0.207264 -4.265483 0.434168 +v -0.440726 -4.171768 0.430133 +v -0.674187 -4.078052 0.426098 +v -0.907648 -3.984335 0.422063 +v -1.141110 -3.890620 0.418028 +v -1.374571 -3.796905 0.413993 +v -1.608033 -3.703188 0.409958 +v -1.841494 -3.609473 0.405923 +v -2.074955 -3.515757 0.401888 +v -2.308417 -3.422041 0.397853 +v -2.541878 -3.328326 0.393818 +v -2.775339 -3.234610 0.389783 +v -3.008801 -3.140894 0.385748 +v -3.242262 -3.047179 0.381713 +v -3.475723 -2.953463 0.377678 +v 0.890203 -4.570719 0.444706 +v 0.656742 -4.477002 0.440671 +v 0.423280 -4.383287 0.436636 +v 0.189819 -4.289571 0.432601 +v -0.043642 -4.195856 0.428566 +v -0.277104 -4.102139 0.424531 +v -0.510565 -4.008424 0.420496 +v -0.744026 -3.914708 0.416461 +v -0.977488 -3.820992 0.412426 +v -1.210949 -3.727276 0.408391 +v -1.444410 -3.633561 0.404356 +v -1.677872 -3.539845 0.400321 +v -1.911333 -3.446129 0.396286 +v -2.144794 -3.352414 0.392251 +v -2.378256 -3.258698 0.388216 +v -2.611717 -3.164982 0.384181 +v -2.845179 -3.071266 0.380146 +v -3.078640 -2.977550 0.376111 +v -3.312101 -2.883835 0.372076 +v -3.545563 -2.790119 0.368041 +v 1.053825 -4.501091 0.439104 +v 0.820364 -4.407374 0.435069 +v 0.586903 -4.313660 0.431034 +v 0.353441 -4.219944 0.426999 +v 0.119980 -4.126228 0.422964 +v -0.113482 -4.032512 0.418929 +v -0.346943 -3.938796 0.414894 +v -0.580405 -3.845080 0.410859 +v -0.813866 -3.751364 0.406824 +v -1.047327 -3.657649 0.402789 +v -1.280789 -3.563933 0.398754 +v -1.514250 -3.470217 0.394719 +v -1.747711 -3.376501 0.390684 +v -1.981173 -3.282785 0.386649 +v -2.214634 -3.189070 0.382614 +v -2.448095 -3.095354 0.378579 +v -2.681557 -3.001638 0.374544 +v -2.915018 -2.907923 0.370509 +v -3.148480 -2.814207 0.366474 +v -3.381941 -2.720491 0.362439 +v -3.615402 -2.626775 0.358404 +v 1.217447 -4.431463 0.433502 +v 0.983986 -4.337747 0.429467 +v 0.750524 -4.244032 0.425432 +v 0.517063 -4.150316 0.421397 +v 0.283602 -4.056600 0.417362 +v 0.050140 -3.962884 0.413327 +v -0.183321 -3.869168 0.409292 +v -0.416783 -3.775452 0.405257 +v -0.650244 -3.681736 0.401222 +v -0.883705 -3.588021 0.397187 +v -1.117167 -3.494305 0.393152 +v -1.350628 -3.400589 0.389117 +v -1.584089 -3.306873 0.385082 +v -1.817551 -3.213157 0.381047 +v -2.051012 -3.119442 0.377012 +v -2.284473 -3.025727 0.372977 +v -2.517935 -2.932010 0.368942 +v -2.751396 -2.838295 0.364907 +v -2.984857 -2.744579 0.360872 +v -3.218319 -2.650863 0.356837 +v -3.451780 -2.557148 0.352802 +v -3.685241 -2.463431 0.348767 +v 1.381069 -4.361835 0.427900 +v 1.147608 -4.268119 0.423865 +v 0.914147 -4.174404 0.419830 +v 0.680685 -4.080688 0.415795 +v 0.447224 -3.986972 0.411760 +v 0.213762 -3.893256 0.407725 +v -0.019699 -3.799540 0.403690 +v -0.253161 -3.705824 0.399655 +v -0.486622 -3.612109 0.395620 +v -0.720084 -3.518393 0.391585 +v -0.953545 -3.424677 0.387550 +v -1.187006 -3.330961 0.383515 +v -1.420467 -3.237246 0.379480 +v -1.653929 -3.143530 0.375445 +v -1.887390 -3.049814 0.371410 +v -2.120852 -2.956098 0.367375 +v -2.354313 -2.862382 0.363340 +v -2.587774 -2.768667 0.359305 +v -2.821235 -2.674951 0.355270 +v -3.054697 -2.581235 0.351235 +v -3.288158 -2.487519 0.347200 +v -3.521620 -2.393804 0.343165 +v -3.755081 -2.300088 0.339130 +v 1.544691 -4.292208 0.422298 +v 1.311230 -4.198491 0.418263 +v 1.077768 -4.104776 0.414228 +v 0.844307 -4.011060 0.410193 +v 0.610846 -3.917344 0.406158 +v 0.377384 -3.823628 0.402123 +v 0.143923 -3.729912 0.398088 +v -0.089539 -3.636197 0.394053 +v -0.323000 -3.542481 0.390018 +v -0.556461 -3.448765 0.385983 +v -0.789923 -3.355049 0.381948 +v -1.023384 -3.261333 0.377913 +v -1.256845 -3.167618 0.373878 +v -1.490307 -3.073902 0.369843 +v -1.723768 -2.980186 0.365808 +v -1.957229 -2.886470 0.361773 +v -2.190691 -2.792754 0.357738 +v -2.424152 -2.699039 0.353703 +v -2.657614 -2.605323 0.349668 +v -2.891075 -2.511607 0.345633 +v -3.124536 -2.417892 0.341598 +v -3.357998 -2.324176 0.337563 +v -3.591459 -2.230460 0.333528 +v -3.824920 -2.136744 0.329493 +v 1.708313 -4.222580 0.416696 +v 1.474852 -4.128863 0.412661 +v 1.241390 -4.035148 0.408626 +v 1.007929 -3.941432 0.404591 +v 0.774468 -3.847716 0.400556 +v 0.541006 -3.754000 0.396521 +v 0.307545 -3.660285 0.392486 +v 0.074084 -3.566569 0.388451 +v -0.159378 -3.472853 0.384416 +v -0.392839 -3.379137 0.380381 +v -0.626301 -3.285421 0.376346 +v -0.859762 -3.191705 0.372311 +v -1.093223 -3.097989 0.368276 +v -1.326685 -3.004274 0.364241 +v -1.560146 -2.910558 0.360206 +v -1.793607 -2.816843 0.356171 +v -2.027069 -2.723127 0.352136 +v -2.260530 -2.629411 0.348101 +v -2.493991 -2.535695 0.344066 +v -2.727453 -2.441979 0.340031 +v -2.960914 -2.348264 0.335996 +v -3.194375 -2.254548 0.331961 +v -3.427837 -2.160832 0.327926 +v -3.661298 -2.067116 0.323891 +v -3.894759 -1.973400 0.319856 +v 1.871935 -4.152952 0.411094 +v 1.638474 -4.059236 0.407059 +v 1.405012 -3.965520 0.403024 +v 1.171551 -3.871805 0.398989 +v 0.938090 -3.778089 0.394954 +v 0.704628 -3.684372 0.390919 +v 0.471167 -3.590657 0.386884 +v 0.237706 -3.496941 0.382849 +v 0.004244 -3.403225 0.378814 +v -0.229217 -3.309509 0.374779 +v -0.462679 -3.215794 0.370744 +v -0.696140 -3.122078 0.366709 +v -0.929602 -3.028362 0.362674 +v -1.163063 -2.934646 0.358639 +v -1.396524 -2.840931 0.354604 +v -1.629985 -2.747215 0.350569 +v -1.863447 -2.653499 0.346534 +v -2.096908 -2.559783 0.342499 +v -2.330369 -2.466068 0.338464 +v -2.563831 -2.372352 0.334429 +v -2.797292 -2.278636 0.330394 +v -3.030753 -2.184920 0.326359 +v -3.264215 -2.091204 0.322324 +v -3.497676 -1.997488 0.318289 +v -3.731138 -1.903773 0.314254 +v -3.964599 -1.810057 0.310219 +v 2.035557 -4.083324 0.405492 +v 1.802096 -3.989609 0.401457 +v 1.568634 -3.895892 0.397422 +v 1.335173 -3.802177 0.393387 +v 1.101712 -3.708461 0.389352 +v 0.868250 -3.614745 0.385317 +v 0.634789 -3.521029 0.381282 +v 0.401328 -3.427313 0.377247 +v 0.167866 -3.333597 0.373212 +v -0.065595 -3.239882 0.369177 +v -0.299057 -3.146165 0.365142 +v -0.532518 -3.052450 0.361107 +v -0.765979 -2.958734 0.357072 +v -0.999441 -2.865018 0.353036 +v -1.232902 -2.771303 0.349001 +v -1.466363 -2.677587 0.344966 +v -1.699825 -2.583871 0.340932 +v -1.933286 -2.490155 0.336897 +v -2.166747 -2.396440 0.332862 +v -2.400209 -2.302724 0.328827 +v -2.633670 -2.209008 0.324792 +v -2.867131 -2.115292 0.320757 +v -3.100593 -2.021576 0.316722 +v -3.334054 -1.927860 0.312687 +v -3.567516 -1.834145 0.308652 +v -3.800977 -1.740429 0.304617 +v -4.034438 -1.646713 0.300582 +v 2.199179 -4.013697 0.399889 +v 1.965718 -3.919981 0.395854 +v 1.732256 -3.826265 0.391819 +v 1.498795 -3.732549 0.387784 +v 1.265334 -3.638833 0.383749 +v 1.031872 -3.545117 0.379714 +v 0.798411 -3.451401 0.375679 +v 0.564950 -3.357686 0.371644 +v 0.331488 -3.263969 0.367610 +v 0.098027 -3.170254 0.363575 +v -0.135435 -3.076538 0.359540 +v -0.368896 -2.982822 0.355505 +v -0.602357 -2.889106 0.351470 +v -0.835819 -2.795390 0.347435 +v -1.069280 -2.701675 0.343400 +v -1.302741 -2.607959 0.339365 +v -1.536203 -2.514243 0.335330 +v -1.769664 -2.420527 0.331295 +v -2.003125 -2.326812 0.327260 +v -2.236587 -2.233096 0.323225 +v -2.470048 -2.139380 0.319190 +v -2.703509 -2.045664 0.315155 +v -2.936971 -1.951948 0.311120 +v -3.170432 -1.858232 0.307085 +v -3.403893 -1.764517 0.303050 +v -3.637355 -1.670801 0.299015 +v -3.870816 -1.577085 0.294980 +v -4.104278 -1.483369 0.290945 +v 2.362801 -3.944069 0.394287 +v 2.129340 -3.850353 0.390253 +v 1.895878 -3.756637 0.386218 +v 1.662417 -3.662921 0.382183 +v 1.428956 -3.569205 0.378148 +v 1.195494 -3.475489 0.374113 +v 0.962033 -3.381773 0.370078 +v 0.728572 -3.288058 0.366043 +v 0.495110 -3.194342 0.362008 +v 0.261649 -3.100626 0.357973 +v 0.028187 -3.006910 0.353938 +v -0.205274 -2.913194 0.349903 +v -0.438735 -2.819478 0.345867 +v -0.672197 -2.725763 0.341832 +v -0.905658 -2.632047 0.337797 +v -1.139120 -2.538331 0.333762 +v -1.372581 -2.444616 0.329727 +v -1.606042 -2.350899 0.325692 +v -1.839504 -2.257183 0.321657 +v -2.072965 -2.163467 0.317622 +v -2.306426 -2.069752 0.313587 +v -2.539887 -1.976036 0.309552 +v -2.773349 -1.882320 0.305517 +v -3.006810 -1.788605 0.301483 +v -3.240271 -1.694889 0.297448 +v -3.473733 -1.601173 0.293413 +v -3.707194 -1.507457 0.289378 +v -3.940656 -1.413742 0.285343 +v -4.174116 -1.320026 0.281308 +v 2.526423 -3.874441 0.388685 +v 2.292962 -3.780725 0.384650 +v 2.059500 -3.687009 0.380615 +v 1.826039 -3.593294 0.376580 +v 1.592578 -3.499577 0.372545 +v 1.359116 -3.405861 0.368510 +v 1.125655 -3.312146 0.364475 +v 0.892194 -3.218430 0.360440 +v 0.658732 -3.124714 0.356405 +v 0.425271 -3.030998 0.352371 +v 0.191809 -2.937282 0.348336 +v -0.041652 -2.843566 0.344300 +v -0.275113 -2.749850 0.340265 +v -0.508575 -2.656135 0.336230 +v -0.742036 -2.562419 0.332195 +v -0.975497 -2.468703 0.328160 +v -1.208959 -2.374988 0.324125 +v -1.442420 -2.281271 0.320090 +v -1.675881 -2.187556 0.316055 +v -1.909343 -2.093840 0.312021 +v -2.142804 -2.000124 0.307986 +v -2.376266 -1.906408 0.303951 +v -2.609727 -1.812692 0.299916 +v -2.843188 -1.718977 0.295881 +v -3.076649 -1.625261 0.291846 +v -3.310111 -1.531545 0.287811 +v -3.543572 -1.437829 0.283776 +v -3.777034 -1.344114 0.279741 +v -4.010494 -1.250398 0.275706 +v -4.243956 -1.156682 0.271671 +v 2.690045 -3.804814 0.383083 +v 2.456584 -3.711097 0.379048 +v 2.223123 -3.617381 0.375013 +v 1.989661 -3.523665 0.370978 +v 1.756200 -3.429949 0.366943 +v 1.522738 -3.336234 0.362908 +v 1.289277 -3.242518 0.358873 +v 1.055816 -3.148802 0.354838 +v 0.822354 -3.055086 0.350803 +v 0.588893 -2.961370 0.346768 +v 0.355431 -2.867654 0.342733 +v 0.121970 -2.773938 0.338698 +v -0.111491 -2.680223 0.334663 +v -0.344953 -2.586506 0.330628 +v -0.578414 -2.492791 0.326593 +v -0.811875 -2.399075 0.322558 +v -1.045337 -2.305359 0.318523 +v -1.278798 -2.211644 0.314488 +v -1.512259 -2.117928 0.310453 +v -1.745721 -2.024212 0.306418 +v -1.979182 -1.930496 0.302383 +v -2.212643 -1.836780 0.298348 +v -2.446105 -1.743064 0.294313 +v -2.679566 -1.649349 0.290278 +v -2.913028 -1.555633 0.286243 +v -3.146489 -1.461917 0.282208 +v -3.379950 -1.368201 0.278173 +v -3.613411 -1.274486 0.274138 +v -3.846873 -1.180770 0.270103 +v -4.080334 -1.087054 0.266068 +v -4.313795 -0.993338 0.262033 +v 2.853667 -3.735186 0.377481 +v 2.620206 -3.641469 0.373446 +v 2.386744 -3.547754 0.369411 +v 2.153283 -3.454038 0.365376 +v 1.919822 -3.360322 0.361341 +v 1.686360 -3.266606 0.357306 +v 1.452899 -3.172890 0.353271 +v 1.219437 -3.079174 0.349236 +v 0.985976 -2.985458 0.345201 +v 0.752515 -2.891742 0.341166 +v 0.519053 -2.798027 0.337131 +v 0.285592 -2.704310 0.333096 +v 0.052131 -2.610595 0.329061 +v -0.181331 -2.516879 0.325026 +v -0.414792 -2.423163 0.320991 +v -0.648253 -2.329447 0.316956 +v -0.881715 -2.235731 0.312921 +v -1.115176 -2.142015 0.308886 +v -1.348638 -2.048300 0.304851 +v -1.582099 -1.954584 0.300816 +v -1.815560 -1.860868 0.296781 +v -2.049021 -1.767152 0.292746 +v -2.282483 -1.673437 0.288711 +v -2.515944 -1.579721 0.284676 +v -2.749406 -1.486005 0.280641 +v -2.982867 -1.392290 0.276606 +v -3.216328 -1.298574 0.272572 +v -3.449790 -1.204858 0.268537 +v -3.683251 -1.111142 0.264502 +v -3.916712 -1.017426 0.260467 +v -4.150173 -0.923711 0.256432 +v -4.383635 -0.829995 0.252397 +v 3.017289 -3.665558 0.371879 +v 2.783828 -3.571841 0.367844 +v 2.550366 -3.478126 0.363809 +v 2.316905 -3.384410 0.359774 +v 2.083444 -3.290694 0.355739 +v 1.849982 -3.196978 0.351704 +v 1.616521 -3.103262 0.347669 +v 1.383060 -3.009546 0.343634 +v 1.149598 -2.915830 0.339599 +v 0.916137 -2.822114 0.335564 +v 0.682675 -2.728399 0.331529 +v 0.449214 -2.634683 0.327494 +v 0.215753 -2.540967 0.323459 +v -0.017709 -2.447251 0.319424 +v -0.251170 -2.353535 0.315389 +v -0.484631 -2.259820 0.311354 +v -0.718093 -2.166104 0.307319 +v -0.951554 -2.072388 0.303284 +v -1.185016 -1.978672 0.299249 +v -1.418477 -1.884956 0.295214 +v -1.651938 -1.791241 0.291179 +v -1.885400 -1.697525 0.287144 +v -2.118861 -1.603809 0.283109 +v -2.352322 -1.510093 0.279074 +v -2.585784 -1.416377 0.275039 +v -2.819245 -1.322662 0.271004 +v -3.052706 -1.228946 0.266969 +v -3.286168 -1.135230 0.262934 +v -3.519629 -1.041514 0.258899 +v -3.753090 -0.947798 0.254864 +v -3.986552 -0.854083 0.250829 +v -4.220013 -0.760367 0.246794 +v -4.453474 -0.666651 0.242759 +v 3.180911 -3.595930 0.366277 +v 2.947450 -3.502214 0.362242 +v 2.713988 -3.408498 0.358207 +v 2.480527 -3.314782 0.354172 +v 2.247066 -3.221066 0.350137 +v 2.013604 -3.127350 0.346102 +v 1.780143 -3.033635 0.342067 +v 1.546681 -2.939919 0.338032 +v 1.313220 -2.846202 0.333997 +v 1.079759 -2.752487 0.329962 +v 0.846297 -2.658771 0.325927 +v 0.612836 -2.565055 0.321892 +v 0.379375 -2.471339 0.317857 +v 0.145913 -2.377623 0.313822 +v -0.087548 -2.283908 0.309787 +v -0.321009 -2.190192 0.305752 +v -0.554471 -2.096476 0.301717 +v -0.787932 -2.002760 0.297682 +v -1.021394 -1.909044 0.293647 +v -1.254855 -1.815328 0.289612 +v -1.488316 -1.721613 0.285577 +v -1.721778 -1.627897 0.281542 +v -1.955239 -1.534181 0.277507 +v -2.188700 -1.440465 0.273472 +v -2.422162 -1.346750 0.269437 +v -2.655623 -1.253034 0.265402 +v -2.889084 -1.159318 0.261367 +v -3.122546 -1.065602 0.257332 +v -3.356007 -0.971886 0.253297 +v -3.589468 -0.878170 0.249262 +v -3.822929 -0.784455 0.245227 +v -4.056391 -0.690739 0.241192 +v -4.289852 -0.597024 0.237157 +v -4.523314 -0.503308 0.233122 +v 3.344533 -3.526303 0.360675 +v 3.111072 -3.432586 0.356640 +v 2.877610 -3.338870 0.352605 +v 2.644149 -3.245154 0.348570 +v 2.410687 -3.151438 0.344535 +v 2.177226 -3.057723 0.340500 +v 1.943765 -2.964007 0.336465 +v 1.710303 -2.870291 0.332430 +v 1.476842 -2.776575 0.328395 +v 1.243381 -2.682859 0.324360 +v 1.009919 -2.589143 0.320325 +v 0.776458 -2.495427 0.316290 +v 0.542997 -2.401711 0.312255 +v 0.309535 -2.307995 0.308220 +v 0.076074 -2.214280 0.304185 +v -0.157387 -2.120564 0.300150 +v -0.390849 -2.026848 0.296115 +v -0.624310 -1.933132 0.292080 +v -0.857772 -1.839417 0.288045 +v -1.091233 -1.745700 0.284010 +v -1.324694 -1.651985 0.279975 +v -1.558156 -1.558269 0.275940 +v -1.791617 -1.464553 0.271905 +v -2.025078 -1.370837 0.267870 +v -2.258540 -1.277122 0.263835 +v -2.492001 -1.183406 0.259800 +v -2.725462 -1.089690 0.255765 +v -2.958924 -0.995974 0.251730 +v -3.192385 -0.902259 0.247695 +v -3.425846 -0.808543 0.243660 +v -3.659307 -0.714827 0.239625 +v -3.892769 -0.621111 0.235590 +v -4.126230 -0.527396 0.231555 +v -4.359692 -0.433680 0.227520 +v -4.593153 -0.339964 0.223485 +v 3.508155 -3.456674 0.355073 +v 3.274693 -3.362958 0.351038 +v 3.041232 -3.269243 0.347003 +v 2.807771 -3.175527 0.342968 +v 2.574309 -3.081810 0.338933 +v 2.340848 -2.988095 0.334898 +v 2.107387 -2.894379 0.330863 +v 1.873925 -2.800663 0.326828 +v 1.640464 -2.706947 0.322793 +v 1.407002 -2.613231 0.318758 +v 1.173541 -2.519516 0.314723 +v 0.940080 -2.425799 0.310688 +v 0.706618 -2.332083 0.306653 +v 0.473157 -2.238368 0.302618 +v 0.239696 -2.144652 0.298583 +v 0.006234 -2.050936 0.294548 +v -0.227227 -1.957220 0.290513 +v -0.460688 -1.863505 0.286478 +v -0.694150 -1.769789 0.282443 +v -0.927611 -1.676073 0.278408 +v -1.161072 -1.582357 0.274373 +v -1.394534 -1.488641 0.270338 +v -1.627995 -1.394925 0.266303 +v -1.861456 -1.301210 0.262268 +v -2.094918 -1.207494 0.258233 +v -2.328379 -1.113778 0.254198 +v -2.561840 -1.020062 0.250163 +v -2.795302 -0.926347 0.246128 +v -3.028763 -0.832631 0.242093 +v -3.262224 -0.738915 0.238058 +v -3.495686 -0.645199 0.234023 +v -3.729147 -0.551483 0.229988 +v -3.962608 -0.457768 0.225953 +v -4.196070 -0.364052 0.221918 +v -4.429531 -0.270336 0.217883 +v -4.662992 -0.176620 0.213848 +v 3.671777 -3.387047 0.349471 +v 3.438316 -3.293330 0.345436 +v 3.204854 -3.199615 0.341401 +v 2.971393 -3.105899 0.337366 +v 2.737931 -3.012183 0.333331 +v 2.504470 -2.918467 0.329296 +v 2.271009 -2.824751 0.325261 +v 2.037547 -2.731035 0.321226 +v 1.804086 -2.637319 0.317191 +v 1.570624 -2.543603 0.313156 +v 1.337163 -2.449888 0.309121 +v 1.103702 -2.356172 0.305086 +v 0.870240 -2.262455 0.301051 +v 0.636779 -2.168740 0.297016 +v 0.403318 -2.075024 0.292981 +v 0.169856 -1.981308 0.288946 +v -0.063605 -1.887592 0.284911 +v -0.297066 -1.793877 0.280876 +v -0.530528 -1.700161 0.276841 +v -0.763989 -1.606445 0.272806 +v -0.997450 -1.512729 0.268771 +v -1.230912 -1.419013 0.264736 +v -1.464373 -1.325298 0.260701 +v -1.697834 -1.231582 0.256666 +v -1.931295 -1.137866 0.252631 +v -2.164757 -1.044150 0.248596 +v -2.398218 -0.950434 0.244561 +v -2.631680 -0.856719 0.240526 +v -2.865141 -0.763003 0.236491 +v -3.098603 -0.669287 0.232456 +v -3.332064 -0.575571 0.228421 +v -3.565525 -0.481856 0.224386 +v -3.798986 -0.388140 0.220351 +v -4.032447 -0.294424 0.216316 +v -4.265909 -0.200708 0.212281 +v -4.499370 -0.106993 0.208246 +v -4.732831 -0.013277 0.204211 +v 3.835399 -3.317418 0.343869 +v 3.601938 -3.223703 0.339834 +v 3.368476 -3.129987 0.335799 +v 3.135015 -3.036271 0.331764 +v 2.901554 -2.942555 0.327729 +v 2.668092 -2.848839 0.323694 +v 2.434631 -2.755123 0.319659 +v 2.201169 -2.661407 0.315624 +v 1.967708 -2.567691 0.311589 +v 1.734246 -2.473976 0.307554 +v 1.500785 -2.380260 0.303519 +v 1.267324 -2.286544 0.299484 +v 1.033862 -2.192828 0.295449 +v 0.800401 -2.099112 0.291414 +v 0.566940 -2.005396 0.287379 +v 0.333478 -1.911680 0.283344 +v 0.100017 -1.817965 0.279309 +v -0.133444 -1.724249 0.275274 +v -0.366906 -1.630533 0.271239 +v -0.600367 -1.536817 0.267204 +v -0.833828 -1.443102 0.263169 +v -1.067290 -1.349386 0.259134 +v -1.300751 -1.255670 0.255099 +v -1.534212 -1.161954 0.251064 +v -1.767674 -1.068238 0.247029 +v -2.001135 -0.974522 0.242994 +v -2.234596 -0.880807 0.238959 +v -2.468058 -0.787091 0.234924 +v -2.701519 -0.693375 0.230889 +v -2.934980 -0.599659 0.226854 +v -3.168442 -0.505944 0.222819 +v -3.401903 -0.412228 0.218784 +v -3.635364 -0.318512 0.214749 +v -3.868825 -0.224796 0.210714 +v -4.102286 -0.131081 0.206679 +v -4.335748 -0.037365 0.202644 +v -4.569209 0.056351 0.198609 +v -4.802670 0.150067 0.194574 +v 3.999021 -3.247791 0.338267 +v 3.765560 -3.154075 0.334232 +v 3.532098 -3.060359 0.330197 +v 3.298637 -2.966643 0.326162 +v 3.065176 -2.872927 0.322127 +v 2.831714 -2.779212 0.318092 +v 2.598253 -2.685495 0.314057 +v 2.364791 -2.591780 0.310022 +v 2.131330 -2.498064 0.305987 +v 1.897868 -2.404348 0.301952 +v 1.664407 -2.310632 0.297917 +v 1.430946 -2.216916 0.293882 +v 1.197484 -2.123200 0.289847 +v 0.964023 -2.029484 0.285812 +v 0.730562 -1.935768 0.281777 +v 0.497100 -1.842052 0.277742 +v 0.263639 -1.748337 0.273707 +v 0.030178 -1.654621 0.269672 +v -0.203284 -1.560905 0.265637 +v -0.436745 -1.467189 0.261602 +v -0.670206 -1.373474 0.257567 +v -0.903668 -1.279758 0.253532 +v -1.137129 -1.186042 0.249497 +v -1.370590 -1.092326 0.245462 +v -1.604052 -0.998610 0.241427 +v -1.837513 -0.904895 0.237392 +v -2.070974 -0.811179 0.233357 +v -2.304435 -0.717463 0.229322 +v -2.537897 -0.623747 0.225287 +v -2.771358 -0.530031 0.221252 +v -3.004820 -0.436316 0.217217 +v -3.238281 -0.342600 0.213182 +v -3.471742 -0.248884 0.209147 +v -3.705204 -0.155168 0.205112 +v -3.938665 -0.061453 0.201077 +v -4.172126 0.032263 0.197042 +v -4.405587 0.125979 0.193007 +v -4.639049 0.219695 0.188972 +v -4.872510 0.313411 0.184937 +v 4.162643 -3.178163 0.332665 +v 3.929182 -3.084447 0.328630 +v 3.695721 -2.990731 0.324595 +v 3.462259 -2.897015 0.320560 +v 3.228797 -2.803299 0.316525 +v 2.995336 -2.709584 0.312490 +v 2.761875 -2.615868 0.308455 +v 2.528413 -2.522151 0.304420 +v 2.294952 -2.428436 0.300385 +v 2.061491 -2.334720 0.296350 +v 1.828029 -2.241004 0.292315 +v 1.594568 -2.147288 0.288280 +v 1.361106 -2.053572 0.284245 +v 1.127645 -1.959856 0.280210 +v 0.894184 -1.866141 0.276175 +v 0.660722 -1.772425 0.272140 +v 0.427261 -1.678709 0.268105 +v 0.193800 -1.584993 0.264070 +v -0.039662 -1.491277 0.260035 +v -0.273123 -1.397561 0.256000 +v -0.506584 -1.303846 0.251965 +v -0.740046 -1.210130 0.247930 +v -0.973507 -1.116414 0.243895 +v -1.206968 -1.022698 0.239860 +v -1.440430 -0.928983 0.235825 +v -1.673891 -0.835267 0.231790 +v -1.907352 -0.741551 0.227755 +v -2.140813 -0.647835 0.223720 +v -2.374275 -0.554119 0.219685 +v -2.607736 -0.460404 0.215650 +v -2.841197 -0.366688 0.211615 +v -3.074659 -0.272972 0.207580 +v -3.308120 -0.179256 0.203545 +v -3.541582 -0.085541 0.199510 +v -3.775043 0.008175 0.195475 +v -4.008504 0.101891 0.191440 +v -4.241965 0.195607 0.187405 +v -4.475427 0.289323 0.183370 +v -4.708888 0.383039 0.179335 +v -4.942349 0.476755 0.175300 +v 4.326265 -3.108535 0.327063 +v 4.092804 -3.014819 0.323028 +v 3.859343 -2.921103 0.318993 +v 3.625881 -2.827387 0.314958 +v 3.392420 -2.733672 0.310923 +v 3.158958 -2.639956 0.306888 +v 2.925497 -2.546240 0.302853 +v 2.692035 -2.452524 0.298818 +v 2.458574 -2.358808 0.294783 +v 2.225112 -2.265092 0.290748 +v 1.991651 -2.171377 0.286713 +v 1.758190 -2.077660 0.282678 +v 1.524728 -1.983944 0.278643 +v 1.291267 -1.890228 0.274608 +v 1.057806 -1.796513 0.270573 +v 0.824344 -1.702797 0.266538 +v 0.590883 -1.609081 0.262503 +v 0.357422 -1.515365 0.258468 +v 0.123960 -1.421649 0.254433 +v -0.109501 -1.327934 0.250398 +v -0.342962 -1.234218 0.246363 +v -0.576424 -1.140502 0.242328 +v -0.809885 -1.046786 0.238293 +v -1.043346 -0.953071 0.234258 +v -1.276808 -0.859355 0.230223 +v -1.510269 -0.765639 0.226188 +v -1.743730 -0.671923 0.222153 +v -1.977192 -0.578207 0.218118 +v -2.210653 -0.484491 0.214083 +v -2.444114 -0.390776 0.210048 +v -2.677576 -0.297060 0.206013 +v -2.911037 -0.203344 0.201978 +v -3.144498 -0.109628 0.197943 +v -3.377960 -0.015913 0.193908 +v -3.611421 0.077803 0.189873 +v -3.844882 0.171519 0.185838 +v -4.078343 0.265235 0.181803 +v -4.311805 0.358951 0.177768 +v -4.545266 0.452667 0.173733 +v -4.778728 0.546382 0.169698 +v -5.012189 0.640098 0.165663 +v 4.489887 -3.038907 0.321461 +v 4.256426 -2.945192 0.317426 +v 4.022964 -2.851475 0.313390 +v 3.789503 -2.757760 0.309355 +v 3.556042 -2.664043 0.305321 +v 3.322580 -2.570328 0.301286 +v 3.089119 -2.476612 0.297251 +v 2.855658 -2.382896 0.293216 +v 2.622196 -2.289180 0.289181 +v 2.388735 -2.195465 0.285146 +v 2.155273 -2.101748 0.281111 +v 1.921812 -2.008032 0.277076 +v 1.688350 -1.914317 0.273041 +v 1.454889 -1.820600 0.269006 +v 1.221428 -1.726885 0.264971 +v 0.987966 -1.633169 0.260936 +v 0.754505 -1.539453 0.256901 +v 0.521044 -1.445737 0.252866 +v 0.287582 -1.352022 0.248831 +v 0.054121 -1.258306 0.244796 +v -0.179340 -1.164590 0.240761 +v -0.412802 -1.070874 0.236726 +v -0.646263 -0.977158 0.232691 +v -0.879724 -0.883443 0.228656 +v -1.113186 -0.789727 0.224621 +v -1.346647 -0.696011 0.220586 +v -1.580108 -0.602295 0.216551 +v -1.813570 -0.508579 0.212516 +v -2.047031 -0.414864 0.208481 +v -2.280492 -0.321148 0.204446 +v -2.513954 -0.227432 0.200411 +v -2.747415 -0.133716 0.196376 +v -2.980876 -0.040001 0.192341 +v -3.214338 0.053715 0.188306 +v -3.447799 0.147431 0.184271 +v -3.681260 0.241147 0.180236 +v -3.914722 0.334863 0.176201 +v -4.148183 0.428579 0.172166 +v -4.381644 0.522295 0.168131 +v -4.615106 0.616011 0.164096 +v -4.848567 0.709726 0.160061 +v -5.082028 0.803442 0.156026 +v 4.653510 -2.969280 0.315859 +v 4.420048 -2.875564 0.311824 +v 4.186587 -2.781847 0.307789 +v 3.953125 -2.688132 0.303754 +v 3.719664 -2.594416 0.299719 +v 3.486202 -2.500700 0.295684 +v 3.252741 -2.406984 0.291649 +v 3.019279 -2.313268 0.287614 +v 2.785818 -2.219553 0.283579 +v 2.552357 -2.125836 0.279544 +v 2.318895 -2.032120 0.275509 +v 2.085434 -1.938404 0.271474 +v 1.851972 -1.844689 0.267439 +v 1.618511 -1.750973 0.263404 +v 1.385050 -1.657257 0.259369 +v 1.151588 -1.563541 0.255334 +v 0.918127 -1.469826 0.251299 +v 0.684666 -1.376110 0.247264 +v 0.451204 -1.282394 0.243229 +v 0.217743 -1.188678 0.239194 +v -0.015718 -1.094962 0.235159 +v -0.249180 -1.001246 0.231124 +v -0.482641 -0.907531 0.227089 +v -0.716102 -0.813815 0.223054 +v -0.949564 -0.720099 0.219019 +v -1.183025 -0.626383 0.214984 +v -1.416486 -0.532667 0.210949 +v -1.649948 -0.438952 0.206914 +v -1.883409 -0.345236 0.202879 +v -2.116870 -0.251520 0.198844 +v -2.350331 -0.157804 0.194809 +v -2.583793 -0.064088 0.190774 +v -2.817254 0.029627 0.186739 +v -3.050715 0.123343 0.182704 +v -3.284177 0.217059 0.178669 +v -3.517638 0.310775 0.174634 +v -3.751100 0.404491 0.170599 +v -3.984561 0.498207 0.166564 +v -4.218022 0.591923 0.162529 +v -4.451484 0.685638 0.158494 +v -4.684945 0.779354 0.154459 +v -4.918406 0.873070 0.150424 +v -5.151868 0.966786 0.146389 +v 4.817132 -2.899652 0.310257 +v 4.583670 -2.805936 0.306221 +v 4.350208 -2.712219 0.302186 +v 4.116747 -2.618504 0.298151 +v 3.883286 -2.524788 0.294116 +v 3.649824 -2.431072 0.290082 +v 3.416363 -2.337356 0.286047 +v 3.182901 -2.243640 0.282012 +v 2.949440 -2.149925 0.277977 +v 2.715979 -2.056208 0.273942 +v 2.482517 -1.962493 0.269907 +v 2.249056 -1.868777 0.265872 +v 2.015594 -1.775061 0.261837 +v 1.782133 -1.681345 0.257802 +v 1.548671 -1.587629 0.253767 +v 1.315210 -1.493914 0.249732 +v 1.081749 -1.400198 0.245697 +v 0.848288 -1.306482 0.241662 +v 0.614826 -1.212766 0.237627 +v 0.381365 -1.119050 0.233592 +v 0.147904 -1.025334 0.229557 +v -0.085558 -0.931619 0.225522 +v -0.319019 -0.837903 0.221487 +v -0.552480 -0.744187 0.217452 +v -0.785942 -0.650471 0.213417 +v -1.019403 -0.556755 0.209382 +v -1.252864 -0.463039 0.205347 +v -1.486326 -0.369324 0.201312 +v -1.719787 -0.275608 0.197277 +v -1.953248 -0.181892 0.193242 +v -2.186710 -0.088176 0.189207 +v -2.420171 0.005539 0.185172 +v -2.653632 0.099255 0.181137 +v -2.887094 0.192971 0.177102 +v -3.120555 0.286687 0.173067 +v -3.354016 0.380403 0.169032 +v -3.587478 0.474118 0.164997 +v -3.820939 0.567834 0.160962 +v -4.054400 0.661550 0.156927 +v -4.287862 0.755266 0.152892 +v -4.521323 0.848982 0.148857 +v -4.754785 0.942698 0.144822 +v -4.988246 1.036414 0.140787 +v -5.221706 1.130129 0.136752 +v 4.980753 -2.830024 0.304654 +v 4.747292 -2.736308 0.300619 +v 4.513830 -2.642592 0.296584 +v 4.280369 -2.548876 0.292549 +v 4.046907 -2.455160 0.288514 +v 3.813446 -2.361444 0.284479 +v 3.579985 -2.267728 0.280444 +v 3.346523 -2.174013 0.276409 +v 3.113062 -2.080297 0.272375 +v 2.879601 -1.986581 0.268340 +v 2.646139 -1.892865 0.264305 +v 2.412678 -1.799149 0.260270 +v 2.179216 -1.705433 0.256235 +v 1.945755 -1.611717 0.252200 +v 1.712294 -1.518002 0.248165 +v 1.478832 -1.424286 0.244130 +v 1.245371 -1.330570 0.240095 +v 1.011909 -1.236854 0.236060 +v 0.778448 -1.143138 0.232025 +v 0.544987 -1.049423 0.227990 +v 0.311526 -0.955707 0.223955 +v 0.078064 -0.861991 0.219920 +v -0.155397 -0.768275 0.215885 +v -0.388859 -0.674559 0.211850 +v -0.622320 -0.580843 0.207815 +v -0.855781 -0.487128 0.203780 +v -1.089242 -0.393412 0.199745 +v -1.322704 -0.299696 0.195710 +v -1.556165 -0.205980 0.191675 +v -1.789626 -0.112264 0.187640 +v -2.023088 -0.018548 0.183605 +v -2.256549 0.075167 0.179570 +v -2.490010 0.168883 0.175535 +v -2.723472 0.262599 0.171500 +v -2.956933 0.356315 0.167465 +v -3.190394 0.450030 0.163430 +v -3.423856 0.543746 0.159395 +v -3.657317 0.637462 0.155360 +v -3.890779 0.731178 0.151325 +v -4.124240 0.824894 0.147290 +v -4.357701 0.918610 0.143255 +v -4.591162 1.012325 0.139220 +v -4.824624 1.106042 0.135185 +v -5.058085 1.199757 0.131150 +v -5.291546 1.293473 0.127115 +v 5.144376 -2.760396 0.299052 +v 4.910913 -2.666680 0.295017 +v 4.677453 -2.572964 0.290982 +v 4.443991 -2.479249 0.286947 +v 4.210530 -2.385532 0.282912 +v 3.977068 -2.291817 0.278877 +v 3.743607 -2.198101 0.274843 +v 3.510145 -2.104385 0.270808 +v 3.276684 -2.010669 0.266773 +v 3.043222 -1.916953 0.262738 +v 2.809761 -1.823237 0.258703 +v 2.576299 -1.729521 0.254668 +v 2.342838 -1.635805 0.250633 +v 2.109377 -1.542089 0.246598 +v 1.875915 -1.448374 0.242563 +v 1.642454 -1.354658 0.238528 +v 1.408993 -1.260942 0.234493 +v 1.175532 -1.167226 0.230458 +v 0.942070 -1.073511 0.226423 +v 0.708609 -0.979795 0.222388 +v 0.475148 -0.886079 0.218353 +v 0.241686 -0.792363 0.214318 +v 0.008225 -0.698647 0.210283 +v -0.225236 -0.604931 0.206248 +v -0.458698 -0.511216 0.202213 +v -0.692159 -0.417500 0.198178 +v -0.925620 -0.323784 0.194143 +v -1.159082 -0.230068 0.190108 +v -1.392543 -0.136352 0.186073 +v -1.626004 -0.042636 0.182038 +v -1.859466 0.051079 0.178003 +v -2.092927 0.144795 0.173968 +v -2.326388 0.238511 0.169933 +v -2.559850 0.332227 0.165898 +v -2.793311 0.425943 0.161863 +v -3.026772 0.519658 0.157828 +v -3.260234 0.613374 0.153793 +v -3.493695 0.707090 0.149758 +v -3.727157 0.800806 0.145723 +v -3.960618 0.894522 0.141688 +v -4.194079 0.988238 0.137653 +v -4.427540 1.081954 0.133618 +v -4.661001 1.175669 0.129583 +v -4.894464 1.269385 0.125548 +v -5.127924 1.363101 0.121513 +v -5.361385 1.456817 0.117478 +v 5.307998 -2.690768 0.293450 +v 5.074536 -2.597052 0.289415 +v 4.841075 -2.503336 0.285380 +v 4.607614 -2.409621 0.281345 +v 4.374152 -2.315905 0.277310 +v 4.140691 -2.222188 0.273275 +v 3.907229 -2.128473 0.269240 +v 3.673767 -2.034757 0.265205 +v 3.440306 -1.941041 0.261170 +v 3.206845 -1.847325 0.257135 +v 2.973383 -1.753609 0.253100 +v 2.739922 -1.659893 0.249065 +v 2.506460 -1.566177 0.245030 +v 2.272999 -1.472462 0.240995 +v 2.039538 -1.378746 0.236960 +v 1.806076 -1.285030 0.232925 +v 1.572615 -1.191314 0.228890 +v 1.339153 -1.097599 0.224855 +v 1.105692 -1.003883 0.220821 +v 0.872231 -0.910167 0.216786 +v 0.638770 -0.816451 0.212751 +v 0.405308 -0.722735 0.208716 +v 0.171847 -0.629019 0.204681 +v -0.061614 -0.535303 0.200646 +v -0.295076 -0.441588 0.196611 +v -0.528537 -0.347872 0.192576 +v -0.761998 -0.254156 0.188541 +v -0.995460 -0.160440 0.184506 +v -1.228921 -0.066724 0.180471 +v -1.462382 0.026991 0.176436 +v -1.695844 0.120707 0.172401 +v -1.929305 0.214423 0.168366 +v -2.162766 0.308139 0.164331 +v -2.396228 0.401855 0.160296 +v -2.629689 0.495571 0.156261 +v -2.863150 0.589286 0.152226 +v -3.096612 0.683002 0.148191 +v -3.330073 0.776718 0.144156 +v -3.563535 0.870434 0.140121 +v -3.796996 0.964150 0.136086 +v -4.030457 1.057866 0.132051 +v -4.263918 1.151582 0.128016 +v -4.497379 1.245297 0.123981 +v -4.730841 1.339013 0.119946 +v -4.964303 1.432729 0.115911 +v -5.197763 1.526445 0.111876 +v -5.431225 1.620160 0.107841 +v 5.471620 -2.621141 0.287848 +v 5.238158 -2.527424 0.283813 +v 5.004697 -2.433708 0.279778 +v 4.771235 -2.339993 0.275743 +v 4.537774 -2.246277 0.271708 +v 4.304313 -2.152560 0.267673 +v 4.070851 -2.058845 0.263638 +v 3.837389 -1.965129 0.259603 +v 3.603928 -1.871413 0.255568 +v 3.370467 -1.777697 0.251533 +v 3.137005 -1.683981 0.247498 +v 2.903544 -1.590265 0.243463 +v 2.670082 -1.496549 0.239429 +v 2.436621 -1.402834 0.235394 +v 2.203160 -1.309118 0.231359 +v 1.969698 -1.215402 0.227324 +v 1.736237 -1.121686 0.223289 +v 1.502776 -1.027971 0.219254 +v 1.269314 -0.934255 0.215219 +v 1.035853 -0.840539 0.211184 +v 0.802391 -0.746823 0.207149 +v 0.568930 -0.653107 0.203114 +v 0.335469 -0.559391 0.199079 +v 0.102008 -0.465676 0.195044 +v -0.131454 -0.371960 0.191009 +v -0.364915 -0.278244 0.186974 +v -0.598377 -0.184528 0.182939 +v -0.831838 -0.090812 0.178904 +v -1.065299 0.002903 0.174869 +v -1.298761 0.096619 0.170834 +v -1.532222 0.190335 0.166799 +v -1.765683 0.284051 0.162764 +v -1.999144 0.377767 0.158729 +v -2.232605 0.471483 0.154694 +v -2.466067 0.565198 0.150659 +v -2.699528 0.658914 0.146624 +v -2.932990 0.752630 0.142589 +v -3.166451 0.846346 0.138554 +v -3.399912 0.940062 0.134519 +v -3.633374 1.033778 0.130484 +v -3.866836 1.127494 0.126449 +v -4.100297 1.221209 0.122414 +v -4.333757 1.314925 0.118379 +v -4.567219 1.408641 0.114344 +v -4.800680 1.502357 0.110309 +v -5.034142 1.596073 0.106274 +v -5.267603 1.689788 0.102239 +v -5.501064 1.783504 0.098204 +v 5.635241 -2.551513 0.282246 +v 5.401779 -2.457797 0.278211 +v 5.168319 -2.364081 0.274176 +v 4.934856 -2.270365 0.270141 +v 4.701396 -2.176649 0.266106 +v 4.467934 -2.082933 0.262071 +v 4.234472 -1.989217 0.258036 +v 4.001011 -1.895501 0.254001 +v 3.767550 -1.801785 0.249966 +v 3.534088 -1.708070 0.245931 +v 3.300627 -1.614354 0.241896 +v 3.067165 -1.520638 0.237861 +v 2.833704 -1.426922 0.233826 +v 2.600243 -1.333206 0.229791 +v 2.366781 -1.239491 0.225756 +v 2.133320 -1.145774 0.221721 +v 1.899859 -1.052059 0.217686 +v 1.666397 -0.958343 0.213651 +v 1.432936 -0.864627 0.209616 +v 1.199475 -0.770911 0.205581 +v 0.966013 -0.677196 0.201546 +v 0.732552 -0.583480 0.197511 +v 0.499091 -0.489764 0.193476 +v 0.265629 -0.396048 0.189441 +v 0.032168 -0.302332 0.185406 +v -0.201293 -0.208616 0.181371 +v -0.434755 -0.114901 0.177336 +v -0.668216 -0.021185 0.173302 +v -0.901677 0.072531 0.169267 +v -1.135139 0.166247 0.165232 +v -1.368600 0.259963 0.161197 +v -1.602061 0.353679 0.157162 +v -1.835523 0.447395 0.153127 +v -2.068984 0.541110 0.149092 +v -2.302445 0.634826 0.145057 +v -2.535906 0.728542 0.141022 +v -2.769368 0.822258 0.136987 +v -3.002829 0.915974 0.132952 +v -3.236290 1.009689 0.128917 +v -3.469752 1.103406 0.124882 +v -3.703213 1.197121 0.120847 +v -3.936675 1.290837 0.116812 +v -4.170135 1.384553 0.112777 +v -4.403597 1.478269 0.108742 +v -4.637058 1.571984 0.104707 +v -4.870520 1.665701 0.100672 +v -5.103981 1.759416 0.096637 +v -5.337442 1.853132 0.092602 +v -5.570904 1.946848 0.088567 +vn 0.0077 0.0622 0.9980 +usemtl None +s off +f 2//1 254//1 104//1 +f 2//1 105//1 254//1 +f 205//1 204//1 3//1 +f 206//1 255//1 205//1 +f 207//1 256//1 206//1 +f 208//1 258//1 207//1 +f 209//1 261//1 208//1 +f 210//1 265//1 209//1 +f 211//1 270//1 210//1 +f 212//1 276//1 211//1 +f 213//1 283//1 212//1 +f 214//1 291//1 213//1 +f 215//1 300//1 214//1 +f 216//1 310//1 215//1 +f 217//1 321//1 216//1 +f 218//1 333//1 217//1 +f 219//1 346//1 218//1 +f 220//1 360//1 219//1 +f 221//1 375//1 220//1 +f 222//1 391//1 221//1 +f 223//1 408//1 222//1 +f 224//1 426//1 223//1 +f 225//1 445//1 224//1 +f 226//1 465//1 225//1 +f 227//1 486//1 226//1 +f 228//1 508//1 227//1 +f 229//1 531//1 228//1 +f 230//1 555//1 229//1 +f 231//1 580//1 230//1 +f 232//1 606//1 231//1 +f 233//1 633//1 232//1 +f 234//1 661//1 233//1 +f 235//1 690//1 234//1 +f 236//1 720//1 235//1 +f 237//1 751//1 236//1 +f 238//1 783//1 237//1 +f 239//1 816//1 238//1 +f 240//1 850//1 239//1 +f 241//1 885//1 240//1 +f 242//1 921//1 241//1 +f 243//1 958//1 242//1 +f 244//1 996//1 243//1 +f 245//1 1035//1 244//1 +f 246//1 1075//1 245//1 +f 247//1 1116//1 246//1 +f 248//1 1158//1 247//1 +f 249//1 1201//1 248//1 +f 250//1 1245//1 249//1 +f 251//1 1290//1 250//1 +f 252//1 1336//1 251//1 +f 253//1 1383//1 252//1 +f 254//1 1431//1 253//1 +f 205//1 255//1 204//1 +f 255//1 203//1 204//1 +f 206//1 256//1 255//1 +f 256//1 257//1 255//1 +f 255//1 257//1 203//1 +f 257//1 202//1 203//1 +f 207//1 258//1 256//1 +f 258//1 259//1 256//1 +f 256//1 259//1 257//1 +f 259//1 260//1 257//1 +f 257//1 260//1 202//1 +f 260//1 201//1 202//1 +f 208//1 261//1 258//1 +f 261//1 262//1 258//1 +f 258//1 262//1 259//1 +f 262//1 263//1 259//1 +f 259//1 263//1 260//1 +f 263//1 264//1 260//1 +f 260//1 264//1 201//1 +f 264//1 200//1 201//1 +f 209//1 265//1 261//1 +f 265//1 266//1 261//1 +f 261//1 266//1 262//1 +f 266//1 267//1 262//1 +f 262//1 267//1 263//1 +f 267//1 268//1 263//1 +f 263//1 268//1 264//1 +f 268//1 269//1 264//1 +f 264//1 269//1 200//1 +f 269//1 199//1 200//1 +f 210//1 270//1 265//1 +f 270//1 271//1 265//1 +f 265//1 271//1 266//1 +f 271//1 272//1 266//1 +f 266//1 272//1 267//1 +f 272//1 273//1 267//1 +f 267//1 273//1 268//1 +f 273//1 274//1 268//1 +f 268//1 274//1 269//1 +f 274//1 275//1 269//1 +f 269//1 275//1 199//1 +f 275//1 198//1 199//1 +f 211//1 276//1 270//1 +f 276//1 277//1 270//1 +f 270//1 277//1 271//1 +f 277//1 278//1 271//1 +f 271//1 278//1 272//1 +f 278//1 279//1 272//1 +f 272//1 279//1 273//1 +f 279//1 280//1 273//1 +f 273//1 280//1 274//1 +f 280//1 281//1 274//1 +f 274//1 281//1 275//1 +f 281//1 282//1 275//1 +f 275//1 282//1 198//1 +f 282//1 197//1 198//1 +f 212//1 283//1 276//1 +f 283//1 284//1 276//1 +f 276//1 284//1 277//1 +f 284//1 285//1 277//1 +f 277//1 285//1 278//1 +f 285//1 286//1 278//1 +f 278//1 286//1 279//1 +f 286//1 287//1 279//1 +f 279//1 287//1 280//1 +f 287//1 288//1 280//1 +f 280//1 288//1 281//1 +f 288//1 289//1 281//1 +f 281//1 289//1 282//1 +f 289//1 290//1 282//1 +f 282//1 290//1 197//1 +f 290//1 196//1 197//1 +f 213//1 291//1 283//1 +f 291//1 292//1 283//1 +f 283//1 292//1 284//1 +f 292//1 293//1 284//1 +f 284//1 293//1 285//1 +f 293//1 294//1 285//1 +f 285//1 294//1 286//1 +f 294//1 295//1 286//1 +f 286//1 295//1 287//1 +f 295//1 296//1 287//1 +f 287//1 296//1 288//1 +f 296//1 297//1 288//1 +f 288//1 297//1 289//1 +f 297//1 298//1 289//1 +f 289//1 298//1 290//1 +f 298//1 299//1 290//1 +f 290//1 299//1 196//1 +f 299//1 195//1 196//1 +f 214//1 300//1 291//1 +f 300//1 301//1 291//1 +f 291//1 301//1 292//1 +f 301//1 302//1 292//1 +f 292//1 302//1 293//1 +f 302//1 303//1 293//1 +f 293//1 303//1 294//1 +f 303//1 304//1 294//1 +f 294//1 304//1 295//1 +f 304//1 305//1 295//1 +f 295//1 305//1 296//1 +f 305//1 306//1 296//1 +f 296//1 306//1 297//1 +f 306//1 307//1 297//1 +f 297//1 307//1 298//1 +f 307//1 308//1 298//1 +f 298//1 308//1 299//1 +f 308//1 309//1 299//1 +f 299//1 309//1 195//1 +f 309//1 194//1 195//1 +f 215//1 310//1 300//1 +f 310//1 311//1 300//1 +f 300//1 311//1 301//1 +f 311//1 312//1 301//1 +f 301//1 312//1 302//1 +f 312//1 313//1 302//1 +f 302//1 313//1 303//1 +f 313//1 314//1 303//1 +f 303//1 314//1 304//1 +f 314//1 315//1 304//1 +f 304//1 315//1 305//1 +f 315//1 316//1 305//1 +f 305//1 316//1 306//1 +f 316//1 317//1 306//1 +f 306//1 317//1 307//1 +f 317//1 318//1 307//1 +f 307//1 318//1 308//1 +f 318//1 319//1 308//1 +f 308//1 319//1 309//1 +f 319//1 320//1 309//1 +f 309//1 320//1 194//1 +f 320//1 193//1 194//1 +f 216//1 321//1 310//1 +f 321//1 322//1 310//1 +f 310//1 322//1 311//1 +f 322//1 323//1 311//1 +f 311//1 323//1 312//1 +f 323//1 324//1 312//1 +f 312//1 324//1 313//1 +f 324//1 325//1 313//1 +f 313//1 325//1 314//1 +f 325//1 326//1 314//1 +f 314//1 326//1 315//1 +f 326//1 327//1 315//1 +f 315//1 327//1 316//1 +f 327//1 328//1 316//1 +f 316//1 328//1 317//1 +f 328//1 329//1 317//1 +f 317//1 329//1 318//1 +f 329//1 330//1 318//1 +f 318//1 330//1 319//1 +f 330//1 331//1 319//1 +f 319//1 331//1 320//1 +f 331//1 332//1 320//1 +f 320//1 332//1 193//1 +f 332//1 192//1 193//1 +f 217//1 333//1 321//1 +f 333//1 334//1 321//1 +f 321//1 334//1 322//1 +f 334//1 335//1 322//1 +f 322//1 335//1 323//1 +f 335//1 336//1 323//1 +f 323//1 336//1 324//1 +f 336//1 337//1 324//1 +f 324//1 337//1 325//1 +f 337//1 338//1 325//1 +f 325//1 338//1 326//1 +f 338//1 339//1 326//1 +f 326//1 339//1 327//1 +f 339//1 340//1 327//1 +f 327//1 340//1 328//1 +f 340//1 341//1 328//1 +f 328//1 341//1 329//1 +f 341//1 342//1 329//1 +f 329//1 342//1 330//1 +f 342//1 343//1 330//1 +f 330//1 343//1 331//1 +f 343//1 344//1 331//1 +f 331//1 344//1 332//1 +f 344//1 345//1 332//1 +f 332//1 345//1 192//1 +f 345//1 191//1 192//1 +f 218//1 346//1 333//1 +f 346//1 347//1 333//1 +f 333//1 347//1 334//1 +f 347//1 348//1 334//1 +f 334//1 348//1 335//1 +f 348//1 349//1 335//1 +f 335//1 349//1 336//1 +f 349//1 350//1 336//1 +f 336//1 350//1 337//1 +f 350//1 351//1 337//1 +f 337//1 351//1 338//1 +f 351//1 352//1 338//1 +f 338//1 352//1 339//1 +f 352//1 353//1 339//1 +f 339//1 353//1 340//1 +f 353//1 354//1 340//1 +f 340//1 354//1 341//1 +f 354//1 355//1 341//1 +f 341//1 355//1 342//1 +f 355//1 356//1 342//1 +f 342//1 356//1 343//1 +f 356//1 357//1 343//1 +f 343//1 357//1 344//1 +f 357//1 358//1 344//1 +f 344//1 358//1 345//1 +f 358//1 359//1 345//1 +f 345//1 359//1 191//1 +f 359//1 190//1 191//1 +f 219//1 360//1 346//1 +f 360//1 361//1 346//1 +f 346//1 361//1 347//1 +f 361//1 362//1 347//1 +f 347//1 362//1 348//1 +f 362//1 363//1 348//1 +f 348//1 363//1 349//1 +f 363//1 364//1 349//1 +f 349//1 364//1 350//1 +f 364//1 365//1 350//1 +f 350//1 365//1 351//1 +f 365//1 366//1 351//1 +f 351//1 366//1 352//1 +f 366//1 367//1 352//1 +f 352//1 367//1 353//1 +f 367//1 368//1 353//1 +f 353//1 368//1 354//1 +f 368//1 369//1 354//1 +f 354//1 369//1 355//1 +f 369//1 370//1 355//1 +f 355//1 370//1 356//1 +f 370//1 371//1 356//1 +f 356//1 371//1 357//1 +f 371//1 372//1 357//1 +f 357//1 372//1 358//1 +f 372//1 373//1 358//1 +f 358//1 373//1 359//1 +f 373//1 374//1 359//1 +f 359//1 374//1 190//1 +f 374//1 189//1 190//1 +f 220//1 375//1 360//1 +f 375//1 376//1 360//1 +f 360//1 376//1 361//1 +f 376//1 377//1 361//1 +f 361//1 377//1 362//1 +f 377//1 378//1 362//1 +f 362//1 378//1 363//1 +f 378//1 379//1 363//1 +f 363//1 379//1 364//1 +f 379//1 380//1 364//1 +f 364//1 380//1 365//1 +f 380//1 381//1 365//1 +f 365//1 381//1 366//1 +f 381//1 382//1 366//1 +f 366//1 382//1 367//1 +f 382//1 383//1 367//1 +f 367//1 383//1 368//1 +f 383//1 384//1 368//1 +f 368//1 384//1 369//1 +f 384//1 385//1 369//1 +f 369//1 385//1 370//1 +f 385//1 386//1 370//1 +f 370//1 386//1 371//1 +f 386//1 387//1 371//1 +f 371//1 387//1 372//1 +f 387//1 388//1 372//1 +f 372//1 388//1 373//1 +f 388//1 389//1 373//1 +f 373//1 389//1 374//1 +f 389//1 390//1 374//1 +f 374//1 390//1 189//1 +f 390//1 188//1 189//1 +f 221//1 391//1 375//1 +f 391//1 392//1 375//1 +f 375//1 392//1 376//1 +f 392//1 393//1 376//1 +f 376//1 393//1 377//1 +f 393//1 394//1 377//1 +f 377//1 394//1 378//1 +f 394//1 395//1 378//1 +f 378//1 395//1 379//1 +f 395//1 396//1 379//1 +f 379//1 396//1 380//1 +f 396//1 397//1 380//1 +f 380//1 397//1 381//1 +f 397//1 398//1 381//1 +f 381//1 398//1 382//1 +f 398//1 399//1 382//1 +f 382//1 399//1 383//1 +f 399//1 400//1 383//1 +f 383//1 400//1 384//1 +f 400//1 401//1 384//1 +f 384//1 401//1 385//1 +f 401//1 402//1 385//1 +f 385//1 402//1 386//1 +f 402//1 403//1 386//1 +f 386//1 403//1 387//1 +f 403//1 404//1 387//1 +f 387//1 404//1 388//1 +f 404//1 405//1 388//1 +f 388//1 405//1 389//1 +f 405//1 406//1 389//1 +f 389//1 406//1 390//1 +f 406//1 407//1 390//1 +f 390//1 407//1 188//1 +f 407//1 187//1 188//1 +f 222//1 408//1 391//1 +f 408//1 409//1 391//1 +f 391//1 409//1 392//1 +f 409//1 410//1 392//1 +f 392//1 410//1 393//1 +f 410//1 411//1 393//1 +f 393//1 411//1 394//1 +f 411//1 412//1 394//1 +f 394//1 412//1 395//1 +f 412//1 413//1 395//1 +f 395//1 413//1 396//1 +f 413//1 414//1 396//1 +f 396//1 414//1 397//1 +f 414//1 415//1 397//1 +f 397//1 415//1 398//1 +f 415//1 416//1 398//1 +f 398//1 416//1 399//1 +f 416//1 417//1 399//1 +f 399//1 417//1 400//1 +f 417//1 418//1 400//1 +f 400//1 418//1 401//1 +f 418//1 419//1 401//1 +f 401//1 419//1 402//1 +f 419//1 420//1 402//1 +f 402//1 420//1 403//1 +f 420//1 421//1 403//1 +f 403//1 421//1 404//1 +f 421//1 422//1 404//1 +f 404//1 422//1 405//1 +f 422//1 423//1 405//1 +f 405//1 423//1 406//1 +f 423//1 424//1 406//1 +f 406//1 424//1 407//1 +f 424//1 425//1 407//1 +f 407//1 425//1 187//1 +f 425//1 186//1 187//1 +f 223//1 426//1 408//1 +f 426//1 427//1 408//1 +f 408//1 427//1 409//1 +f 427//1 428//1 409//1 +f 409//1 428//1 410//1 +f 428//1 429//1 410//1 +f 410//1 429//1 411//1 +f 429//1 430//1 411//1 +f 411//1 430//1 412//1 +f 430//1 431//1 412//1 +f 412//1 431//1 413//1 +f 431//1 432//1 413//1 +f 413//1 432//1 414//1 +f 432//1 433//1 414//1 +f 414//1 433//1 415//1 +f 433//1 434//1 415//1 +f 415//1 434//1 416//1 +f 434//1 435//1 416//1 +f 416//1 435//1 417//1 +f 435//1 436//1 417//1 +f 417//1 436//1 418//1 +f 436//1 437//1 418//1 +f 418//1 437//1 419//1 +f 437//1 438//1 419//1 +f 419//1 438//1 420//1 +f 438//1 439//1 420//1 +f 420//1 439//1 421//1 +f 439//1 440//1 421//1 +f 421//1 440//1 422//1 +f 440//1 441//1 422//1 +f 422//1 441//1 423//1 +f 441//1 442//1 423//1 +f 423//1 442//1 424//1 +f 442//1 443//1 424//1 +f 424//1 443//1 425//1 +f 443//1 444//1 425//1 +f 425//1 444//1 186//1 +f 444//1 185//1 186//1 +f 224//1 445//1 426//1 +f 445//1 446//1 426//1 +f 426//1 446//1 427//1 +f 446//1 447//1 427//1 +f 427//1 447//1 428//1 +f 447//1 448//1 428//1 +f 428//1 448//1 429//1 +f 448//1 449//1 429//1 +f 429//1 449//1 430//1 +f 449//1 450//1 430//1 +f 430//1 450//1 431//1 +f 450//1 451//1 431//1 +f 431//1 451//1 432//1 +f 451//1 452//1 432//1 +f 432//1 452//1 433//1 +f 452//1 453//1 433//1 +f 433//1 453//1 434//1 +f 453//1 454//1 434//1 +f 434//1 454//1 435//1 +f 454//1 455//1 435//1 +f 435//1 455//1 436//1 +f 455//1 456//1 436//1 +f 436//1 456//1 437//1 +f 456//1 457//1 437//1 +f 437//1 457//1 438//1 +f 457//1 458//1 438//1 +f 438//1 458//1 439//1 +f 458//1 459//1 439//1 +f 439//1 459//1 440//1 +f 459//1 460//1 440//1 +f 440//1 460//1 441//1 +f 460//1 461//1 441//1 +f 441//1 461//1 442//1 +f 461//1 462//1 442//1 +f 442//1 462//1 443//1 +f 462//1 463//1 443//1 +f 443//1 463//1 444//1 +f 463//1 464//1 444//1 +f 444//1 464//1 185//1 +f 464//1 184//1 185//1 +f 225//1 465//1 445//1 +f 465//1 466//1 445//1 +f 445//1 466//1 446//1 +f 466//1 467//1 446//1 +f 446//1 467//1 447//1 +f 467//1 468//1 447//1 +f 447//1 468//1 448//1 +f 468//1 469//1 448//1 +f 448//1 469//1 449//1 +f 469//1 470//1 449//1 +f 449//1 470//1 450//1 +f 470//1 471//1 450//1 +f 450//1 471//1 451//1 +f 471//1 472//1 451//1 +f 451//1 472//1 452//1 +f 472//1 473//1 452//1 +f 452//1 473//1 453//1 +f 473//1 474//1 453//1 +f 453//1 474//1 454//1 +f 474//1 475//1 454//1 +f 454//1 475//1 455//1 +f 475//1 476//1 455//1 +f 455//1 476//1 456//1 +f 476//1 477//1 456//1 +f 456//1 477//1 457//1 +f 477//1 478//1 457//1 +f 457//1 478//1 458//1 +f 478//1 479//1 458//1 +f 458//1 479//1 459//1 +f 479//1 480//1 459//1 +f 459//1 480//1 460//1 +f 480//1 481//1 460//1 +f 460//1 481//1 461//1 +f 481//1 482//1 461//1 +f 461//1 482//1 462//1 +f 482//1 483//1 462//1 +f 462//1 483//1 463//1 +f 483//1 484//1 463//1 +f 463//1 484//1 464//1 +f 484//1 485//1 464//1 +f 464//1 485//1 184//1 +f 485//1 183//1 184//1 +f 226//1 486//1 465//1 +f 486//1 487//1 465//1 +f 465//1 487//1 466//1 +f 487//1 488//1 466//1 +f 466//1 488//1 467//1 +f 488//1 489//1 467//1 +f 467//1 489//1 468//1 +f 489//1 490//1 468//1 +f 468//1 490//1 469//1 +f 490//1 491//1 469//1 +f 469//1 491//1 470//1 +f 491//1 492//1 470//1 +f 470//1 492//1 471//1 +f 492//1 493//1 471//1 +f 471//1 493//1 472//1 +f 493//1 494//1 472//1 +f 472//1 494//1 473//1 +f 494//1 495//1 473//1 +f 473//1 495//1 474//1 +f 495//1 496//1 474//1 +f 474//1 496//1 475//1 +f 496//1 497//1 475//1 +f 475//1 497//1 476//1 +f 497//1 498//1 476//1 +f 476//1 498//1 477//1 +f 498//1 499//1 477//1 +f 477//1 499//1 478//1 +f 499//1 500//1 478//1 +f 478//1 500//1 479//1 +f 500//1 501//1 479//1 +f 479//1 501//1 480//1 +f 501//1 502//1 480//1 +f 480//1 502//1 481//1 +f 502//1 503//1 481//1 +f 481//1 503//1 482//1 +f 503//1 504//1 482//1 +f 482//1 504//1 483//1 +f 504//1 505//1 483//1 +f 483//1 505//1 484//1 +f 505//1 506//1 484//1 +f 484//1 506//1 485//1 +f 506//1 507//1 485//1 +f 485//1 507//1 183//1 +f 507//1 182//1 183//1 +f 227//1 508//1 486//1 +f 508//1 509//1 486//1 +f 486//1 509//1 487//1 +f 509//1 510//1 487//1 +f 487//1 510//1 488//1 +f 510//1 511//1 488//1 +f 488//1 511//1 489//1 +f 511//1 512//1 489//1 +f 489//1 512//1 490//1 +f 512//1 513//1 490//1 +f 490//1 513//1 491//1 +f 513//1 514//1 491//1 +f 491//1 514//1 492//1 +f 514//1 515//1 492//1 +f 492//1 515//1 493//1 +f 515//1 516//1 493//1 +f 493//1 516//1 494//1 +f 516//1 517//1 494//1 +f 494//1 517//1 495//1 +f 517//1 518//1 495//1 +f 495//1 518//1 496//1 +f 518//1 519//1 496//1 +f 496//1 519//1 497//1 +f 519//1 520//1 497//1 +f 497//1 520//1 498//1 +f 520//1 521//1 498//1 +f 498//1 521//1 499//1 +f 521//1 522//1 499//1 +f 499//1 522//1 500//1 +f 522//1 523//1 500//1 +f 500//1 523//1 501//1 +f 523//1 524//1 501//1 +f 501//1 524//1 502//1 +f 524//1 525//1 502//1 +f 502//1 525//1 503//1 +f 525//1 526//1 503//1 +f 503//1 526//1 504//1 +f 526//1 527//1 504//1 +f 504//1 527//1 505//1 +f 527//1 528//1 505//1 +f 505//1 528//1 506//1 +f 528//1 529//1 506//1 +f 506//1 529//1 507//1 +f 529//1 530//1 507//1 +f 507//1 530//1 182//1 +f 530//1 181//1 182//1 +f 228//1 531//1 508//1 +f 531//1 532//1 508//1 +f 508//1 532//1 509//1 +f 532//1 533//1 509//1 +f 509//1 533//1 510//1 +f 533//1 534//1 510//1 +f 510//1 534//1 511//1 +f 534//1 535//1 511//1 +f 511//1 535//1 512//1 +f 535//1 536//1 512//1 +f 512//1 536//1 513//1 +f 536//1 537//1 513//1 +f 513//1 537//1 514//1 +f 537//1 538//1 514//1 +f 514//1 538//1 515//1 +f 538//1 539//1 515//1 +f 515//1 539//1 516//1 +f 539//1 540//1 516//1 +f 516//1 540//1 517//1 +f 540//1 541//1 517//1 +f 517//1 541//1 518//1 +f 541//1 542//1 518//1 +f 518//1 542//1 519//1 +f 542//1 543//1 519//1 +f 519//1 543//1 520//1 +f 543//1 544//1 520//1 +f 520//1 544//1 521//1 +f 544//1 545//1 521//1 +f 521//1 545//1 522//1 +f 545//1 546//1 522//1 +f 522//1 546//1 523//1 +f 546//1 547//1 523//1 +f 523//1 547//1 524//1 +f 547//1 548//1 524//1 +f 524//1 548//1 525//1 +f 548//1 549//1 525//1 +f 525//1 549//1 526//1 +f 549//1 550//1 526//1 +f 526//1 550//1 527//1 +f 550//1 551//1 527//1 +f 527//1 551//1 528//1 +f 551//1 552//1 528//1 +f 528//1 552//1 529//1 +f 552//1 553//1 529//1 +f 529//1 553//1 530//1 +f 553//1 554//1 530//1 +f 530//1 554//1 181//1 +f 554//1 180//1 181//1 +f 229//1 555//1 531//1 +f 555//1 556//1 531//1 +f 531//1 556//1 532//1 +f 556//1 557//1 532//1 +f 532//1 557//1 533//1 +f 557//1 558//1 533//1 +f 533//1 558//1 534//1 +f 558//1 559//1 534//1 +f 534//1 559//1 535//1 +f 559//1 560//1 535//1 +f 535//1 560//1 536//1 +f 560//1 561//1 536//1 +f 536//1 561//1 537//1 +f 561//1 562//1 537//1 +f 537//1 562//1 538//1 +f 562//1 563//1 538//1 +f 538//1 563//1 539//1 +f 563//1 564//1 539//1 +f 539//1 564//1 540//1 +f 564//1 565//1 540//1 +f 540//1 565//1 541//1 +f 565//1 566//1 541//1 +f 541//1 566//1 542//1 +f 566//1 567//1 542//1 +f 542//1 567//1 543//1 +f 567//1 568//1 543//1 +f 543//1 568//1 544//1 +f 568//1 569//1 544//1 +f 544//1 569//1 545//1 +f 569//1 570//1 545//1 +f 545//1 570//1 546//1 +f 570//1 571//1 546//1 +f 546//1 571//1 547//1 +f 571//1 572//1 547//1 +f 547//1 572//1 548//1 +f 572//1 573//1 548//1 +f 548//1 573//1 549//1 +f 573//1 574//1 549//1 +f 549//1 574//1 550//1 +f 574//1 575//1 550//1 +f 550//1 575//1 551//1 +f 575//1 576//1 551//1 +f 551//1 576//1 552//1 +f 576//1 577//1 552//1 +f 552//1 577//1 553//1 +f 577//1 578//1 553//1 +f 553//1 578//1 554//1 +f 578//1 579//1 554//1 +f 554//1 579//1 180//1 +f 579//1 179//1 180//1 +f 230//1 580//1 555//1 +f 580//1 581//1 555//1 +f 555//1 581//1 556//1 +f 581//1 582//1 556//1 +f 556//1 582//1 557//1 +f 582//1 583//1 557//1 +f 557//1 583//1 558//1 +f 583//1 584//1 558//1 +f 558//1 584//1 559//1 +f 584//1 585//1 559//1 +f 559//1 585//1 560//1 +f 585//1 586//1 560//1 +f 560//1 586//1 561//1 +f 586//1 587//1 561//1 +f 561//1 587//1 562//1 +f 587//1 588//1 562//1 +f 562//1 588//1 563//1 +f 588//1 589//1 563//1 +f 563//1 589//1 564//1 +f 589//1 590//1 564//1 +f 564//1 590//1 565//1 +f 590//1 591//1 565//1 +f 565//1 591//1 566//1 +f 591//1 592//1 566//1 +f 566//1 592//1 567//1 +f 592//1 593//1 567//1 +f 567//1 593//1 568//1 +f 593//1 594//1 568//1 +f 568//1 594//1 569//1 +f 594//1 595//1 569//1 +f 569//1 595//1 570//1 +f 595//1 596//1 570//1 +f 570//1 596//1 571//1 +f 596//1 597//1 571//1 +f 571//1 597//1 572//1 +f 597//1 598//1 572//1 +f 572//1 598//1 573//1 +f 598//1 599//1 573//1 +f 573//1 599//1 574//1 +f 599//1 600//1 574//1 +f 574//1 600//1 575//1 +f 600//1 601//1 575//1 +f 575//1 601//1 576//1 +f 601//1 602//1 576//1 +f 576//1 602//1 577//1 +f 602//1 603//1 577//1 +f 577//1 603//1 578//1 +f 603//1 604//1 578//1 +f 578//1 604//1 579//1 +f 604//1 605//1 579//1 +f 579//1 605//1 179//1 +f 605//1 178//1 179//1 +f 231//1 606//1 580//1 +f 606//1 607//1 580//1 +f 580//1 607//1 581//1 +f 607//1 608//1 581//1 +f 581//1 608//1 582//1 +f 608//1 609//1 582//1 +f 582//1 609//1 583//1 +f 609//1 610//1 583//1 +f 583//1 610//1 584//1 +f 610//1 611//1 584//1 +f 584//1 611//1 585//1 +f 611//1 612//1 585//1 +f 585//1 612//1 586//1 +f 612//1 613//1 586//1 +f 586//1 613//1 587//1 +f 613//1 614//1 587//1 +f 587//1 614//1 588//1 +f 614//1 615//1 588//1 +f 588//1 615//1 589//1 +f 615//1 616//1 589//1 +f 589//1 616//1 590//1 +f 616//1 617//1 590//1 +f 590//1 617//1 591//1 +f 617//1 618//1 591//1 +f 591//1 618//1 592//1 +f 618//1 619//1 592//1 +f 592//1 619//1 593//1 +f 619//1 620//1 593//1 +f 593//1 620//1 594//1 +f 620//1 621//1 594//1 +f 594//1 621//1 595//1 +f 621//1 622//1 595//1 +f 595//1 622//1 596//1 +f 622//1 623//1 596//1 +f 596//1 623//1 597//1 +f 623//1 624//1 597//1 +f 597//1 624//1 598//1 +f 624//1 625//1 598//1 +f 598//1 625//1 599//1 +f 625//1 626//1 599//1 +f 599//1 626//1 600//1 +f 626//1 627//1 600//1 +f 600//1 627//1 601//1 +f 627//1 628//1 601//1 +f 601//1 628//1 602//1 +f 628//1 629//1 602//1 +f 602//1 629//1 603//1 +f 629//1 630//1 603//1 +f 603//1 630//1 604//1 +f 630//1 631//1 604//1 +f 604//1 631//1 605//1 +f 631//1 632//1 605//1 +f 605//1 632//1 178//1 +f 632//1 177//1 178//1 +f 232//1 633//1 606//1 +f 633//1 634//1 606//1 +f 606//1 634//1 607//1 +f 634//1 635//1 607//1 +f 607//1 635//1 608//1 +f 635//1 636//1 608//1 +f 608//1 636//1 609//1 +f 636//1 637//1 609//1 +f 609//1 637//1 610//1 +f 637//1 638//1 610//1 +f 610//1 638//1 611//1 +f 638//1 639//1 611//1 +f 611//1 639//1 612//1 +f 639//1 640//1 612//1 +f 612//1 640//1 613//1 +f 640//1 641//1 613//1 +f 613//1 641//1 614//1 +f 641//1 642//1 614//1 +f 614//1 642//1 615//1 +f 642//1 643//1 615//1 +f 615//1 643//1 616//1 +f 643//1 644//1 616//1 +f 616//1 644//1 617//1 +f 644//1 645//1 617//1 +f 617//1 645//1 618//1 +f 645//1 646//1 618//1 +f 618//1 646//1 619//1 +f 646//1 647//1 619//1 +f 619//1 647//1 620//1 +f 647//1 648//1 620//1 +f 620//1 648//1 621//1 +f 648//1 649//1 621//1 +f 621//1 649//1 622//1 +f 649//1 650//1 622//1 +f 622//1 650//1 623//1 +f 650//1 651//1 623//1 +f 623//1 651//1 624//1 +f 651//1 652//1 624//1 +f 624//1 652//1 625//1 +f 652//1 653//1 625//1 +f 625//1 653//1 626//1 +f 653//1 654//1 626//1 +f 626//1 654//1 627//1 +f 654//1 655//1 627//1 +f 627//1 655//1 628//1 +f 655//1 656//1 628//1 +f 628//1 656//1 629//1 +f 656//1 657//1 629//1 +f 629//1 657//1 630//1 +f 657//1 658//1 630//1 +f 630//1 658//1 631//1 +f 658//1 659//1 631//1 +f 631//1 659//1 632//1 +f 659//1 660//1 632//1 +f 632//1 660//1 177//1 +f 660//1 176//1 177//1 +f 233//1 661//1 633//1 +f 661//1 662//1 633//1 +f 633//1 662//1 634//1 +f 662//1 663//1 634//1 +f 634//1 663//1 635//1 +f 663//1 664//1 635//1 +f 635//1 664//1 636//1 +f 664//1 665//1 636//1 +f 636//1 665//1 637//1 +f 665//1 666//1 637//1 +f 637//1 666//1 638//1 +f 666//1 667//1 638//1 +f 638//1 667//1 639//1 +f 667//1 668//1 639//1 +f 639//1 668//1 640//1 +f 668//1 669//1 640//1 +f 640//1 669//1 641//1 +f 669//1 670//1 641//1 +f 641//1 670//1 642//1 +f 670//1 671//1 642//1 +f 642//1 671//1 643//1 +f 671//1 672//1 643//1 +f 643//1 672//1 644//1 +f 672//1 673//1 644//1 +f 644//1 673//1 645//1 +f 673//1 674//1 645//1 +f 645//1 674//1 646//1 +f 674//1 675//1 646//1 +f 646//1 675//1 647//1 +f 675//1 676//1 647//1 +f 647//1 676//1 648//1 +f 676//1 677//1 648//1 +f 648//1 677//1 649//1 +f 677//1 678//1 649//1 +f 649//1 678//1 650//1 +f 678//1 679//1 650//1 +f 650//1 679//1 651//1 +f 679//1 680//1 651//1 +f 651//1 680//1 652//1 +f 680//1 681//1 652//1 +f 652//1 681//1 653//1 +f 681//1 682//1 653//1 +f 653//1 682//1 654//1 +f 682//1 683//1 654//1 +f 654//1 683//1 655//1 +f 683//1 684//1 655//1 +f 655//1 684//1 656//1 +f 684//1 685//1 656//1 +f 656//1 685//1 657//1 +f 685//1 686//1 657//1 +f 657//1 686//1 658//1 +f 686//1 687//1 658//1 +f 658//1 687//1 659//1 +f 687//1 688//1 659//1 +f 659//1 688//1 660//1 +f 688//1 689//1 660//1 +f 660//1 689//1 176//1 +f 689//1 175//1 176//1 +f 234//1 690//1 661//1 +f 690//1 691//1 661//1 +f 661//1 691//1 662//1 +f 691//1 692//1 662//1 +f 662//1 692//1 663//1 +f 692//1 693//1 663//1 +f 663//1 693//1 664//1 +f 693//1 694//1 664//1 +f 664//1 694//1 665//1 +f 694//1 695//1 665//1 +f 665//1 695//1 666//1 +f 695//1 696//1 666//1 +f 666//1 696//1 667//1 +f 696//1 697//1 667//1 +f 667//1 697//1 668//1 +f 697//1 698//1 668//1 +f 668//1 698//1 669//1 +f 698//1 699//1 669//1 +f 669//1 699//1 670//1 +f 699//1 700//1 670//1 +f 670//1 700//1 671//1 +f 700//1 701//1 671//1 +f 671//1 701//1 672//1 +f 701//1 702//1 672//1 +f 672//1 702//1 673//1 +f 702//1 703//1 673//1 +f 673//1 703//1 674//1 +f 703//1 704//1 674//1 +f 674//1 704//1 675//1 +f 704//1 705//1 675//1 +f 675//1 705//1 676//1 +f 705//1 706//1 676//1 +f 676//1 706//1 677//1 +f 706//1 707//1 677//1 +f 677//1 707//1 678//1 +f 707//1 708//1 678//1 +f 678//1 708//1 679//1 +f 708//1 709//1 679//1 +f 679//1 709//1 680//1 +f 709//1 710//1 680//1 +f 680//1 710//1 681//1 +f 710//1 711//1 681//1 +f 681//1 711//1 682//1 +f 711//1 712//1 682//1 +f 682//1 712//1 683//1 +f 712//1 713//1 683//1 +f 683//1 713//1 684//1 +f 713//1 714//1 684//1 +f 684//1 714//1 685//1 +f 714//1 715//1 685//1 +f 685//1 715//1 686//1 +f 715//1 716//1 686//1 +f 686//1 716//1 687//1 +f 716//1 717//1 687//1 +f 687//1 717//1 688//1 +f 717//1 718//1 688//1 +f 688//1 718//1 689//1 +f 718//1 719//1 689//1 +f 689//1 719//1 175//1 +f 719//1 174//1 175//1 +f 235//1 720//1 690//1 +f 720//1 721//1 690//1 +f 690//1 721//1 691//1 +f 721//1 722//1 691//1 +f 691//1 722//1 692//1 +f 722//1 723//1 692//1 +f 692//1 723//1 693//1 +f 723//1 724//1 693//1 +f 693//1 724//1 694//1 +f 724//1 725//1 694//1 +f 694//1 725//1 695//1 +f 725//1 726//1 695//1 +f 695//1 726//1 696//1 +f 726//1 727//1 696//1 +f 696//1 727//1 697//1 +f 727//1 728//1 697//1 +f 697//1 728//1 698//1 +f 728//1 729//1 698//1 +f 698//1 729//1 699//1 +f 729//1 730//1 699//1 +f 699//1 730//1 700//1 +f 730//1 731//1 700//1 +f 700//1 731//1 701//1 +f 731//1 732//1 701//1 +f 701//1 732//1 702//1 +f 732//1 733//1 702//1 +f 702//1 733//1 703//1 +f 733//1 734//1 703//1 +f 703//1 734//1 704//1 +f 734//1 735//1 704//1 +f 704//1 735//1 705//1 +f 735//1 736//1 705//1 +f 705//1 736//1 706//1 +f 736//1 737//1 706//1 +f 706//1 737//1 707//1 +f 737//1 738//1 707//1 +f 707//1 738//1 708//1 +f 738//1 739//1 708//1 +f 708//1 739//1 709//1 +f 739//1 740//1 709//1 +f 709//1 740//1 710//1 +f 740//1 741//1 710//1 +f 710//1 741//1 711//1 +f 741//1 742//1 711//1 +f 711//1 742//1 712//1 +f 742//1 743//1 712//1 +f 712//1 743//1 713//1 +f 743//1 744//1 713//1 +f 713//1 744//1 714//1 +f 744//1 745//1 714//1 +f 714//1 745//1 715//1 +f 745//1 746//1 715//1 +f 715//1 746//1 716//1 +f 746//1 747//1 716//1 +f 716//1 747//1 717//1 +f 747//1 748//1 717//1 +f 717//1 748//1 718//1 +f 748//1 749//1 718//1 +f 718//1 749//1 719//1 +f 749//1 750//1 719//1 +f 719//1 750//1 174//1 +f 750//1 173//1 174//1 +f 236//1 751//1 720//1 +f 751//1 752//1 720//1 +f 720//1 752//1 721//1 +f 752//1 753//1 721//1 +f 721//1 753//1 722//1 +f 753//1 754//1 722//1 +f 722//1 754//1 723//1 +f 754//1 755//1 723//1 +f 723//1 755//1 724//1 +f 755//1 756//1 724//1 +f 724//1 756//1 725//1 +f 756//1 757//1 725//1 +f 725//1 757//1 726//1 +f 757//1 758//1 726//1 +f 726//1 758//1 727//1 +f 758//1 759//1 727//1 +f 727//1 759//1 728//1 +f 759//1 760//1 728//1 +f 728//1 760//1 729//1 +f 760//1 761//1 729//1 +f 729//1 761//1 730//1 +f 761//1 762//1 730//1 +f 730//1 762//1 731//1 +f 762//1 763//1 731//1 +f 731//1 763//1 732//1 +f 763//1 764//1 732//1 +f 732//1 764//1 733//1 +f 764//1 765//1 733//1 +f 733//1 765//1 734//1 +f 765//1 766//1 734//1 +f 734//1 766//1 735//1 +f 766//1 767//1 735//1 +f 735//1 767//1 736//1 +f 767//1 768//1 736//1 +f 736//1 768//1 737//1 +f 768//1 769//1 737//1 +f 737//1 769//1 738//1 +f 769//1 770//1 738//1 +f 738//1 770//1 739//1 +f 770//1 771//1 739//1 +f 739//1 771//1 740//1 +f 771//1 772//1 740//1 +f 740//1 772//1 741//1 +f 772//1 773//1 741//1 +f 741//1 773//1 742//1 +f 773//1 774//1 742//1 +f 742//1 774//1 743//1 +f 774//1 775//1 743//1 +f 743//1 775//1 744//1 +f 775//1 776//1 744//1 +f 744//1 776//1 745//1 +f 776//1 777//1 745//1 +f 745//1 777//1 746//1 +f 777//1 778//1 746//1 +f 746//1 778//1 747//1 +f 778//1 779//1 747//1 +f 747//1 779//1 748//1 +f 779//1 780//1 748//1 +f 748//1 780//1 749//1 +f 780//1 781//1 749//1 +f 749//1 781//1 750//1 +f 781//1 782//1 750//1 +f 750//1 782//1 173//1 +f 782//1 172//1 173//1 +f 237//1 783//1 751//1 +f 783//1 784//1 751//1 +f 751//1 784//1 752//1 +f 784//1 785//1 752//1 +f 752//1 785//1 753//1 +f 785//1 786//1 753//1 +f 753//1 786//1 754//1 +f 786//1 787//1 754//1 +f 754//1 787//1 755//1 +f 787//1 788//1 755//1 +f 755//1 788//1 756//1 +f 788//1 789//1 756//1 +f 756//1 789//1 757//1 +f 789//1 790//1 757//1 +f 757//1 790//1 758//1 +f 790//1 791//1 758//1 +f 758//1 791//1 759//1 +f 791//1 792//1 759//1 +f 759//1 792//1 760//1 +f 792//1 793//1 760//1 +f 760//1 793//1 761//1 +f 793//1 794//1 761//1 +f 761//1 794//1 762//1 +f 794//1 795//1 762//1 +f 762//1 795//1 763//1 +f 795//1 796//1 763//1 +f 763//1 796//1 764//1 +f 796//1 797//1 764//1 +f 764//1 797//1 765//1 +f 797//1 798//1 765//1 +f 765//1 798//1 766//1 +f 798//1 799//1 766//1 +f 766//1 799//1 767//1 +f 799//1 800//1 767//1 +f 767//1 800//1 768//1 +f 800//1 801//1 768//1 +f 768//1 801//1 769//1 +f 801//1 802//1 769//1 +f 769//1 802//1 770//1 +f 802//1 803//1 770//1 +f 770//1 803//1 771//1 +f 803//1 804//1 771//1 +f 771//1 804//1 772//1 +f 804//1 805//1 772//1 +f 772//1 805//1 773//1 +f 805//1 806//1 773//1 +f 773//1 806//1 774//1 +f 806//1 807//1 774//1 +f 774//1 807//1 775//1 +f 807//1 808//1 775//1 +f 775//1 808//1 776//1 +f 808//1 809//1 776//1 +f 776//1 809//1 777//1 +f 809//1 810//1 777//1 +f 777//1 810//1 778//1 +f 810//1 811//1 778//1 +f 778//1 811//1 779//1 +f 811//1 812//1 779//1 +f 779//1 812//1 780//1 +f 812//1 813//1 780//1 +f 780//1 813//1 781//1 +f 813//1 814//1 781//1 +f 781//1 814//1 782//1 +f 814//1 815//1 782//1 +f 782//1 815//1 172//1 +f 815//1 171//1 172//1 +f 238//1 816//1 783//1 +f 816//1 817//1 783//1 +f 783//1 817//1 784//1 +f 817//1 818//1 784//1 +f 784//1 818//1 785//1 +f 818//1 819//1 785//1 +f 785//1 819//1 786//1 +f 819//1 820//1 786//1 +f 786//1 820//1 787//1 +f 820//1 821//1 787//1 +f 787//1 821//1 788//1 +f 821//1 822//1 788//1 +f 788//1 822//1 789//1 +f 822//1 823//1 789//1 +f 789//1 823//1 790//1 +f 823//1 824//1 790//1 +f 790//1 824//1 791//1 +f 824//1 825//1 791//1 +f 791//1 825//1 792//1 +f 825//1 826//1 792//1 +f 792//1 826//1 793//1 +f 826//1 827//1 793//1 +f 793//1 827//1 794//1 +f 827//1 828//1 794//1 +f 794//1 828//1 795//1 +f 828//1 829//1 795//1 +f 795//1 829//1 796//1 +f 829//1 830//1 796//1 +f 796//1 830//1 797//1 +f 830//1 831//1 797//1 +f 797//1 831//1 798//1 +f 831//1 832//1 798//1 +f 798//1 832//1 799//1 +f 832//1 833//1 799//1 +f 799//1 833//1 800//1 +f 833//1 834//1 800//1 +f 800//1 834//1 801//1 +f 834//1 835//1 801//1 +f 801//1 835//1 802//1 +f 835//1 836//1 802//1 +f 802//1 836//1 803//1 +f 836//1 837//1 803//1 +f 803//1 837//1 804//1 +f 837//1 838//1 804//1 +f 804//1 838//1 805//1 +f 838//1 839//1 805//1 +f 805//1 839//1 806//1 +f 839//1 840//1 806//1 +f 806//1 840//1 807//1 +f 840//1 841//1 807//1 +f 807//1 841//1 808//1 +f 841//1 842//1 808//1 +f 808//1 842//1 809//1 +f 842//1 843//1 809//1 +f 809//1 843//1 810//1 +f 843//1 844//1 810//1 +f 810//1 844//1 811//1 +f 844//1 845//1 811//1 +f 811//1 845//1 812//1 +f 845//1 846//1 812//1 +f 812//1 846//1 813//1 +f 846//1 847//1 813//1 +f 813//1 847//1 814//1 +f 847//1 848//1 814//1 +f 814//1 848//1 815//1 +f 848//1 849//1 815//1 +f 815//1 849//1 171//1 +f 849//1 170//1 171//1 +f 239//1 850//1 816//1 +f 850//1 851//1 816//1 +f 816//1 851//1 817//1 +f 851//1 852//1 817//1 +f 817//1 852//1 818//1 +f 852//1 853//1 818//1 +f 818//1 853//1 819//1 +f 853//1 854//1 819//1 +f 819//1 854//1 820//1 +f 854//1 855//1 820//1 +f 820//1 855//1 821//1 +f 855//1 856//1 821//1 +f 821//1 856//1 822//1 +f 856//1 857//1 822//1 +f 822//1 857//1 823//1 +f 857//1 858//1 823//1 +f 823//1 858//1 824//1 +f 858//1 859//1 824//1 +f 824//1 859//1 825//1 +f 859//1 860//1 825//1 +f 825//1 860//1 826//1 +f 860//1 861//1 826//1 +f 826//1 861//1 827//1 +f 861//1 862//1 827//1 +f 827//1 862//1 828//1 +f 862//1 863//1 828//1 +f 828//1 863//1 829//1 +f 863//1 864//1 829//1 +f 829//1 864//1 830//1 +f 864//1 865//1 830//1 +f 830//1 865//1 831//1 +f 865//1 866//1 831//1 +f 831//1 866//1 832//1 +f 866//1 867//1 832//1 +f 832//1 867//1 833//1 +f 867//1 868//1 833//1 +f 833//1 868//1 834//1 +f 868//1 869//1 834//1 +f 834//1 869//1 835//1 +f 869//1 870//1 835//1 +f 835//1 870//1 836//1 +f 870//1 871//1 836//1 +f 836//1 871//1 837//1 +f 871//1 872//1 837//1 +f 837//1 872//1 838//1 +f 872//1 873//1 838//1 +f 838//1 873//1 839//1 +f 873//1 874//1 839//1 +f 839//1 874//1 840//1 +f 874//1 875//1 840//1 +f 840//1 875//1 841//1 +f 875//1 876//1 841//1 +f 841//1 876//1 842//1 +f 876//1 877//1 842//1 +f 842//1 877//1 843//1 +f 877//1 878//1 843//1 +f 843//1 878//1 844//1 +f 878//1 879//1 844//1 +f 844//1 879//1 845//1 +f 879//1 880//1 845//1 +f 845//1 880//1 846//1 +f 880//1 881//1 846//1 +f 846//1 881//1 847//1 +f 881//1 882//1 847//1 +f 847//1 882//1 848//1 +f 882//1 883//1 848//1 +f 848//1 883//1 849//1 +f 883//1 884//1 849//1 +f 849//1 884//1 170//1 +f 884//1 169//1 170//1 +f 240//1 885//1 850//1 +f 885//1 886//1 850//1 +f 850//1 886//1 851//1 +f 886//1 887//1 851//1 +f 851//1 887//1 852//1 +f 887//1 888//1 852//1 +f 852//1 888//1 853//1 +f 888//1 889//1 853//1 +f 853//1 889//1 854//1 +f 889//1 890//1 854//1 +f 854//1 890//1 855//1 +f 890//1 891//1 855//1 +f 855//1 891//1 856//1 +f 891//1 892//1 856//1 +f 856//1 892//1 857//1 +f 892//1 893//1 857//1 +f 857//1 893//1 858//1 +f 893//1 894//1 858//1 +f 858//1 894//1 859//1 +f 894//1 895//1 859//1 +f 859//1 895//1 860//1 +f 895//1 896//1 860//1 +f 860//1 896//1 861//1 +f 896//1 897//1 861//1 +f 861//1 897//1 862//1 +f 897//1 898//1 862//1 +f 862//1 898//1 863//1 +f 898//1 899//1 863//1 +f 863//1 899//1 864//1 +f 899//1 900//1 864//1 +f 864//1 900//1 865//1 +f 900//1 901//1 865//1 +f 865//1 901//1 866//1 +f 901//1 902//1 866//1 +f 866//1 902//1 867//1 +f 902//1 903//1 867//1 +f 867//1 903//1 868//1 +f 903//1 904//1 868//1 +f 868//1 904//1 869//1 +f 904//1 905//1 869//1 +f 869//1 905//1 870//1 +f 905//1 906//1 870//1 +f 870//1 906//1 871//1 +f 906//1 907//1 871//1 +f 871//1 907//1 872//1 +f 907//1 908//1 872//1 +f 872//1 908//1 873//1 +f 908//1 909//1 873//1 +f 873//1 909//1 874//1 +f 909//1 910//1 874//1 +f 874//1 910//1 875//1 +f 910//1 911//1 875//1 +f 875//1 911//1 876//1 +f 911//1 912//1 876//1 +f 876//1 912//1 877//1 +f 912//1 913//1 877//1 +f 877//1 913//1 878//1 +f 913//1 914//1 878//1 +f 878//1 914//1 879//1 +f 914//1 915//1 879//1 +f 879//1 915//1 880//1 +f 915//1 916//1 880//1 +f 880//1 916//1 881//1 +f 916//1 917//1 881//1 +f 881//1 917//1 882//1 +f 917//1 918//1 882//1 +f 882//1 918//1 883//1 +f 918//1 919//1 883//1 +f 883//1 919//1 884//1 +f 919//1 920//1 884//1 +f 884//1 920//1 169//1 +f 920//1 168//1 169//1 +f 241//1 921//1 885//1 +f 921//1 922//1 885//1 +f 885//1 922//1 886//1 +f 922//1 923//1 886//1 +f 886//1 923//1 887//1 +f 923//1 924//1 887//1 +f 887//1 924//1 888//1 +f 924//1 925//1 888//1 +f 888//1 925//1 889//1 +f 925//1 926//1 889//1 +f 889//1 926//1 890//1 +f 926//1 927//1 890//1 +f 890//1 927//1 891//1 +f 927//1 928//1 891//1 +f 891//1 928//1 892//1 +f 928//1 929//1 892//1 +f 892//1 929//1 893//1 +f 929//1 930//1 893//1 +f 893//1 930//1 894//1 +f 930//1 931//1 894//1 +f 894//1 931//1 895//1 +f 931//1 932//1 895//1 +f 895//1 932//1 896//1 +f 932//1 933//1 896//1 +f 896//1 933//1 897//1 +f 933//1 934//1 897//1 +f 897//1 934//1 898//1 +f 934//1 935//1 898//1 +f 898//1 935//1 899//1 +f 935//1 936//1 899//1 +f 899//1 936//1 900//1 +f 936//1 937//1 900//1 +f 900//1 937//1 901//1 +f 937//1 938//1 901//1 +f 901//1 938//1 902//1 +f 938//1 939//1 902//1 +f 902//1 939//1 903//1 +f 939//1 940//1 903//1 +f 903//1 940//1 904//1 +f 940//1 941//1 904//1 +f 904//1 941//1 905//1 +f 941//1 942//1 905//1 +f 905//1 942//1 906//1 +f 942//1 943//1 906//1 +f 906//1 943//1 907//1 +f 943//1 944//1 907//1 +f 907//1 944//1 908//1 +f 944//1 945//1 908//1 +f 908//1 945//1 909//1 +f 945//1 946//1 909//1 +f 909//1 946//1 910//1 +f 946//1 947//1 910//1 +f 910//1 947//1 911//1 +f 947//1 948//1 911//1 +f 911//1 948//1 912//1 +f 948//1 949//1 912//1 +f 912//1 949//1 913//1 +f 949//1 950//1 913//1 +f 913//1 950//1 914//1 +f 950//1 951//1 914//1 +f 914//1 951//1 915//1 +f 951//1 952//1 915//1 +f 915//1 952//1 916//1 +f 952//1 953//1 916//1 +f 916//1 953//1 917//1 +f 953//1 954//1 917//1 +f 917//1 954//1 918//1 +f 954//1 955//1 918//1 +f 918//1 955//1 919//1 +f 955//1 956//1 919//1 +f 919//1 956//1 920//1 +f 956//1 957//1 920//1 +f 920//1 957//1 168//1 +f 957//1 167//1 168//1 +f 242//1 958//1 921//1 +f 958//1 959//1 921//1 +f 921//1 959//1 922//1 +f 959//1 960//1 922//1 +f 922//1 960//1 923//1 +f 960//1 961//1 923//1 +f 923//1 961//1 924//1 +f 961//1 962//1 924//1 +f 924//1 962//1 925//1 +f 962//1 963//1 925//1 +f 925//1 963//1 926//1 +f 963//1 964//1 926//1 +f 926//1 964//1 927//1 +f 964//1 965//1 927//1 +f 927//1 965//1 928//1 +f 965//1 966//1 928//1 +f 928//1 966//1 929//1 +f 966//1 967//1 929//1 +f 929//1 967//1 930//1 +f 967//1 968//1 930//1 +f 930//1 968//1 931//1 +f 968//1 969//1 931//1 +f 931//1 969//1 932//1 +f 969//1 970//1 932//1 +f 932//1 970//1 933//1 +f 970//1 971//1 933//1 +f 933//1 971//1 934//1 +f 971//1 972//1 934//1 +f 934//1 972//1 935//1 +f 972//1 973//1 935//1 +f 935//1 973//1 936//1 +f 973//1 974//1 936//1 +f 936//1 974//1 937//1 +f 974//1 975//1 937//1 +f 937//1 975//1 938//1 +f 975//1 976//1 938//1 +f 938//1 976//1 939//1 +f 976//1 977//1 939//1 +f 939//1 977//1 940//1 +f 977//1 978//1 940//1 +f 940//1 978//1 941//1 +f 978//1 979//1 941//1 +f 941//1 979//1 942//1 +f 979//1 980//1 942//1 +f 942//1 980//1 943//1 +f 980//1 981//1 943//1 +f 943//1 981//1 944//1 +f 981//1 982//1 944//1 +f 944//1 982//1 945//1 +f 982//1 983//1 945//1 +f 945//1 983//1 946//1 +f 983//1 984//1 946//1 +f 946//1 984//1 947//1 +f 984//1 985//1 947//1 +f 947//1 985//1 948//1 +f 985//1 986//1 948//1 +f 948//1 986//1 949//1 +f 986//1 987//1 949//1 +f 949//1 987//1 950//1 +f 987//1 988//1 950//1 +f 950//1 988//1 951//1 +f 988//1 989//1 951//1 +f 951//1 989//1 952//1 +f 989//1 990//1 952//1 +f 952//1 990//1 953//1 +f 990//1 991//1 953//1 +f 953//1 991//1 954//1 +f 991//1 992//1 954//1 +f 954//1 992//1 955//1 +f 992//1 993//1 955//1 +f 955//1 993//1 956//1 +f 993//1 994//1 956//1 +f 956//1 994//1 957//1 +f 994//1 995//1 957//1 +f 957//1 995//1 167//1 +f 995//1 166//1 167//1 +f 243//1 996//1 958//1 +f 996//1 997//1 958//1 +f 958//1 997//1 959//1 +f 997//1 998//1 959//1 +f 959//1 998//1 960//1 +f 998//1 999//1 960//1 +f 960//1 999//1 961//1 +f 999//1 1000//1 961//1 +f 961//1 1000//1 962//1 +f 1000//1 1001//1 962//1 +f 962//1 1001//1 963//1 +f 1001//1 1002//1 963//1 +f 963//1 1002//1 964//1 +f 1002//1 1003//1 964//1 +f 964//1 1003//1 965//1 +f 1003//1 1004//1 965//1 +f 965//1 1004//1 966//1 +f 1004//1 1005//1 966//1 +f 966//1 1005//1 967//1 +f 1005//1 1006//1 967//1 +f 967//1 1006//1 968//1 +f 1006//1 1007//1 968//1 +f 968//1 1007//1 969//1 +f 1007//1 1008//1 969//1 +f 969//1 1008//1 970//1 +f 1008//1 1009//1 970//1 +f 970//1 1009//1 971//1 +f 1009//1 1010//1 971//1 +f 971//1 1010//1 972//1 +f 1010//1 1011//1 972//1 +f 972//1 1011//1 973//1 +f 1011//1 1012//1 973//1 +f 973//1 1012//1 974//1 +f 1012//1 1013//1 974//1 +f 974//1 1013//1 975//1 +f 1013//1 1014//1 975//1 +f 975//1 1014//1 976//1 +f 1014//1 1015//1 976//1 +f 976//1 1015//1 977//1 +f 1015//1 1016//1 977//1 +f 977//1 1016//1 978//1 +f 1016//1 1017//1 978//1 +f 978//1 1017//1 979//1 +f 1017//1 1018//1 979//1 +f 979//1 1018//1 980//1 +f 1018//1 1019//1 980//1 +f 980//1 1019//1 981//1 +f 1019//1 1020//1 981//1 +f 981//1 1020//1 982//1 +f 1020//1 1021//1 982//1 +f 982//1 1021//1 983//1 +f 1021//1 1022//1 983//1 +f 983//1 1022//1 984//1 +f 1022//1 1023//1 984//1 +f 984//1 1023//1 985//1 +f 1023//1 1024//1 985//1 +f 985//1 1024//1 986//1 +f 1024//1 1025//1 986//1 +f 986//1 1025//1 987//1 +f 1025//1 1026//1 987//1 +f 987//1 1026//1 988//1 +f 1026//1 1027//1 988//1 +f 988//1 1027//1 989//1 +f 1027//1 1028//1 989//1 +f 989//1 1028//1 990//1 +f 1028//1 1029//1 990//1 +f 990//1 1029//1 991//1 +f 1029//1 1030//1 991//1 +f 991//1 1030//1 992//1 +f 1030//1 1031//1 992//1 +f 992//1 1031//1 993//1 +f 1031//1 1032//1 993//1 +f 993//1 1032//1 994//1 +f 1032//1 1033//1 994//1 +f 994//1 1033//1 995//1 +f 1033//1 1034//1 995//1 +f 995//1 1034//1 166//1 +f 1034//1 165//1 166//1 +f 244//1 1035//1 996//1 +f 1035//1 1036//1 996//1 +f 996//1 1036//1 997//1 +f 1036//1 1037//1 997//1 +f 997//1 1037//1 998//1 +f 1037//1 1038//1 998//1 +f 998//1 1038//1 999//1 +f 1038//1 1039//1 999//1 +f 999//1 1039//1 1000//1 +f 1039//1 1040//1 1000//1 +f 1000//1 1040//1 1001//1 +f 1040//1 1041//1 1001//1 +f 1001//1 1041//1 1002//1 +f 1041//1 1042//1 1002//1 +f 1002//1 1042//1 1003//1 +f 1042//1 1043//1 1003//1 +f 1003//1 1043//1 1004//1 +f 1043//1 1044//1 1004//1 +f 1004//1 1044//1 1005//1 +f 1044//1 1045//1 1005//1 +f 1005//1 1045//1 1006//1 +f 1045//1 1046//1 1006//1 +f 1006//1 1046//1 1007//1 +f 1046//1 1047//1 1007//1 +f 1007//1 1047//1 1008//1 +f 1047//1 1048//1 1008//1 +f 1008//1 1048//1 1009//1 +f 1048//1 1049//1 1009//1 +f 1009//1 1049//1 1010//1 +f 1049//1 1050//1 1010//1 +f 1010//1 1050//1 1011//1 +f 1050//1 1051//1 1011//1 +f 1011//1 1051//1 1012//1 +f 1051//1 1052//1 1012//1 +f 1012//1 1052//1 1013//1 +f 1052//1 1053//1 1013//1 +f 1013//1 1053//1 1014//1 +f 1053//1 1054//1 1014//1 +f 1014//1 1054//1 1015//1 +f 1054//1 1055//1 1015//1 +f 1015//1 1055//1 1016//1 +f 1055//1 1056//1 1016//1 +f 1016//1 1056//1 1017//1 +f 1056//1 1057//1 1017//1 +f 1017//1 1057//1 1018//1 +f 1057//1 1058//1 1018//1 +f 1018//1 1058//1 1019//1 +f 1058//1 1059//1 1019//1 +f 1019//1 1059//1 1020//1 +f 1059//1 1060//1 1020//1 +f 1020//1 1060//1 1021//1 +f 1060//1 1061//1 1021//1 +f 1021//1 1061//1 1022//1 +f 1061//1 1062//1 1022//1 +f 1022//1 1062//1 1023//1 +f 1062//1 1063//1 1023//1 +f 1023//1 1063//1 1024//1 +f 1063//1 1064//1 1024//1 +f 1024//1 1064//1 1025//1 +f 1064//1 1065//1 1025//1 +f 1025//1 1065//1 1026//1 +f 1065//1 1066//1 1026//1 +f 1026//1 1066//1 1027//1 +f 1066//1 1067//1 1027//1 +f 1027//1 1067//1 1028//1 +f 1067//1 1068//1 1028//1 +f 1028//1 1068//1 1029//1 +f 1068//1 1069//1 1029//1 +f 1029//1 1069//1 1030//1 +f 1069//1 1070//1 1030//1 +f 1030//1 1070//1 1031//1 +f 1070//1 1071//1 1031//1 +f 1031//1 1071//1 1032//1 +f 1071//1 1072//1 1032//1 +f 1032//1 1072//1 1033//1 +f 1072//1 1073//1 1033//1 +f 1033//1 1073//1 1034//1 +f 1073//1 1074//1 1034//1 +f 1034//1 1074//1 165//1 +f 1074//1 164//1 165//1 +f 245//1 1075//1 1035//1 +f 1075//1 1076//1 1035//1 +f 1035//1 1076//1 1036//1 +f 1076//1 1077//1 1036//1 +f 1036//1 1077//1 1037//1 +f 1077//1 1078//1 1037//1 +f 1037//1 1078//1 1038//1 +f 1078//1 1079//1 1038//1 +f 1038//1 1079//1 1039//1 +f 1079//1 1080//1 1039//1 +f 1039//1 1080//1 1040//1 +f 1080//1 1081//1 1040//1 +f 1040//1 1081//1 1041//1 +f 1081//1 1082//1 1041//1 +f 1041//1 1082//1 1042//1 +f 1082//1 1083//1 1042//1 +f 1042//1 1083//1 1043//1 +f 1083//1 1084//1 1043//1 +f 1043//1 1084//1 1044//1 +f 1084//1 1085//1 1044//1 +f 1044//1 1085//1 1045//1 +f 1085//1 1086//1 1045//1 +f 1045//1 1086//1 1046//1 +f 1086//1 1087//1 1046//1 +f 1046//1 1087//1 1047//1 +f 1087//1 1088//1 1047//1 +f 1047//1 1088//1 1048//1 +f 1088//1 1089//1 1048//1 +f 1048//1 1089//1 1049//1 +f 1089//1 1090//1 1049//1 +f 1049//1 1090//1 1050//1 +f 1090//1 1091//1 1050//1 +f 1050//1 1091//1 1051//1 +f 1091//1 1092//1 1051//1 +f 1051//1 1092//1 1052//1 +f 1092//1 1093//1 1052//1 +f 1052//1 1093//1 1053//1 +f 1093//1 1094//1 1053//1 +f 1053//1 1094//1 1054//1 +f 1094//1 1095//1 1054//1 +f 1054//1 1095//1 1055//1 +f 1095//1 1096//1 1055//1 +f 1055//1 1096//1 1056//1 +f 1096//1 1097//1 1056//1 +f 1056//1 1097//1 1057//1 +f 1097//1 1098//1 1057//1 +f 1057//1 1098//1 1058//1 +f 1098//1 1099//1 1058//1 +f 1058//1 1099//1 1059//1 +f 1099//1 1100//1 1059//1 +f 1059//1 1100//1 1060//1 +f 1100//1 1101//1 1060//1 +f 1060//1 1101//1 1061//1 +f 1101//1 1102//1 1061//1 +f 1061//1 1102//1 1062//1 +f 1102//1 1103//1 1062//1 +f 1062//1 1103//1 1063//1 +f 1103//1 1104//1 1063//1 +f 1063//1 1104//1 1064//1 +f 1104//1 1105//1 1064//1 +f 1064//1 1105//1 1065//1 +f 1105//1 1106//1 1065//1 +f 1065//1 1106//1 1066//1 +f 1106//1 1107//1 1066//1 +f 1066//1 1107//1 1067//1 +f 1107//1 1108//1 1067//1 +f 1067//1 1108//1 1068//1 +f 1108//1 1109//1 1068//1 +f 1068//1 1109//1 1069//1 +f 1109//1 1110//1 1069//1 +f 1069//1 1110//1 1070//1 +f 1110//1 1111//1 1070//1 +f 1070//1 1111//1 1071//1 +f 1111//1 1112//1 1071//1 +f 1071//1 1112//1 1072//1 +f 1112//1 1113//1 1072//1 +f 1072//1 1113//1 1073//1 +f 1113//1 1114//1 1073//1 +f 1073//1 1114//1 1074//1 +f 1114//1 1115//1 1074//1 +f 1074//1 1115//1 164//1 +f 1115//1 163//1 164//1 +f 246//1 1116//1 1075//1 +f 1116//1 1117//1 1075//1 +f 1075//1 1117//1 1076//1 +f 1117//1 1118//1 1076//1 +f 1076//1 1118//1 1077//1 +f 1118//1 1119//1 1077//1 +f 1077//1 1119//1 1078//1 +f 1119//1 1120//1 1078//1 +f 1078//1 1120//1 1079//1 +f 1120//1 1121//1 1079//1 +f 1079//1 1121//1 1080//1 +f 1121//1 1122//1 1080//1 +f 1080//1 1122//1 1081//1 +f 1122//1 1123//1 1081//1 +f 1081//1 1123//1 1082//1 +f 1123//1 1124//1 1082//1 +f 1082//1 1124//1 1083//1 +f 1124//1 1125//1 1083//1 +f 1083//1 1125//1 1084//1 +f 1125//1 1126//1 1084//1 +f 1084//1 1126//1 1085//1 +f 1126//1 1127//1 1085//1 +f 1085//1 1127//1 1086//1 +f 1127//1 1128//1 1086//1 +f 1086//1 1128//1 1087//1 +f 1128//1 1129//1 1087//1 +f 1087//1 1129//1 1088//1 +f 1129//1 1130//1 1088//1 +f 1088//1 1130//1 1089//1 +f 1130//1 1131//1 1089//1 +f 1089//1 1131//1 1090//1 +f 1131//1 1132//1 1090//1 +f 1090//1 1132//1 1091//1 +f 1132//1 1133//1 1091//1 +f 1091//1 1133//1 1092//1 +f 1133//1 1134//1 1092//1 +f 1092//1 1134//1 1093//1 +f 1134//1 1135//1 1093//1 +f 1093//1 1135//1 1094//1 +f 1135//1 1136//1 1094//1 +f 1094//1 1136//1 1095//1 +f 1136//1 1137//1 1095//1 +f 1095//1 1137//1 1096//1 +f 1137//1 1138//1 1096//1 +f 1096//1 1138//1 1097//1 +f 1138//1 1139//1 1097//1 +f 1097//1 1139//1 1098//1 +f 1139//1 1140//1 1098//1 +f 1098//1 1140//1 1099//1 +f 1140//1 1141//1 1099//1 +f 1099//1 1141//1 1100//1 +f 1141//1 1142//1 1100//1 +f 1100//1 1142//1 1101//1 +f 1142//1 1143//1 1101//1 +f 1101//1 1143//1 1102//1 +f 1143//1 1144//1 1102//1 +f 1102//1 1144//1 1103//1 +f 1144//1 1145//1 1103//1 +f 1103//1 1145//1 1104//1 +f 1145//1 1146//1 1104//1 +f 1104//1 1146//1 1105//1 +f 1146//1 1147//1 1105//1 +f 1105//1 1147//1 1106//1 +f 1147//1 1148//1 1106//1 +f 1106//1 1148//1 1107//1 +f 1148//1 1149//1 1107//1 +f 1107//1 1149//1 1108//1 +f 1149//1 1150//1 1108//1 +f 1108//1 1150//1 1109//1 +f 1150//1 1151//1 1109//1 +f 1109//1 1151//1 1110//1 +f 1151//1 1152//1 1110//1 +f 1110//1 1152//1 1111//1 +f 1152//1 1153//1 1111//1 +f 1111//1 1153//1 1112//1 +f 1153//1 1154//1 1112//1 +f 1112//1 1154//1 1113//1 +f 1154//1 1155//1 1113//1 +f 1113//1 1155//1 1114//1 +f 1155//1 1156//1 1114//1 +f 1114//1 1156//1 1115//1 +f 1156//1 1157//1 1115//1 +f 1115//1 1157//1 163//1 +f 1157//1 162//1 163//1 +f 247//1 1158//1 1116//1 +f 1158//1 1159//1 1116//1 +f 1116//1 1159//1 1117//1 +f 1159//1 1160//1 1117//1 +f 1117//1 1160//1 1118//1 +f 1160//1 1161//1 1118//1 +f 1118//1 1161//1 1119//1 +f 1161//1 1162//1 1119//1 +f 1119//1 1162//1 1120//1 +f 1162//1 1163//1 1120//1 +f 1120//1 1163//1 1121//1 +f 1163//1 1164//1 1121//1 +f 1121//1 1164//1 1122//1 +f 1164//1 1165//1 1122//1 +f 1122//1 1165//1 1123//1 +f 1165//1 1166//1 1123//1 +f 1123//1 1166//1 1124//1 +f 1166//1 1167//1 1124//1 +f 1124//1 1167//1 1125//1 +f 1167//1 1168//1 1125//1 +f 1125//1 1168//1 1126//1 +f 1168//1 1169//1 1126//1 +f 1126//1 1169//1 1127//1 +f 1169//1 1170//1 1127//1 +f 1127//1 1170//1 1128//1 +f 1170//1 1171//1 1128//1 +f 1128//1 1171//1 1129//1 +f 1171//1 1172//1 1129//1 +f 1129//1 1172//1 1130//1 +f 1172//1 1173//1 1130//1 +f 1130//1 1173//1 1131//1 +f 1173//1 1174//1 1131//1 +f 1131//1 1174//1 1132//1 +f 1174//1 1175//1 1132//1 +f 1132//1 1175//1 1133//1 +f 1175//1 1176//1 1133//1 +f 1133//1 1176//1 1134//1 +f 1176//1 1177//1 1134//1 +f 1134//1 1177//1 1135//1 +f 1177//1 1178//1 1135//1 +f 1135//1 1178//1 1136//1 +f 1178//1 1179//1 1136//1 +f 1136//1 1179//1 1137//1 +f 1179//1 1180//1 1137//1 +f 1137//1 1180//1 1138//1 +f 1180//1 1181//1 1138//1 +f 1138//1 1181//1 1139//1 +f 1181//1 1182//1 1139//1 +f 1139//1 1182//1 1140//1 +f 1182//1 1183//1 1140//1 +f 1140//1 1183//1 1141//1 +f 1183//1 1184//1 1141//1 +f 1141//1 1184//1 1142//1 +f 1184//1 1185//1 1142//1 +f 1142//1 1185//1 1143//1 +f 1185//1 1186//1 1143//1 +f 1143//1 1186//1 1144//1 +f 1186//1 1187//1 1144//1 +f 1144//1 1187//1 1145//1 +f 1187//1 1188//1 1145//1 +f 1145//1 1188//1 1146//1 +f 1188//1 1189//1 1146//1 +f 1146//1 1189//1 1147//1 +f 1189//1 1190//1 1147//1 +f 1147//1 1190//1 1148//1 +f 1190//1 1191//1 1148//1 +f 1148//1 1191//1 1149//1 +f 1191//1 1192//1 1149//1 +f 1149//1 1192//1 1150//1 +f 1192//1 1193//1 1150//1 +f 1150//1 1193//1 1151//1 +f 1193//1 1194//1 1151//1 +f 1151//1 1194//1 1152//1 +f 1194//1 1195//1 1152//1 +f 1152//1 1195//1 1153//1 +f 1195//1 1196//1 1153//1 +f 1153//1 1196//1 1154//1 +f 1196//1 1197//1 1154//1 +f 1154//1 1197//1 1155//1 +f 1197//1 1198//1 1155//1 +f 1155//1 1198//1 1156//1 +f 1198//1 1199//1 1156//1 +f 1156//1 1199//1 1157//1 +f 1199//1 1200//1 1157//1 +f 1157//1 1200//1 162//1 +f 1200//1 161//1 162//1 +f 248//1 1201//1 1158//1 +f 1201//1 1202//1 1158//1 +f 1158//1 1202//1 1159//1 +f 1202//1 1203//1 1159//1 +f 1159//1 1203//1 1160//1 +f 1203//1 1204//1 1160//1 +f 1160//1 1204//1 1161//1 +f 1204//1 1205//1 1161//1 +f 1161//1 1205//1 1162//1 +f 1205//1 1206//1 1162//1 +f 1162//1 1206//1 1163//1 +f 1206//1 1207//1 1163//1 +f 1163//1 1207//1 1164//1 +f 1207//1 1208//1 1164//1 +f 1164//1 1208//1 1165//1 +f 1208//1 1209//1 1165//1 +f 1165//1 1209//1 1166//1 +f 1209//1 1210//1 1166//1 +f 1166//1 1210//1 1167//1 +f 1210//1 1211//1 1167//1 +f 1167//1 1211//1 1168//1 +f 1211//1 1212//1 1168//1 +f 1168//1 1212//1 1169//1 +f 1212//1 1213//1 1169//1 +f 1169//1 1213//1 1170//1 +f 1213//1 1214//1 1170//1 +f 1170//1 1214//1 1171//1 +f 1214//1 1215//1 1171//1 +f 1171//1 1215//1 1172//1 +f 1215//1 1216//1 1172//1 +f 1172//1 1216//1 1173//1 +f 1216//1 1217//1 1173//1 +f 1173//1 1217//1 1174//1 +f 1217//1 1218//1 1174//1 +f 1174//1 1218//1 1175//1 +f 1218//1 1219//1 1175//1 +f 1175//1 1219//1 1176//1 +f 1219//1 1220//1 1176//1 +f 1176//1 1220//1 1177//1 +f 1220//1 1221//1 1177//1 +f 1177//1 1221//1 1178//1 +f 1221//1 1222//1 1178//1 +f 1178//1 1222//1 1179//1 +f 1222//1 1223//1 1179//1 +f 1179//1 1223//1 1180//1 +f 1223//1 1224//1 1180//1 +f 1180//1 1224//1 1181//1 +f 1224//1 1225//1 1181//1 +f 1181//1 1225//1 1182//1 +f 1225//1 1226//1 1182//1 +f 1182//1 1226//1 1183//1 +f 1226//1 1227//1 1183//1 +f 1183//1 1227//1 1184//1 +f 1227//1 1228//1 1184//1 +f 1184//1 1228//1 1185//1 +f 1228//1 1229//1 1185//1 +f 1185//1 1229//1 1186//1 +f 1229//1 1230//1 1186//1 +f 1186//1 1230//1 1187//1 +f 1230//1 1231//1 1187//1 +f 1187//1 1231//1 1188//1 +f 1231//1 1232//1 1188//1 +f 1188//1 1232//1 1189//1 +f 1232//1 1233//1 1189//1 +f 1189//1 1233//1 1190//1 +f 1233//1 1234//1 1190//1 +f 1190//1 1234//1 1191//1 +f 1234//1 1235//1 1191//1 +f 1191//1 1235//1 1192//1 +f 1235//1 1236//1 1192//1 +f 1192//1 1236//1 1193//1 +f 1236//1 1237//1 1193//1 +f 1193//1 1237//1 1194//1 +f 1237//1 1238//1 1194//1 +f 1194//1 1238//1 1195//1 +f 1238//1 1239//1 1195//1 +f 1195//1 1239//1 1196//1 +f 1239//1 1240//1 1196//1 +f 1196//1 1240//1 1197//1 +f 1240//1 1241//1 1197//1 +f 1197//1 1241//1 1198//1 +f 1241//1 1242//1 1198//1 +f 1198//1 1242//1 1199//1 +f 1242//1 1243//1 1199//1 +f 1199//1 1243//1 1200//1 +f 1243//1 1244//1 1200//1 +f 1200//1 1244//1 161//1 +f 1244//1 160//1 161//1 +f 249//1 1245//1 1201//1 +f 1245//1 1246//1 1201//1 +f 1201//1 1246//1 1202//1 +f 1246//1 1247//1 1202//1 +f 1202//1 1247//1 1203//1 +f 1247//1 1248//1 1203//1 +f 1203//1 1248//1 1204//1 +f 1248//1 1249//1 1204//1 +f 1204//1 1249//1 1205//1 +f 1249//1 1250//1 1205//1 +f 1205//1 1250//1 1206//1 +f 1250//1 1251//1 1206//1 +f 1206//1 1251//1 1207//1 +f 1251//1 1252//1 1207//1 +f 1207//1 1252//1 1208//1 +f 1252//1 1253//1 1208//1 +f 1208//1 1253//1 1209//1 +f 1253//1 1254//1 1209//1 +f 1209//1 1254//1 1210//1 +f 1254//1 1255//1 1210//1 +f 1210//1 1255//1 1211//1 +f 1255//1 1256//1 1211//1 +f 1211//1 1256//1 1212//1 +f 1256//1 1257//1 1212//1 +f 1212//1 1257//1 1213//1 +f 1257//1 1258//1 1213//1 +f 1213//1 1258//1 1214//1 +f 1258//1 1259//1 1214//1 +f 1214//1 1259//1 1215//1 +f 1259//1 1260//1 1215//1 +f 1215//1 1260//1 1216//1 +f 1260//1 1261//1 1216//1 +f 1216//1 1261//1 1217//1 +f 1261//1 1262//1 1217//1 +f 1217//1 1262//1 1218//1 +f 1262//1 1263//1 1218//1 +f 1218//1 1263//1 1219//1 +f 1263//1 1264//1 1219//1 +f 1219//1 1264//1 1220//1 +f 1264//1 1265//1 1220//1 +f 1220//1 1265//1 1221//1 +f 1265//1 1266//1 1221//1 +f 1221//1 1266//1 1222//1 +f 1266//1 1267//1 1222//1 +f 1222//1 1267//1 1223//1 +f 1267//1 1268//1 1223//1 +f 1223//1 1268//1 1224//1 +f 1268//1 1269//1 1224//1 +f 1224//1 1269//1 1225//1 +f 1269//1 1270//1 1225//1 +f 1225//1 1270//1 1226//1 +f 1270//1 1271//1 1226//1 +f 1226//1 1271//1 1227//1 +f 1271//1 1272//1 1227//1 +f 1227//1 1272//1 1228//1 +f 1272//1 1273//1 1228//1 +f 1228//1 1273//1 1229//1 +f 1273//1 1274//1 1229//1 +f 1229//1 1274//1 1230//1 +f 1274//1 1275//1 1230//1 +f 1230//1 1275//1 1231//1 +f 1275//1 1276//1 1231//1 +f 1231//1 1276//1 1232//1 +f 1276//1 1277//1 1232//1 +f 1232//1 1277//1 1233//1 +f 1277//1 1278//1 1233//1 +f 1233//1 1278//1 1234//1 +f 1278//1 1279//1 1234//1 +f 1234//1 1279//1 1235//1 +f 1279//1 1280//1 1235//1 +f 1235//1 1280//1 1236//1 +f 1280//1 1281//1 1236//1 +f 1236//1 1281//1 1237//1 +f 1281//1 1282//1 1237//1 +f 1237//1 1282//1 1238//1 +f 1282//1 1283//1 1238//1 +f 1238//1 1283//1 1239//1 +f 1283//1 1284//1 1239//1 +f 1239//1 1284//1 1240//1 +f 1284//1 1285//1 1240//1 +f 1240//1 1285//1 1241//1 +f 1285//1 1286//1 1241//1 +f 1241//1 1286//1 1242//1 +f 1286//1 1287//1 1242//1 +f 1242//1 1287//1 1243//1 +f 1287//1 1288//1 1243//1 +f 1243//1 1288//1 1244//1 +f 1288//1 1289//1 1244//1 +f 1244//1 1289//1 160//1 +f 1289//1 159//1 160//1 +f 250//1 1290//1 1245//1 +f 1290//1 1291//1 1245//1 +f 1245//1 1291//1 1246//1 +f 1291//1 1292//1 1246//1 +f 1246//1 1292//1 1247//1 +f 1292//1 1293//1 1247//1 +f 1247//1 1293//1 1248//1 +f 1293//1 1294//1 1248//1 +f 1248//1 1294//1 1249//1 +f 1294//1 1295//1 1249//1 +f 1249//1 1295//1 1250//1 +f 1295//1 1296//1 1250//1 +f 1250//1 1296//1 1251//1 +f 1296//1 1297//1 1251//1 +f 1251//1 1297//1 1252//1 +f 1297//1 1298//1 1252//1 +f 1252//1 1298//1 1253//1 +f 1298//1 1299//1 1253//1 +f 1253//1 1299//1 1254//1 +f 1299//1 1300//1 1254//1 +f 1254//1 1300//1 1255//1 +f 1300//1 1301//1 1255//1 +f 1255//1 1301//1 1256//1 +f 1301//1 1302//1 1256//1 +f 1256//1 1302//1 1257//1 +f 1302//1 1303//1 1257//1 +f 1257//1 1303//1 1258//1 +f 1303//1 1304//1 1258//1 +f 1258//1 1304//1 1259//1 +f 1304//1 1305//1 1259//1 +f 1259//1 1305//1 1260//1 +f 1305//1 1306//1 1260//1 +f 1260//1 1306//1 1261//1 +f 1306//1 1307//1 1261//1 +f 1261//1 1307//1 1262//1 +f 1307//1 1308//1 1262//1 +f 1262//1 1308//1 1263//1 +f 1308//1 1309//1 1263//1 +f 1263//1 1309//1 1264//1 +f 1309//1 1310//1 1264//1 +f 1264//1 1310//1 1265//1 +f 1310//1 1311//1 1265//1 +f 1265//1 1311//1 1266//1 +f 1311//1 1312//1 1266//1 +f 1266//1 1312//1 1267//1 +f 1312//1 1313//1 1267//1 +f 1267//1 1313//1 1268//1 +f 1313//1 1314//1 1268//1 +f 1268//1 1314//1 1269//1 +f 1314//1 1315//1 1269//1 +f 1269//1 1315//1 1270//1 +f 1315//1 1316//1 1270//1 +f 1270//1 1316//1 1271//1 +f 1316//1 1317//1 1271//1 +f 1271//1 1317//1 1272//1 +f 1317//1 1318//1 1272//1 +f 1272//1 1318//1 1273//1 +f 1318//1 1319//1 1273//1 +f 1273//1 1319//1 1274//1 +f 1319//1 1320//1 1274//1 +f 1274//1 1320//1 1275//1 +f 1320//1 1321//1 1275//1 +f 1275//1 1321//1 1276//1 +f 1321//1 1322//1 1276//1 +f 1276//1 1322//1 1277//1 +f 1322//1 1323//1 1277//1 +f 1277//1 1323//1 1278//1 +f 1323//1 1324//1 1278//1 +f 1278//1 1324//1 1279//1 +f 1324//1 1325//1 1279//1 +f 1279//1 1325//1 1280//1 +f 1325//1 1326//1 1280//1 +f 1280//1 1326//1 1281//1 +f 1326//1 1327//1 1281//1 +f 1281//1 1327//1 1282//1 +f 1327//1 1328//1 1282//1 +f 1282//1 1328//1 1283//1 +f 1328//1 1329//1 1283//1 +f 1283//1 1329//1 1284//1 +f 1329//1 1330//1 1284//1 +f 1284//1 1330//1 1285//1 +f 1330//1 1331//1 1285//1 +f 1285//1 1331//1 1286//1 +f 1331//1 1332//1 1286//1 +f 1286//1 1332//1 1287//1 +f 1332//1 1333//1 1287//1 +f 1287//1 1333//1 1288//1 +f 1333//1 1334//1 1288//1 +f 1288//1 1334//1 1289//1 +f 1334//1 1335//1 1289//1 +f 1289//1 1335//1 159//1 +f 1335//1 158//1 159//1 +f 251//1 1336//1 1290//1 +f 1336//1 1337//1 1290//1 +f 1290//1 1337//1 1291//1 +f 1337//1 1338//1 1291//1 +f 1291//1 1338//1 1292//1 +f 1338//1 1339//1 1292//1 +f 1292//1 1339//1 1293//1 +f 1339//1 1340//1 1293//1 +f 1293//1 1340//1 1294//1 +f 1340//1 1341//1 1294//1 +f 1294//1 1341//1 1295//1 +f 1341//1 1342//1 1295//1 +f 1295//1 1342//1 1296//1 +f 1342//1 1343//1 1296//1 +f 1296//1 1343//1 1297//1 +f 1343//1 1344//1 1297//1 +f 1297//1 1344//1 1298//1 +f 1344//1 1345//1 1298//1 +f 1298//1 1345//1 1299//1 +f 1345//1 1346//1 1299//1 +f 1299//1 1346//1 1300//1 +f 1346//1 1347//1 1300//1 +f 1300//1 1347//1 1301//1 +f 1347//1 1348//1 1301//1 +f 1301//1 1348//1 1302//1 +f 1348//1 1349//1 1302//1 +f 1302//1 1349//1 1303//1 +f 1349//1 1350//1 1303//1 +f 1303//1 1350//1 1304//1 +f 1350//1 1351//1 1304//1 +f 1304//1 1351//1 1305//1 +f 1351//1 1352//1 1305//1 +f 1305//1 1352//1 1306//1 +f 1352//1 1353//1 1306//1 +f 1306//1 1353//1 1307//1 +f 1353//1 1354//1 1307//1 +f 1307//1 1354//1 1308//1 +f 1354//1 1355//1 1308//1 +f 1308//1 1355//1 1309//1 +f 1355//1 1356//1 1309//1 +f 1309//1 1356//1 1310//1 +f 1356//1 1357//1 1310//1 +f 1310//1 1357//1 1311//1 +f 1357//1 1358//1 1311//1 +f 1311//1 1358//1 1312//1 +f 1358//1 1359//1 1312//1 +f 1312//1 1359//1 1313//1 +f 1359//1 1360//1 1313//1 +f 1313//1 1360//1 1314//1 +f 1360//1 1361//1 1314//1 +f 1314//1 1361//1 1315//1 +f 1361//1 1362//1 1315//1 +f 1315//1 1362//1 1316//1 +f 1362//1 1363//1 1316//1 +f 1316//1 1363//1 1317//1 +f 1363//1 1364//1 1317//1 +f 1317//1 1364//1 1318//1 +f 1364//1 1365//1 1318//1 +f 1318//1 1365//1 1319//1 +f 1365//1 1366//1 1319//1 +f 1319//1 1366//1 1320//1 +f 1366//1 1367//1 1320//1 +f 1320//1 1367//1 1321//1 +f 1367//1 1368//1 1321//1 +f 1321//1 1368//1 1322//1 +f 1368//1 1369//1 1322//1 +f 1322//1 1369//1 1323//1 +f 1369//1 1370//1 1323//1 +f 1323//1 1370//1 1324//1 +f 1370//1 1371//1 1324//1 +f 1324//1 1371//1 1325//1 +f 1371//1 1372//1 1325//1 +f 1325//1 1372//1 1326//1 +f 1372//1 1373//1 1326//1 +f 1326//1 1373//1 1327//1 +f 1373//1 1374//1 1327//1 +f 1327//1 1374//1 1328//1 +f 1374//1 1375//1 1328//1 +f 1328//1 1375//1 1329//1 +f 1375//1 1376//1 1329//1 +f 1329//1 1376//1 1330//1 +f 1376//1 1377//1 1330//1 +f 1330//1 1377//1 1331//1 +f 1377//1 1378//1 1331//1 +f 1331//1 1378//1 1332//1 +f 1378//1 1379//1 1332//1 +f 1332//1 1379//1 1333//1 +f 1379//1 1380//1 1333//1 +f 1333//1 1380//1 1334//1 +f 1380//1 1381//1 1334//1 +f 1334//1 1381//1 1335//1 +f 1381//1 1382//1 1335//1 +f 1335//1 1382//1 158//1 +f 1382//1 157//1 158//1 +f 252//1 1383//1 1336//1 +f 1383//1 1384//1 1336//1 +f 1336//1 1384//1 1337//1 +f 1384//1 1385//1 1337//1 +f 1337//1 1385//1 1338//1 +f 1385//1 1386//1 1338//1 +f 1338//1 1386//1 1339//1 +f 1386//1 1387//1 1339//1 +f 1339//1 1387//1 1340//1 +f 1387//1 1388//1 1340//1 +f 1340//1 1388//1 1341//1 +f 1388//1 1389//1 1341//1 +f 1341//1 1389//1 1342//1 +f 1389//1 1390//1 1342//1 +f 1342//1 1390//1 1343//1 +f 1390//1 1391//1 1343//1 +f 1343//1 1391//1 1344//1 +f 1391//1 1392//1 1344//1 +f 1344//1 1392//1 1345//1 +f 1392//1 1393//1 1345//1 +f 1345//1 1393//1 1346//1 +f 1393//1 1394//1 1346//1 +f 1346//1 1394//1 1347//1 +f 1394//1 1395//1 1347//1 +f 1347//1 1395//1 1348//1 +f 1395//1 1396//1 1348//1 +f 1348//1 1396//1 1349//1 +f 1396//1 1397//1 1349//1 +f 1349//1 1397//1 1350//1 +f 1397//1 1398//1 1350//1 +f 1350//1 1398//1 1351//1 +f 1398//1 1399//1 1351//1 +f 1351//1 1399//1 1352//1 +f 1399//1 1400//1 1352//1 +f 1352//1 1400//1 1353//1 +f 1400//1 1401//1 1353//1 +f 1353//1 1401//1 1354//1 +f 1401//1 1402//1 1354//1 +f 1354//1 1402//1 1355//1 +f 1402//1 1403//1 1355//1 +f 1355//1 1403//1 1356//1 +f 1403//1 1404//1 1356//1 +f 1356//1 1404//1 1357//1 +f 1404//1 1405//1 1357//1 +f 1357//1 1405//1 1358//1 +f 1405//1 1406//1 1358//1 +f 1358//1 1406//1 1359//1 +f 1406//1 1407//1 1359//1 +f 1359//1 1407//1 1360//1 +f 1407//1 1408//1 1360//1 +f 1360//1 1408//1 1361//1 +f 1408//1 1409//1 1361//1 +f 1361//1 1409//1 1362//1 +f 1409//1 1410//1 1362//1 +f 1362//1 1410//1 1363//1 +f 1410//1 1411//1 1363//1 +f 1363//1 1411//1 1364//1 +f 1411//1 1412//1 1364//1 +f 1364//1 1412//1 1365//1 +f 1412//1 1413//1 1365//1 +f 1365//1 1413//1 1366//1 +f 1413//1 1414//1 1366//1 +f 1366//1 1414//1 1367//1 +f 1414//1 1415//1 1367//1 +f 1367//1 1415//1 1368//1 +f 1415//1 1416//1 1368//1 +f 1368//1 1416//1 1369//1 +f 1416//1 1417//1 1369//1 +f 1369//1 1417//1 1370//1 +f 1417//1 1418//1 1370//1 +f 1370//1 1418//1 1371//1 +f 1418//1 1419//1 1371//1 +f 1371//1 1419//1 1372//1 +f 1419//1 1420//1 1372//1 +f 1372//1 1420//1 1373//1 +f 1420//1 1421//1 1373//1 +f 1373//1 1421//1 1374//1 +f 1421//1 1422//1 1374//1 +f 1374//1 1422//1 1375//1 +f 1422//1 1423//1 1375//1 +f 1375//1 1423//1 1376//1 +f 1423//1 1424//1 1376//1 +f 1376//1 1424//1 1377//1 +f 1424//1 1425//1 1377//1 +f 1377//1 1425//1 1378//1 +f 1425//1 1426//1 1378//1 +f 1378//1 1426//1 1379//1 +f 1426//1 1427//1 1379//1 +f 1379//1 1427//1 1380//1 +f 1427//1 1428//1 1380//1 +f 1380//1 1428//1 1381//1 +f 1428//1 1429//1 1381//1 +f 1381//1 1429//1 1382//1 +f 1429//1 1430//1 1382//1 +f 1382//1 1430//1 157//1 +f 1430//1 156//1 157//1 +f 253//1 1431//1 1383//1 +f 1431//1 1432//1 1383//1 +f 1383//1 1432//1 1384//1 +f 1432//1 1433//1 1384//1 +f 1384//1 1433//1 1385//1 +f 1433//1 1434//1 1385//1 +f 1385//1 1434//1 1386//1 +f 1434//1 1435//1 1386//1 +f 1386//1 1435//1 1387//1 +f 1435//1 1436//1 1387//1 +f 1387//1 1436//1 1388//1 +f 1436//1 1437//1 1388//1 +f 1388//1 1437//1 1389//1 +f 1437//1 1438//1 1389//1 +f 1389//1 1438//1 1390//1 +f 1438//1 1439//1 1390//1 +f 1390//1 1439//1 1391//1 +f 1439//1 1440//1 1391//1 +f 1391//1 1440//1 1392//1 +f 1440//1 1441//1 1392//1 +f 1392//1 1441//1 1393//1 +f 1441//1 1442//1 1393//1 +f 1393//1 1442//1 1394//1 +f 1442//1 1443//1 1394//1 +f 1394//1 1443//1 1395//1 +f 1443//1 1444//1 1395//1 +f 1395//1 1444//1 1396//1 +f 1444//1 1445//1 1396//1 +f 1396//1 1445//1 1397//1 +f 1445//1 1446//1 1397//1 +f 1397//1 1446//1 1398//1 +f 1446//1 1447//1 1398//1 +f 1398//1 1447//1 1399//1 +f 1447//1 1448//1 1399//1 +f 1399//1 1448//1 1400//1 +f 1448//1 1449//1 1400//1 +f 1400//1 1449//1 1401//1 +f 1449//1 1450//1 1401//1 +f 1401//1 1450//1 1402//1 +f 1450//1 1451//1 1402//1 +f 1402//1 1451//1 1403//1 +f 1451//1 1452//1 1403//1 +f 1403//1 1452//1 1404//1 +f 1452//1 1453//1 1404//1 +f 1404//1 1453//1 1405//1 +f 1453//1 1454//1 1405//1 +f 1405//1 1454//1 1406//1 +f 1454//1 1455//1 1406//1 +f 1406//1 1455//1 1407//1 +f 1455//1 1456//1 1407//1 +f 1407//1 1456//1 1408//1 +f 1456//1 1457//1 1408//1 +f 1408//1 1457//1 1409//1 +f 1457//1 1458//1 1409//1 +f 1409//1 1458//1 1410//1 +f 1458//1 1459//1 1410//1 +f 1410//1 1459//1 1411//1 +f 1459//1 1460//1 1411//1 +f 1411//1 1460//1 1412//1 +f 1460//1 1461//1 1412//1 +f 1412//1 1461//1 1413//1 +f 1461//1 1462//1 1413//1 +f 1413//1 1462//1 1414//1 +f 1462//1 1463//1 1414//1 +f 1414//1 1463//1 1415//1 +f 1463//1 1464//1 1415//1 +f 1415//1 1464//1 1416//1 +f 1464//1 1465//1 1416//1 +f 1416//1 1465//1 1417//1 +f 1465//1 1466//1 1417//1 +f 1417//1 1466//1 1418//1 +f 1466//1 1467//1 1418//1 +f 1418//1 1467//1 1419//1 +f 1467//1 1468//1 1419//1 +f 1419//1 1468//1 1420//1 +f 1468//1 1469//1 1420//1 +f 1420//1 1469//1 1421//1 +f 1469//1 1470//1 1421//1 +f 1421//1 1470//1 1422//1 +f 1470//1 1471//1 1422//1 +f 1422//1 1471//1 1423//1 +f 1471//1 1472//1 1423//1 +f 1423//1 1472//1 1424//1 +f 1472//1 1473//1 1424//1 +f 1424//1 1473//1 1425//1 +f 1473//1 1474//1 1425//1 +f 1425//1 1474//1 1426//1 +f 1474//1 1475//1 1426//1 +f 1426//1 1475//1 1427//1 +f 1475//1 1476//1 1427//1 +f 1427//1 1476//1 1428//1 +f 1476//1 1477//1 1428//1 +f 1428//1 1477//1 1429//1 +f 1477//1 1478//1 1429//1 +f 1429//1 1478//1 1430//1 +f 1478//1 1479//1 1430//1 +f 1430//1 1479//1 156//1 +f 1479//1 155//1 156//1 +f 254//1 105//1 1431//1 +f 105//1 106//1 1431//1 +f 1431//1 106//1 1432//1 +f 106//1 107//1 1432//1 +f 1432//1 107//1 1433//1 +f 107//1 108//1 1433//1 +f 1433//1 108//1 1434//1 +f 108//1 109//1 1434//1 +f 1434//1 109//1 1435//1 +f 109//1 110//1 1435//1 +f 1435//1 110//1 1436//1 +f 110//1 111//1 1436//1 +f 1436//1 111//1 1437//1 +f 111//1 112//1 1437//1 +f 1437//1 112//1 1438//1 +f 112//1 113//1 1438//1 +f 1438//1 113//1 1439//1 +f 113//1 114//1 1439//1 +f 1439//1 114//1 1440//1 +f 114//1 115//1 1440//1 +f 1440//1 115//1 1441//1 +f 115//1 116//1 1441//1 +f 1441//1 116//1 1442//1 +f 116//1 117//1 1442//1 +f 1442//1 117//1 1443//1 +f 117//1 118//1 1443//1 +f 1443//1 118//1 1444//1 +f 118//1 119//1 1444//1 +f 1444//1 119//1 1445//1 +f 119//1 120//1 1445//1 +f 1445//1 120//1 1446//1 +f 120//1 121//1 1446//1 +f 1446//1 121//1 1447//1 +f 121//1 122//1 1447//1 +f 1447//1 122//1 1448//1 +f 122//1 123//1 1448//1 +f 1448//1 123//1 1449//1 +f 123//1 124//1 1449//1 +f 1449//1 124//1 1450//1 +f 124//1 125//1 1450//1 +f 1450//1 125//1 1451//1 +f 125//1 126//1 1451//1 +f 1451//1 126//1 1452//1 +f 126//1 127//1 1452//1 +f 1452//1 127//1 1453//1 +f 127//1 128//1 1453//1 +f 1453//1 128//1 1454//1 +f 128//1 129//1 1454//1 +f 1454//1 129//1 1455//1 +f 129//1 130//1 1455//1 +f 1455//1 130//1 1456//1 +f 130//1 131//1 1456//1 +f 1456//1 131//1 1457//1 +f 131//1 132//1 1457//1 +f 1457//1 132//1 1458//1 +f 132//1 133//1 1458//1 +f 1458//1 133//1 1459//1 +f 133//1 134//1 1459//1 +f 1459//1 134//1 1460//1 +f 134//1 135//1 1460//1 +f 1460//1 135//1 1461//1 +f 135//1 136//1 1461//1 +f 1461//1 136//1 1462//1 +f 136//1 137//1 1462//1 +f 1462//1 137//1 1463//1 +f 137//1 138//1 1463//1 +f 1463//1 138//1 1464//1 +f 138//1 139//1 1464//1 +f 1464//1 139//1 1465//1 +f 139//1 140//1 1465//1 +f 1465//1 140//1 1466//1 +f 140//1 141//1 1466//1 +f 1466//1 141//1 1467//1 +f 141//1 142//1 1467//1 +f 1467//1 142//1 1468//1 +f 142//1 143//1 1468//1 +f 1468//1 143//1 1469//1 +f 143//1 144//1 1469//1 +f 1469//1 144//1 1470//1 +f 144//1 145//1 1470//1 +f 1470//1 145//1 1471//1 +f 145//1 146//1 1471//1 +f 1471//1 146//1 1472//1 +f 146//1 147//1 1472//1 +f 1472//1 147//1 1473//1 +f 147//1 148//1 1473//1 +f 1473//1 148//1 1474//1 +f 148//1 149//1 1474//1 +f 1474//1 149//1 1475//1 +f 149//1 150//1 1475//1 +f 1475//1 150//1 1476//1 +f 150//1 151//1 1476//1 +f 1476//1 151//1 1477//1 +f 151//1 152//1 1477//1 +f 1477//1 152//1 1478//1 +f 152//1 153//1 1478//1 +f 1478//1 153//1 1479//1 +f 153//1 154//1 1479//1 +f 1479//1 154//1 155//1 +f 154//1 4//1 155//1 +f 55//1 54//1 1//1 +f 56//1 1480//1 55//1 +f 57//1 1481//1 56//1 +f 58//1 1483//1 57//1 +f 59//1 1486//1 58//1 +f 60//1 1490//1 59//1 +f 61//1 1495//1 60//1 +f 62//1 1501//1 61//1 +f 63//1 1508//1 62//1 +f 64//1 1516//1 63//1 +f 65//1 1525//1 64//1 +f 66//1 1535//1 65//1 +f 67//1 1546//1 66//1 +f 68//1 1558//1 67//1 +f 69//1 1571//1 68//1 +f 70//1 1585//1 69//1 +f 71//1 1600//1 70//1 +f 72//1 1616//1 71//1 +f 73//1 1633//1 72//1 +f 74//1 1651//1 73//1 +f 75//1 1670//1 74//1 +f 76//1 1690//1 75//1 +f 77//1 1711//1 76//1 +f 78//1 1733//1 77//1 +f 79//1 1756//1 78//1 +f 80//1 1780//1 79//1 +f 81//1 1805//1 80//1 +f 82//1 1831//1 81//1 +f 83//1 1858//1 82//1 +f 84//1 1886//1 83//1 +f 85//1 1915//1 84//1 +f 86//1 1945//1 85//1 +f 87//1 1976//1 86//1 +f 88//1 2008//1 87//1 +f 89//1 2041//1 88//1 +f 90//1 2075//1 89//1 +f 91//1 2110//1 90//1 +f 92//1 2146//1 91//1 +f 93//1 2183//1 92//1 +f 94//1 2221//1 93//1 +f 95//1 2260//1 94//1 +f 96//1 2300//1 95//1 +f 97//1 2341//1 96//1 +f 98//1 2383//1 97//1 +f 99//1 2426//1 98//1 +f 100//1 2470//1 99//1 +f 101//1 2515//1 100//1 +f 102//1 2561//1 101//1 +f 103//1 2608//1 102//1 +f 104//1 2656//1 103//1 +f 55//1 1480//1 54//1 +f 1480//1 53//1 54//1 +f 56//1 1481//1 1480//1 +f 1481//1 1482//1 1480//1 +f 1480//1 1482//1 53//1 +f 1482//1 52//1 53//1 +f 57//1 1483//1 1481//1 +f 1483//1 1484//1 1481//1 +f 1481//1 1484//1 1482//1 +f 1484//1 1485//1 1482//1 +f 1482//1 1485//1 52//1 +f 1485//1 51//1 52//1 +f 58//1 1486//1 1483//1 +f 1486//1 1487//1 1483//1 +f 1483//1 1487//1 1484//1 +f 1487//1 1488//1 1484//1 +f 1484//1 1488//1 1485//1 +f 1488//1 1489//1 1485//1 +f 1485//1 1489//1 51//1 +f 1489//1 50//1 51//1 +f 59//1 1490//1 1486//1 +f 1490//1 1491//1 1486//1 +f 1486//1 1491//1 1487//1 +f 1491//1 1492//1 1487//1 +f 1487//1 1492//1 1488//1 +f 1492//1 1493//1 1488//1 +f 1488//1 1493//1 1489//1 +f 1493//1 1494//1 1489//1 +f 1489//1 1494//1 50//1 +f 1494//1 49//1 50//1 +f 60//1 1495//1 1490//1 +f 1495//1 1496//1 1490//1 +f 1490//1 1496//1 1491//1 +f 1496//1 1497//1 1491//1 +f 1491//1 1497//1 1492//1 +f 1497//1 1498//1 1492//1 +f 1492//1 1498//1 1493//1 +f 1498//1 1499//1 1493//1 +f 1493//1 1499//1 1494//1 +f 1499//1 1500//1 1494//1 +f 1494//1 1500//1 49//1 +f 1500//1 48//1 49//1 +f 61//1 1501//1 1495//1 +f 1501//1 1502//1 1495//1 +f 1495//1 1502//1 1496//1 +f 1502//1 1503//1 1496//1 +f 1496//1 1503//1 1497//1 +f 1503//1 1504//1 1497//1 +f 1497//1 1504//1 1498//1 +f 1504//1 1505//1 1498//1 +f 1498//1 1505//1 1499//1 +f 1505//1 1506//1 1499//1 +f 1499//1 1506//1 1500//1 +f 1506//1 1507//1 1500//1 +f 1500//1 1507//1 48//1 +f 1507//1 47//1 48//1 +f 62//1 1508//1 1501//1 +f 1508//1 1509//1 1501//1 +f 1501//1 1509//1 1502//1 +f 1509//1 1510//1 1502//1 +f 1502//1 1510//1 1503//1 +f 1510//1 1511//1 1503//1 +f 1503//1 1511//1 1504//1 +f 1511//1 1512//1 1504//1 +f 1504//1 1512//1 1505//1 +f 1512//1 1513//1 1505//1 +f 1505//1 1513//1 1506//1 +f 1513//1 1514//1 1506//1 +f 1506//1 1514//1 1507//1 +f 1514//1 1515//1 1507//1 +f 1507//1 1515//1 47//1 +f 1515//1 46//1 47//1 +f 63//1 1516//1 1508//1 +f 1516//1 1517//1 1508//1 +f 1508//1 1517//1 1509//1 +f 1517//1 1518//1 1509//1 +f 1509//1 1518//1 1510//1 +f 1518//1 1519//1 1510//1 +f 1510//1 1519//1 1511//1 +f 1519//1 1520//1 1511//1 +f 1511//1 1520//1 1512//1 +f 1520//1 1521//1 1512//1 +f 1512//1 1521//1 1513//1 +f 1521//1 1522//1 1513//1 +f 1513//1 1522//1 1514//1 +f 1522//1 1523//1 1514//1 +f 1514//1 1523//1 1515//1 +f 1523//1 1524//1 1515//1 +f 1515//1 1524//1 46//1 +f 1524//1 45//1 46//1 +f 64//1 1525//1 1516//1 +f 1525//1 1526//1 1516//1 +f 1516//1 1526//1 1517//1 +f 1526//1 1527//1 1517//1 +f 1517//1 1527//1 1518//1 +f 1527//1 1528//1 1518//1 +f 1518//1 1528//1 1519//1 +f 1528//1 1529//1 1519//1 +f 1519//1 1529//1 1520//1 +f 1529//1 1530//1 1520//1 +f 1520//1 1530//1 1521//1 +f 1530//1 1531//1 1521//1 +f 1521//1 1531//1 1522//1 +f 1531//1 1532//1 1522//1 +f 1522//1 1532//1 1523//1 +f 1532//1 1533//1 1523//1 +f 1523//1 1533//1 1524//1 +f 1533//1 1534//1 1524//1 +f 1524//1 1534//1 45//1 +f 1534//1 44//1 45//1 +f 65//1 1535//1 1525//1 +f 1535//1 1536//1 1525//1 +f 1525//1 1536//1 1526//1 +f 1536//1 1537//1 1526//1 +f 1526//1 1537//1 1527//1 +f 1537//1 1538//1 1527//1 +f 1527//1 1538//1 1528//1 +f 1538//1 1539//1 1528//1 +f 1528//1 1539//1 1529//1 +f 1539//1 1540//1 1529//1 +f 1529//1 1540//1 1530//1 +f 1540//1 1541//1 1530//1 +f 1530//1 1541//1 1531//1 +f 1541//1 1542//1 1531//1 +f 1531//1 1542//1 1532//1 +f 1542//1 1543//1 1532//1 +f 1532//1 1543//1 1533//1 +f 1543//1 1544//1 1533//1 +f 1533//1 1544//1 1534//1 +f 1544//1 1545//1 1534//1 +f 1534//1 1545//1 44//1 +f 1545//1 43//1 44//1 +f 66//1 1546//1 1535//1 +f 1546//1 1547//1 1535//1 +f 1535//1 1547//1 1536//1 +f 1547//1 1548//1 1536//1 +f 1536//1 1548//1 1537//1 +f 1548//1 1549//1 1537//1 +f 1537//1 1549//1 1538//1 +f 1549//1 1550//1 1538//1 +f 1538//1 1550//1 1539//1 +f 1550//1 1551//1 1539//1 +f 1539//1 1551//1 1540//1 +f 1551//1 1552//1 1540//1 +f 1540//1 1552//1 1541//1 +f 1552//1 1553//1 1541//1 +f 1541//1 1553//1 1542//1 +f 1553//1 1554//1 1542//1 +f 1542//1 1554//1 1543//1 +f 1554//1 1555//1 1543//1 +f 1543//1 1555//1 1544//1 +f 1555//1 1556//1 1544//1 +f 1544//1 1556//1 1545//1 +f 1556//1 1557//1 1545//1 +f 1545//1 1557//1 43//1 +f 1557//1 42//1 43//1 +f 67//1 1558//1 1546//1 +f 1558//1 1559//1 1546//1 +f 1546//1 1559//1 1547//1 +f 1559//1 1560//1 1547//1 +f 1547//1 1560//1 1548//1 +f 1560//1 1561//1 1548//1 +f 1548//1 1561//1 1549//1 +f 1561//1 1562//1 1549//1 +f 1549//1 1562//1 1550//1 +f 1562//1 1563//1 1550//1 +f 1550//1 1563//1 1551//1 +f 1563//1 1564//1 1551//1 +f 1551//1 1564//1 1552//1 +f 1564//1 1565//1 1552//1 +f 1552//1 1565//1 1553//1 +f 1565//1 1566//1 1553//1 +f 1553//1 1566//1 1554//1 +f 1566//1 1567//1 1554//1 +f 1554//1 1567//1 1555//1 +f 1567//1 1568//1 1555//1 +f 1555//1 1568//1 1556//1 +f 1568//1 1569//1 1556//1 +f 1556//1 1569//1 1557//1 +f 1569//1 1570//1 1557//1 +f 1557//1 1570//1 42//1 +f 1570//1 41//1 42//1 +f 68//1 1571//1 1558//1 +f 1571//1 1572//1 1558//1 +f 1558//1 1572//1 1559//1 +f 1572//1 1573//1 1559//1 +f 1559//1 1573//1 1560//1 +f 1573//1 1574//1 1560//1 +f 1560//1 1574//1 1561//1 +f 1574//1 1575//1 1561//1 +f 1561//1 1575//1 1562//1 +f 1575//1 1576//1 1562//1 +f 1562//1 1576//1 1563//1 +f 1576//1 1577//1 1563//1 +f 1563//1 1577//1 1564//1 +f 1577//1 1578//1 1564//1 +f 1564//1 1578//1 1565//1 +f 1578//1 1579//1 1565//1 +f 1565//1 1579//1 1566//1 +f 1579//1 1580//1 1566//1 +f 1566//1 1580//1 1567//1 +f 1580//1 1581//1 1567//1 +f 1567//1 1581//1 1568//1 +f 1581//1 1582//1 1568//1 +f 1568//1 1582//1 1569//1 +f 1582//1 1583//1 1569//1 +f 1569//1 1583//1 1570//1 +f 1583//1 1584//1 1570//1 +f 1570//1 1584//1 41//1 +f 1584//1 40//1 41//1 +f 69//1 1585//1 1571//1 +f 1585//1 1586//1 1571//1 +f 1571//1 1586//1 1572//1 +f 1586//1 1587//1 1572//1 +f 1572//1 1587//1 1573//1 +f 1587//1 1588//1 1573//1 +f 1573//1 1588//1 1574//1 +f 1588//1 1589//1 1574//1 +f 1574//1 1589//1 1575//1 +f 1589//1 1590//1 1575//1 +f 1575//1 1590//1 1576//1 +f 1590//1 1591//1 1576//1 +f 1576//1 1591//1 1577//1 +f 1591//1 1592//1 1577//1 +f 1577//1 1592//1 1578//1 +f 1592//1 1593//1 1578//1 +f 1578//1 1593//1 1579//1 +f 1593//1 1594//1 1579//1 +f 1579//1 1594//1 1580//1 +f 1594//1 1595//1 1580//1 +f 1580//1 1595//1 1581//1 +f 1595//1 1596//1 1581//1 +f 1581//1 1596//1 1582//1 +f 1596//1 1597//1 1582//1 +f 1582//1 1597//1 1583//1 +f 1597//1 1598//1 1583//1 +f 1583//1 1598//1 1584//1 +f 1598//1 1599//1 1584//1 +f 1584//1 1599//1 40//1 +f 1599//1 39//1 40//1 +f 70//1 1600//1 1585//1 +f 1600//1 1601//1 1585//1 +f 1585//1 1601//1 1586//1 +f 1601//1 1602//1 1586//1 +f 1586//1 1602//1 1587//1 +f 1602//1 1603//1 1587//1 +f 1587//1 1603//1 1588//1 +f 1603//1 1604//1 1588//1 +f 1588//1 1604//1 1589//1 +f 1604//1 1605//1 1589//1 +f 1589//1 1605//1 1590//1 +f 1605//1 1606//1 1590//1 +f 1590//1 1606//1 1591//1 +f 1606//1 1607//1 1591//1 +f 1591//1 1607//1 1592//1 +f 1607//1 1608//1 1592//1 +f 1592//1 1608//1 1593//1 +f 1608//1 1609//1 1593//1 +f 1593//1 1609//1 1594//1 +f 1609//1 1610//1 1594//1 +f 1594//1 1610//1 1595//1 +f 1610//1 1611//1 1595//1 +f 1595//1 1611//1 1596//1 +f 1611//1 1612//1 1596//1 +f 1596//1 1612//1 1597//1 +f 1612//1 1613//1 1597//1 +f 1597//1 1613//1 1598//1 +f 1613//1 1614//1 1598//1 +f 1598//1 1614//1 1599//1 +f 1614//1 1615//1 1599//1 +f 1599//1 1615//1 39//1 +f 1615//1 38//1 39//1 +f 71//1 1616//1 1600//1 +f 1616//1 1617//1 1600//1 +f 1600//1 1617//1 1601//1 +f 1617//1 1618//1 1601//1 +f 1601//1 1618//1 1602//1 +f 1618//1 1619//1 1602//1 +f 1602//1 1619//1 1603//1 +f 1619//1 1620//1 1603//1 +f 1603//1 1620//1 1604//1 +f 1620//1 1621//1 1604//1 +f 1604//1 1621//1 1605//1 +f 1621//1 1622//1 1605//1 +f 1605//1 1622//1 1606//1 +f 1622//1 1623//1 1606//1 +f 1606//1 1623//1 1607//1 +f 1623//1 1624//1 1607//1 +f 1607//1 1624//1 1608//1 +f 1624//1 1625//1 1608//1 +f 1608//1 1625//1 1609//1 +f 1625//1 1626//1 1609//1 +f 1609//1 1626//1 1610//1 +f 1626//1 1627//1 1610//1 +f 1610//1 1627//1 1611//1 +f 1627//1 1628//1 1611//1 +f 1611//1 1628//1 1612//1 +f 1628//1 1629//1 1612//1 +f 1612//1 1629//1 1613//1 +f 1629//1 1630//1 1613//1 +f 1613//1 1630//1 1614//1 +f 1630//1 1631//1 1614//1 +f 1614//1 1631//1 1615//1 +f 1631//1 1632//1 1615//1 +f 1615//1 1632//1 38//1 +f 1632//1 37//1 38//1 +f 72//1 1633//1 1616//1 +f 1633//1 1634//1 1616//1 +f 1616//1 1634//1 1617//1 +f 1634//1 1635//1 1617//1 +f 1617//1 1635//1 1618//1 +f 1635//1 1636//1 1618//1 +f 1618//1 1636//1 1619//1 +f 1636//1 1637//1 1619//1 +f 1619//1 1637//1 1620//1 +f 1637//1 1638//1 1620//1 +f 1620//1 1638//1 1621//1 +f 1638//1 1639//1 1621//1 +f 1621//1 1639//1 1622//1 +f 1639//1 1640//1 1622//1 +f 1622//1 1640//1 1623//1 +f 1640//1 1641//1 1623//1 +f 1623//1 1641//1 1624//1 +f 1641//1 1642//1 1624//1 +f 1624//1 1642//1 1625//1 +f 1642//1 1643//1 1625//1 +f 1625//1 1643//1 1626//1 +f 1643//1 1644//1 1626//1 +f 1626//1 1644//1 1627//1 +f 1644//1 1645//1 1627//1 +f 1627//1 1645//1 1628//1 +f 1645//1 1646//1 1628//1 +f 1628//1 1646//1 1629//1 +f 1646//1 1647//1 1629//1 +f 1629//1 1647//1 1630//1 +f 1647//1 1648//1 1630//1 +f 1630//1 1648//1 1631//1 +f 1648//1 1649//1 1631//1 +f 1631//1 1649//1 1632//1 +f 1649//1 1650//1 1632//1 +f 1632//1 1650//1 37//1 +f 1650//1 36//1 37//1 +f 73//1 1651//1 1633//1 +f 1651//1 1652//1 1633//1 +f 1633//1 1652//1 1634//1 +f 1652//1 1653//1 1634//1 +f 1634//1 1653//1 1635//1 +f 1653//1 1654//1 1635//1 +f 1635//1 1654//1 1636//1 +f 1654//1 1655//1 1636//1 +f 1636//1 1655//1 1637//1 +f 1655//1 1656//1 1637//1 +f 1637//1 1656//1 1638//1 +f 1656//1 1657//1 1638//1 +f 1638//1 1657//1 1639//1 +f 1657//1 1658//1 1639//1 +f 1639//1 1658//1 1640//1 +f 1658//1 1659//1 1640//1 +f 1640//1 1659//1 1641//1 +f 1659//1 1660//1 1641//1 +f 1641//1 1660//1 1642//1 +f 1660//1 1661//1 1642//1 +f 1642//1 1661//1 1643//1 +f 1661//1 1662//1 1643//1 +f 1643//1 1662//1 1644//1 +f 1662//1 1663//1 1644//1 +f 1644//1 1663//1 1645//1 +f 1663//1 1664//1 1645//1 +f 1645//1 1664//1 1646//1 +f 1664//1 1665//1 1646//1 +f 1646//1 1665//1 1647//1 +f 1665//1 1666//1 1647//1 +f 1647//1 1666//1 1648//1 +f 1666//1 1667//1 1648//1 +f 1648//1 1667//1 1649//1 +f 1667//1 1668//1 1649//1 +f 1649//1 1668//1 1650//1 +f 1668//1 1669//1 1650//1 +f 1650//1 1669//1 36//1 +f 1669//1 35//1 36//1 +f 74//1 1670//1 1651//1 +f 1670//1 1671//1 1651//1 +f 1651//1 1671//1 1652//1 +f 1671//1 1672//1 1652//1 +f 1652//1 1672//1 1653//1 +f 1672//1 1673//1 1653//1 +f 1653//1 1673//1 1654//1 +f 1673//1 1674//1 1654//1 +f 1654//1 1674//1 1655//1 +f 1674//1 1675//1 1655//1 +f 1655//1 1675//1 1656//1 +f 1675//1 1676//1 1656//1 +f 1656//1 1676//1 1657//1 +f 1676//1 1677//1 1657//1 +f 1657//1 1677//1 1658//1 +f 1677//1 1678//1 1658//1 +f 1658//1 1678//1 1659//1 +f 1678//1 1679//1 1659//1 +f 1659//1 1679//1 1660//1 +f 1679//1 1680//1 1660//1 +f 1660//1 1680//1 1661//1 +f 1680//1 1681//1 1661//1 +f 1661//1 1681//1 1662//1 +f 1681//1 1682//1 1662//1 +f 1662//1 1682//1 1663//1 +f 1682//1 1683//1 1663//1 +f 1663//1 1683//1 1664//1 +f 1683//1 1684//1 1664//1 +f 1664//1 1684//1 1665//1 +f 1684//1 1685//1 1665//1 +f 1665//1 1685//1 1666//1 +f 1685//1 1686//1 1666//1 +f 1666//1 1686//1 1667//1 +f 1686//1 1687//1 1667//1 +f 1667//1 1687//1 1668//1 +f 1687//1 1688//1 1668//1 +f 1668//1 1688//1 1669//1 +f 1688//1 1689//1 1669//1 +f 1669//1 1689//1 35//1 +f 1689//1 34//1 35//1 +f 75//1 1690//1 1670//1 +f 1690//1 1691//1 1670//1 +f 1670//1 1691//1 1671//1 +f 1691//1 1692//1 1671//1 +f 1671//1 1692//1 1672//1 +f 1692//1 1693//1 1672//1 +f 1672//1 1693//1 1673//1 +f 1693//1 1694//1 1673//1 +f 1673//1 1694//1 1674//1 +f 1694//1 1695//1 1674//1 +f 1674//1 1695//1 1675//1 +f 1695//1 1696//1 1675//1 +f 1675//1 1696//1 1676//1 +f 1696//1 1697//1 1676//1 +f 1676//1 1697//1 1677//1 +f 1697//1 1698//1 1677//1 +f 1677//1 1698//1 1678//1 +f 1698//1 1699//1 1678//1 +f 1678//1 1699//1 1679//1 +f 1699//1 1700//1 1679//1 +f 1679//1 1700//1 1680//1 +f 1700//1 1701//1 1680//1 +f 1680//1 1701//1 1681//1 +f 1701//1 1702//1 1681//1 +f 1681//1 1702//1 1682//1 +f 1702//1 1703//1 1682//1 +f 1682//1 1703//1 1683//1 +f 1703//1 1704//1 1683//1 +f 1683//1 1704//1 1684//1 +f 1704//1 1705//1 1684//1 +f 1684//1 1705//1 1685//1 +f 1705//1 1706//1 1685//1 +f 1685//1 1706//1 1686//1 +f 1706//1 1707//1 1686//1 +f 1686//1 1707//1 1687//1 +f 1707//1 1708//1 1687//1 +f 1687//1 1708//1 1688//1 +f 1708//1 1709//1 1688//1 +f 1688//1 1709//1 1689//1 +f 1709//1 1710//1 1689//1 +f 1689//1 1710//1 34//1 +f 1710//1 33//1 34//1 +f 76//1 1711//1 1690//1 +f 1711//1 1712//1 1690//1 +f 1690//1 1712//1 1691//1 +f 1712//1 1713//1 1691//1 +f 1691//1 1713//1 1692//1 +f 1713//1 1714//1 1692//1 +f 1692//1 1714//1 1693//1 +f 1714//1 1715//1 1693//1 +f 1693//1 1715//1 1694//1 +f 1715//1 1716//1 1694//1 +f 1694//1 1716//1 1695//1 +f 1716//1 1717//1 1695//1 +f 1695//1 1717//1 1696//1 +f 1717//1 1718//1 1696//1 +f 1696//1 1718//1 1697//1 +f 1718//1 1719//1 1697//1 +f 1697//1 1719//1 1698//1 +f 1719//1 1720//1 1698//1 +f 1698//1 1720//1 1699//1 +f 1720//1 1721//1 1699//1 +f 1699//1 1721//1 1700//1 +f 1721//1 1722//1 1700//1 +f 1700//1 1722//1 1701//1 +f 1722//1 1723//1 1701//1 +f 1701//1 1723//1 1702//1 +f 1723//1 1724//1 1702//1 +f 1702//1 1724//1 1703//1 +f 1724//1 1725//1 1703//1 +f 1703//1 1725//1 1704//1 +f 1725//1 1726//1 1704//1 +f 1704//1 1726//1 1705//1 +f 1726//1 1727//1 1705//1 +f 1705//1 1727//1 1706//1 +f 1727//1 1728//1 1706//1 +f 1706//1 1728//1 1707//1 +f 1728//1 1729//1 1707//1 +f 1707//1 1729//1 1708//1 +f 1729//1 1730//1 1708//1 +f 1708//1 1730//1 1709//1 +f 1730//1 1731//1 1709//1 +f 1709//1 1731//1 1710//1 +f 1731//1 1732//1 1710//1 +f 1710//1 1732//1 33//1 +f 1732//1 32//1 33//1 +f 77//1 1733//1 1711//1 +f 1733//1 1734//1 1711//1 +f 1711//1 1734//1 1712//1 +f 1734//1 1735//1 1712//1 +f 1712//1 1735//1 1713//1 +f 1735//1 1736//1 1713//1 +f 1713//1 1736//1 1714//1 +f 1736//1 1737//1 1714//1 +f 1714//1 1737//1 1715//1 +f 1737//1 1738//1 1715//1 +f 1715//1 1738//1 1716//1 +f 1738//1 1739//1 1716//1 +f 1716//1 1739//1 1717//1 +f 1739//1 1740//1 1717//1 +f 1717//1 1740//1 1718//1 +f 1740//1 1741//1 1718//1 +f 1718//1 1741//1 1719//1 +f 1741//1 1742//1 1719//1 +f 1719//1 1742//1 1720//1 +f 1742//1 1743//1 1720//1 +f 1720//1 1743//1 1721//1 +f 1743//1 1744//1 1721//1 +f 1721//1 1744//1 1722//1 +f 1744//1 1745//1 1722//1 +f 1722//1 1745//1 1723//1 +f 1745//1 1746//1 1723//1 +f 1723//1 1746//1 1724//1 +f 1746//1 1747//1 1724//1 +f 1724//1 1747//1 1725//1 +f 1747//1 1748//1 1725//1 +f 1725//1 1748//1 1726//1 +f 1748//1 1749//1 1726//1 +f 1726//1 1749//1 1727//1 +f 1749//1 1750//1 1727//1 +f 1727//1 1750//1 1728//1 +f 1750//1 1751//1 1728//1 +f 1728//1 1751//1 1729//1 +f 1751//1 1752//1 1729//1 +f 1729//1 1752//1 1730//1 +f 1752//1 1753//1 1730//1 +f 1730//1 1753//1 1731//1 +f 1753//1 1754//1 1731//1 +f 1731//1 1754//1 1732//1 +f 1754//1 1755//1 1732//1 +f 1732//1 1755//1 32//1 +f 1755//1 31//1 32//1 +f 78//1 1756//1 1733//1 +f 1756//1 1757//1 1733//1 +f 1733//1 1757//1 1734//1 +f 1757//1 1758//1 1734//1 +f 1734//1 1758//1 1735//1 +f 1758//1 1759//1 1735//1 +f 1735//1 1759//1 1736//1 +f 1759//1 1760//1 1736//1 +f 1736//1 1760//1 1737//1 +f 1760//1 1761//1 1737//1 +f 1737//1 1761//1 1738//1 +f 1761//1 1762//1 1738//1 +f 1738//1 1762//1 1739//1 +f 1762//1 1763//1 1739//1 +f 1739//1 1763//1 1740//1 +f 1763//1 1764//1 1740//1 +f 1740//1 1764//1 1741//1 +f 1764//1 1765//1 1741//1 +f 1741//1 1765//1 1742//1 +f 1765//1 1766//1 1742//1 +f 1742//1 1766//1 1743//1 +f 1766//1 1767//1 1743//1 +f 1743//1 1767//1 1744//1 +f 1767//1 1768//1 1744//1 +f 1744//1 1768//1 1745//1 +f 1768//1 1769//1 1745//1 +f 1745//1 1769//1 1746//1 +f 1769//1 1770//1 1746//1 +f 1746//1 1770//1 1747//1 +f 1770//1 1771//1 1747//1 +f 1747//1 1771//1 1748//1 +f 1771//1 1772//1 1748//1 +f 1748//1 1772//1 1749//1 +f 1772//1 1773//1 1749//1 +f 1749//1 1773//1 1750//1 +f 1773//1 1774//1 1750//1 +f 1750//1 1774//1 1751//1 +f 1774//1 1775//1 1751//1 +f 1751//1 1775//1 1752//1 +f 1775//1 1776//1 1752//1 +f 1752//1 1776//1 1753//1 +f 1776//1 1777//1 1753//1 +f 1753//1 1777//1 1754//1 +f 1777//1 1778//1 1754//1 +f 1754//1 1778//1 1755//1 +f 1778//1 1779//1 1755//1 +f 1755//1 1779//1 31//1 +f 1779//1 30//1 31//1 +f 79//1 1780//1 1756//1 +f 1780//1 1781//1 1756//1 +f 1756//1 1781//1 1757//1 +f 1781//1 1782//1 1757//1 +f 1757//1 1782//1 1758//1 +f 1782//1 1783//1 1758//1 +f 1758//1 1783//1 1759//1 +f 1783//1 1784//1 1759//1 +f 1759//1 1784//1 1760//1 +f 1784//1 1785//1 1760//1 +f 1760//1 1785//1 1761//1 +f 1785//1 1786//1 1761//1 +f 1761//1 1786//1 1762//1 +f 1786//1 1787//1 1762//1 +f 1762//1 1787//1 1763//1 +f 1787//1 1788//1 1763//1 +f 1763//1 1788//1 1764//1 +f 1788//1 1789//1 1764//1 +f 1764//1 1789//1 1765//1 +f 1789//1 1790//1 1765//1 +f 1765//1 1790//1 1766//1 +f 1790//1 1791//1 1766//1 +f 1766//1 1791//1 1767//1 +f 1791//1 1792//1 1767//1 +f 1767//1 1792//1 1768//1 +f 1792//1 1793//1 1768//1 +f 1768//1 1793//1 1769//1 +f 1793//1 1794//1 1769//1 +f 1769//1 1794//1 1770//1 +f 1794//1 1795//1 1770//1 +f 1770//1 1795//1 1771//1 +f 1795//1 1796//1 1771//1 +f 1771//1 1796//1 1772//1 +f 1796//1 1797//1 1772//1 +f 1772//1 1797//1 1773//1 +f 1797//1 1798//1 1773//1 +f 1773//1 1798//1 1774//1 +f 1798//1 1799//1 1774//1 +f 1774//1 1799//1 1775//1 +f 1799//1 1800//1 1775//1 +f 1775//1 1800//1 1776//1 +f 1800//1 1801//1 1776//1 +f 1776//1 1801//1 1777//1 +f 1801//1 1802//1 1777//1 +f 1777//1 1802//1 1778//1 +f 1802//1 1803//1 1778//1 +f 1778//1 1803//1 1779//1 +f 1803//1 1804//1 1779//1 +f 1779//1 1804//1 30//1 +f 1804//1 29//1 30//1 +f 80//1 1805//1 1780//1 +f 1805//1 1806//1 1780//1 +f 1780//1 1806//1 1781//1 +f 1806//1 1807//1 1781//1 +f 1781//1 1807//1 1782//1 +f 1807//1 1808//1 1782//1 +f 1782//1 1808//1 1783//1 +f 1808//1 1809//1 1783//1 +f 1783//1 1809//1 1784//1 +f 1809//1 1810//1 1784//1 +f 1784//1 1810//1 1785//1 +f 1810//1 1811//1 1785//1 +f 1785//1 1811//1 1786//1 +f 1811//1 1812//1 1786//1 +f 1786//1 1812//1 1787//1 +f 1812//1 1813//1 1787//1 +f 1787//1 1813//1 1788//1 +f 1813//1 1814//1 1788//1 +f 1788//1 1814//1 1789//1 +f 1814//1 1815//1 1789//1 +f 1789//1 1815//1 1790//1 +f 1815//1 1816//1 1790//1 +f 1790//1 1816//1 1791//1 +f 1816//1 1817//1 1791//1 +f 1791//1 1817//1 1792//1 +f 1817//1 1818//1 1792//1 +f 1792//1 1818//1 1793//1 +f 1818//1 1819//1 1793//1 +f 1793//1 1819//1 1794//1 +f 1819//1 1820//1 1794//1 +f 1794//1 1820//1 1795//1 +f 1820//1 1821//1 1795//1 +f 1795//1 1821//1 1796//1 +f 1821//1 1822//1 1796//1 +f 1796//1 1822//1 1797//1 +f 1822//1 1823//1 1797//1 +f 1797//1 1823//1 1798//1 +f 1823//1 1824//1 1798//1 +f 1798//1 1824//1 1799//1 +f 1824//1 1825//1 1799//1 +f 1799//1 1825//1 1800//1 +f 1825//1 1826//1 1800//1 +f 1800//1 1826//1 1801//1 +f 1826//1 1827//1 1801//1 +f 1801//1 1827//1 1802//1 +f 1827//1 1828//1 1802//1 +f 1802//1 1828//1 1803//1 +f 1828//1 1829//1 1803//1 +f 1803//1 1829//1 1804//1 +f 1829//1 1830//1 1804//1 +f 1804//1 1830//1 29//1 +f 1830//1 28//1 29//1 +f 81//1 1831//1 1805//1 +f 1831//1 1832//1 1805//1 +f 1805//1 1832//1 1806//1 +f 1832//1 1833//1 1806//1 +f 1806//1 1833//1 1807//1 +f 1833//1 1834//1 1807//1 +f 1807//1 1834//1 1808//1 +f 1834//1 1835//1 1808//1 +f 1808//1 1835//1 1809//1 +f 1835//1 1836//1 1809//1 +f 1809//1 1836//1 1810//1 +f 1836//1 1837//1 1810//1 +f 1810//1 1837//1 1811//1 +f 1837//1 1838//1 1811//1 +f 1811//1 1838//1 1812//1 +f 1838//1 1839//1 1812//1 +f 1812//1 1839//1 1813//1 +f 1839//1 1840//1 1813//1 +f 1813//1 1840//1 1814//1 +f 1840//1 1841//1 1814//1 +f 1814//1 1841//1 1815//1 +f 1841//1 1842//1 1815//1 +f 1815//1 1842//1 1816//1 +f 1842//1 1843//1 1816//1 +f 1816//1 1843//1 1817//1 +f 1843//1 1844//1 1817//1 +f 1817//1 1844//1 1818//1 +f 1844//1 1845//1 1818//1 +f 1818//1 1845//1 1819//1 +f 1845//1 1846//1 1819//1 +f 1819//1 1846//1 1820//1 +f 1846//1 1847//1 1820//1 +f 1820//1 1847//1 1821//1 +f 1847//1 1848//1 1821//1 +f 1821//1 1848//1 1822//1 +f 1848//1 1849//1 1822//1 +f 1822//1 1849//1 1823//1 +f 1849//1 1850//1 1823//1 +f 1823//1 1850//1 1824//1 +f 1850//1 1851//1 1824//1 +f 1824//1 1851//1 1825//1 +f 1851//1 1852//1 1825//1 +f 1825//1 1852//1 1826//1 +f 1852//1 1853//1 1826//1 +f 1826//1 1853//1 1827//1 +f 1853//1 1854//1 1827//1 +f 1827//1 1854//1 1828//1 +f 1854//1 1855//1 1828//1 +f 1828//1 1855//1 1829//1 +f 1855//1 1856//1 1829//1 +f 1829//1 1856//1 1830//1 +f 1856//1 1857//1 1830//1 +f 1830//1 1857//1 28//1 +f 1857//1 27//1 28//1 +f 82//1 1858//1 1831//1 +f 1858//1 1859//1 1831//1 +f 1831//1 1859//1 1832//1 +f 1859//1 1860//1 1832//1 +f 1832//1 1860//1 1833//1 +f 1860//1 1861//1 1833//1 +f 1833//1 1861//1 1834//1 +f 1861//1 1862//1 1834//1 +f 1834//1 1862//1 1835//1 +f 1862//1 1863//1 1835//1 +f 1835//1 1863//1 1836//1 +f 1863//1 1864//1 1836//1 +f 1836//1 1864//1 1837//1 +f 1864//1 1865//1 1837//1 +f 1837//1 1865//1 1838//1 +f 1865//1 1866//1 1838//1 +f 1838//1 1866//1 1839//1 +f 1866//1 1867//1 1839//1 +f 1839//1 1867//1 1840//1 +f 1867//1 1868//1 1840//1 +f 1840//1 1868//1 1841//1 +f 1868//1 1869//1 1841//1 +f 1841//1 1869//1 1842//1 +f 1869//1 1870//1 1842//1 +f 1842//1 1870//1 1843//1 +f 1870//1 1871//1 1843//1 +f 1843//1 1871//1 1844//1 +f 1871//1 1872//1 1844//1 +f 1844//1 1872//1 1845//1 +f 1872//1 1873//1 1845//1 +f 1845//1 1873//1 1846//1 +f 1873//1 1874//1 1846//1 +f 1846//1 1874//1 1847//1 +f 1874//1 1875//1 1847//1 +f 1847//1 1875//1 1848//1 +f 1875//1 1876//1 1848//1 +f 1848//1 1876//1 1849//1 +f 1876//1 1877//1 1849//1 +f 1849//1 1877//1 1850//1 +f 1877//1 1878//1 1850//1 +f 1850//1 1878//1 1851//1 +f 1878//1 1879//1 1851//1 +f 1851//1 1879//1 1852//1 +f 1879//1 1880//1 1852//1 +f 1852//1 1880//1 1853//1 +f 1880//1 1881//1 1853//1 +f 1853//1 1881//1 1854//1 +f 1881//1 1882//1 1854//1 +f 1854//1 1882//1 1855//1 +f 1882//1 1883//1 1855//1 +f 1855//1 1883//1 1856//1 +f 1883//1 1884//1 1856//1 +f 1856//1 1884//1 1857//1 +f 1884//1 1885//1 1857//1 +f 1857//1 1885//1 27//1 +f 1885//1 26//1 27//1 +f 83//1 1886//1 1858//1 +f 1886//1 1887//1 1858//1 +f 1858//1 1887//1 1859//1 +f 1887//1 1888//1 1859//1 +f 1859//1 1888//1 1860//1 +f 1888//1 1889//1 1860//1 +f 1860//1 1889//1 1861//1 +f 1889//1 1890//1 1861//1 +f 1861//1 1890//1 1862//1 +f 1890//1 1891//1 1862//1 +f 1862//1 1891//1 1863//1 +f 1891//1 1892//1 1863//1 +f 1863//1 1892//1 1864//1 +f 1892//1 1893//1 1864//1 +f 1864//1 1893//1 1865//1 +f 1893//1 1894//1 1865//1 +f 1865//1 1894//1 1866//1 +f 1894//1 1895//1 1866//1 +f 1866//1 1895//1 1867//1 +f 1895//1 1896//1 1867//1 +f 1867//1 1896//1 1868//1 +f 1896//1 1897//1 1868//1 +f 1868//1 1897//1 1869//1 +f 1897//1 1898//1 1869//1 +f 1869//1 1898//1 1870//1 +f 1898//1 1899//1 1870//1 +f 1870//1 1899//1 1871//1 +f 1899//1 1900//1 1871//1 +f 1871//1 1900//1 1872//1 +f 1900//1 1901//1 1872//1 +f 1872//1 1901//1 1873//1 +f 1901//1 1902//1 1873//1 +f 1873//1 1902//1 1874//1 +f 1902//1 1903//1 1874//1 +f 1874//1 1903//1 1875//1 +f 1903//1 1904//1 1875//1 +f 1875//1 1904//1 1876//1 +f 1904//1 1905//1 1876//1 +f 1876//1 1905//1 1877//1 +f 1905//1 1906//1 1877//1 +f 1877//1 1906//1 1878//1 +f 1906//1 1907//1 1878//1 +f 1878//1 1907//1 1879//1 +f 1907//1 1908//1 1879//1 +f 1879//1 1908//1 1880//1 +f 1908//1 1909//1 1880//1 +f 1880//1 1909//1 1881//1 +f 1909//1 1910//1 1881//1 +f 1881//1 1910//1 1882//1 +f 1910//1 1911//1 1882//1 +f 1882//1 1911//1 1883//1 +f 1911//1 1912//1 1883//1 +f 1883//1 1912//1 1884//1 +f 1912//1 1913//1 1884//1 +f 1884//1 1913//1 1885//1 +f 1913//1 1914//1 1885//1 +f 1885//1 1914//1 26//1 +f 1914//1 25//1 26//1 +f 84//1 1915//1 1886//1 +f 1915//1 1916//1 1886//1 +f 1886//1 1916//1 1887//1 +f 1916//1 1917//1 1887//1 +f 1887//1 1917//1 1888//1 +f 1917//1 1918//1 1888//1 +f 1888//1 1918//1 1889//1 +f 1918//1 1919//1 1889//1 +f 1889//1 1919//1 1890//1 +f 1919//1 1920//1 1890//1 +f 1890//1 1920//1 1891//1 +f 1920//1 1921//1 1891//1 +f 1891//1 1921//1 1892//1 +f 1921//1 1922//1 1892//1 +f 1892//1 1922//1 1893//1 +f 1922//1 1923//1 1893//1 +f 1893//1 1923//1 1894//1 +f 1923//1 1924//1 1894//1 +f 1894//1 1924//1 1895//1 +f 1924//1 1925//1 1895//1 +f 1895//1 1925//1 1896//1 +f 1925//1 1926//1 1896//1 +f 1896//1 1926//1 1897//1 +f 1926//1 1927//1 1897//1 +f 1897//1 1927//1 1898//1 +f 1927//1 1928//1 1898//1 +f 1898//1 1928//1 1899//1 +f 1928//1 1929//1 1899//1 +f 1899//1 1929//1 1900//1 +f 1929//1 1930//1 1900//1 +f 1900//1 1930//1 1901//1 +f 1930//1 1931//1 1901//1 +f 1901//1 1931//1 1902//1 +f 1931//1 1932//1 1902//1 +f 1902//1 1932//1 1903//1 +f 1932//1 1933//1 1903//1 +f 1903//1 1933//1 1904//1 +f 1933//1 1934//1 1904//1 +f 1904//1 1934//1 1905//1 +f 1934//1 1935//1 1905//1 +f 1905//1 1935//1 1906//1 +f 1935//1 1936//1 1906//1 +f 1906//1 1936//1 1907//1 +f 1936//1 1937//1 1907//1 +f 1907//1 1937//1 1908//1 +f 1937//1 1938//1 1908//1 +f 1908//1 1938//1 1909//1 +f 1938//1 1939//1 1909//1 +f 1909//1 1939//1 1910//1 +f 1939//1 1940//1 1910//1 +f 1910//1 1940//1 1911//1 +f 1940//1 1941//1 1911//1 +f 1911//1 1941//1 1912//1 +f 1941//1 1942//1 1912//1 +f 1912//1 1942//1 1913//1 +f 1942//1 1943//1 1913//1 +f 1913//1 1943//1 1914//1 +f 1943//1 1944//1 1914//1 +f 1914//1 1944//1 25//1 +f 1944//1 24//1 25//1 +f 85//1 1945//1 1915//1 +f 1945//1 1946//1 1915//1 +f 1915//1 1946//1 1916//1 +f 1946//1 1947//1 1916//1 +f 1916//1 1947//1 1917//1 +f 1947//1 1948//1 1917//1 +f 1917//1 1948//1 1918//1 +f 1948//1 1949//1 1918//1 +f 1918//1 1949//1 1919//1 +f 1949//1 1950//1 1919//1 +f 1919//1 1950//1 1920//1 +f 1950//1 1951//1 1920//1 +f 1920//1 1951//1 1921//1 +f 1951//1 1952//1 1921//1 +f 1921//1 1952//1 1922//1 +f 1952//1 1953//1 1922//1 +f 1922//1 1953//1 1923//1 +f 1953//1 1954//1 1923//1 +f 1923//1 1954//1 1924//1 +f 1954//1 1955//1 1924//1 +f 1924//1 1955//1 1925//1 +f 1955//1 1956//1 1925//1 +f 1925//1 1956//1 1926//1 +f 1956//1 1957//1 1926//1 +f 1926//1 1957//1 1927//1 +f 1957//1 1958//1 1927//1 +f 1927//1 1958//1 1928//1 +f 1958//1 1959//1 1928//1 +f 1928//1 1959//1 1929//1 +f 1959//1 1960//1 1929//1 +f 1929//1 1960//1 1930//1 +f 1960//1 1961//1 1930//1 +f 1930//1 1961//1 1931//1 +f 1961//1 1962//1 1931//1 +f 1931//1 1962//1 1932//1 +f 1962//1 1963//1 1932//1 +f 1932//1 1963//1 1933//1 +f 1963//1 1964//1 1933//1 +f 1933//1 1964//1 1934//1 +f 1964//1 1965//1 1934//1 +f 1934//1 1965//1 1935//1 +f 1965//1 1966//1 1935//1 +f 1935//1 1966//1 1936//1 +f 1966//1 1967//1 1936//1 +f 1936//1 1967//1 1937//1 +f 1967//1 1968//1 1937//1 +f 1937//1 1968//1 1938//1 +f 1968//1 1969//1 1938//1 +f 1938//1 1969//1 1939//1 +f 1969//1 1970//1 1939//1 +f 1939//1 1970//1 1940//1 +f 1970//1 1971//1 1940//1 +f 1940//1 1971//1 1941//1 +f 1971//1 1972//1 1941//1 +f 1941//1 1972//1 1942//1 +f 1972//1 1973//1 1942//1 +f 1942//1 1973//1 1943//1 +f 1973//1 1974//1 1943//1 +f 1943//1 1974//1 1944//1 +f 1974//1 1975//1 1944//1 +f 1944//1 1975//1 24//1 +f 1975//1 23//1 24//1 +f 86//1 1976//1 1945//1 +f 1976//1 1977//1 1945//1 +f 1945//1 1977//1 1946//1 +f 1977//1 1978//1 1946//1 +f 1946//1 1978//1 1947//1 +f 1978//1 1979//1 1947//1 +f 1947//1 1979//1 1948//1 +f 1979//1 1980//1 1948//1 +f 1948//1 1980//1 1949//1 +f 1980//1 1981//1 1949//1 +f 1949//1 1981//1 1950//1 +f 1981//1 1982//1 1950//1 +f 1950//1 1982//1 1951//1 +f 1982//1 1983//1 1951//1 +f 1951//1 1983//1 1952//1 +f 1983//1 1984//1 1952//1 +f 1952//1 1984//1 1953//1 +f 1984//1 1985//1 1953//1 +f 1953//1 1985//1 1954//1 +f 1985//1 1986//1 1954//1 +f 1954//1 1986//1 1955//1 +f 1986//1 1987//1 1955//1 +f 1955//1 1987//1 1956//1 +f 1987//1 1988//1 1956//1 +f 1956//1 1988//1 1957//1 +f 1988//1 1989//1 1957//1 +f 1957//1 1989//1 1958//1 +f 1989//1 1990//1 1958//1 +f 1958//1 1990//1 1959//1 +f 1990//1 1991//1 1959//1 +f 1959//1 1991//1 1960//1 +f 1991//1 1992//1 1960//1 +f 1960//1 1992//1 1961//1 +f 1992//1 1993//1 1961//1 +f 1961//1 1993//1 1962//1 +f 1993//1 1994//1 1962//1 +f 1962//1 1994//1 1963//1 +f 1994//1 1995//1 1963//1 +f 1963//1 1995//1 1964//1 +f 1995//1 1996//1 1964//1 +f 1964//1 1996//1 1965//1 +f 1996//1 1997//1 1965//1 +f 1965//1 1997//1 1966//1 +f 1997//1 1998//1 1966//1 +f 1966//1 1998//1 1967//1 +f 1998//1 1999//1 1967//1 +f 1967//1 1999//1 1968//1 +f 1999//1 2000//1 1968//1 +f 1968//1 2000//1 1969//1 +f 2000//1 2001//1 1969//1 +f 1969//1 2001//1 1970//1 +f 2001//1 2002//1 1970//1 +f 1970//1 2002//1 1971//1 +f 2002//1 2003//1 1971//1 +f 1971//1 2003//1 1972//1 +f 2003//1 2004//1 1972//1 +f 1972//1 2004//1 1973//1 +f 2004//1 2005//1 1973//1 +f 1973//1 2005//1 1974//1 +f 2005//1 2006//1 1974//1 +f 1974//1 2006//1 1975//1 +f 2006//1 2007//1 1975//1 +f 1975//1 2007//1 23//1 +f 2007//1 22//1 23//1 +f 87//1 2008//1 1976//1 +f 2008//1 2009//1 1976//1 +f 1976//1 2009//1 1977//1 +f 2009//1 2010//1 1977//1 +f 1977//1 2010//1 1978//1 +f 2010//1 2011//1 1978//1 +f 1978//1 2011//1 1979//1 +f 2011//1 2012//1 1979//1 +f 1979//1 2012//1 1980//1 +f 2012//1 2013//1 1980//1 +f 1980//1 2013//1 1981//1 +f 2013//1 2014//1 1981//1 +f 1981//1 2014//1 1982//1 +f 2014//1 2015//1 1982//1 +f 1982//1 2015//1 1983//1 +f 2015//1 2016//1 1983//1 +f 1983//1 2016//1 1984//1 +f 2016//1 2017//1 1984//1 +f 1984//1 2017//1 1985//1 +f 2017//1 2018//1 1985//1 +f 1985//1 2018//1 1986//1 +f 2018//1 2019//1 1986//1 +f 1986//1 2019//1 1987//1 +f 2019//1 2020//1 1987//1 +f 1987//1 2020//1 1988//1 +f 2020//1 2021//1 1988//1 +f 1988//1 2021//1 1989//1 +f 2021//1 2022//1 1989//1 +f 1989//1 2022//1 1990//1 +f 2022//1 2023//1 1990//1 +f 1990//1 2023//1 1991//1 +f 2023//1 2024//1 1991//1 +f 1991//1 2024//1 1992//1 +f 2024//1 2025//1 1992//1 +f 1992//1 2025//1 1993//1 +f 2025//1 2026//1 1993//1 +f 1993//1 2026//1 1994//1 +f 2026//1 2027//1 1994//1 +f 1994//1 2027//1 1995//1 +f 2027//1 2028//1 1995//1 +f 1995//1 2028//1 1996//1 +f 2028//1 2029//1 1996//1 +f 1996//1 2029//1 1997//1 +f 2029//1 2030//1 1997//1 +f 1997//1 2030//1 1998//1 +f 2030//1 2031//1 1998//1 +f 1998//1 2031//1 1999//1 +f 2031//1 2032//1 1999//1 +f 1999//1 2032//1 2000//1 +f 2032//1 2033//1 2000//1 +f 2000//1 2033//1 2001//1 +f 2033//1 2034//1 2001//1 +f 2001//1 2034//1 2002//1 +f 2034//1 2035//1 2002//1 +f 2002//1 2035//1 2003//1 +f 2035//1 2036//1 2003//1 +f 2003//1 2036//1 2004//1 +f 2036//1 2037//1 2004//1 +f 2004//1 2037//1 2005//1 +f 2037//1 2038//1 2005//1 +f 2005//1 2038//1 2006//1 +f 2038//1 2039//1 2006//1 +f 2006//1 2039//1 2007//1 +f 2039//1 2040//1 2007//1 +f 2007//1 2040//1 22//1 +f 2040//1 21//1 22//1 +f 88//1 2041//1 2008//1 +f 2041//1 2042//1 2008//1 +f 2008//1 2042//1 2009//1 +f 2042//1 2043//1 2009//1 +f 2009//1 2043//1 2010//1 +f 2043//1 2044//1 2010//1 +f 2010//1 2044//1 2011//1 +f 2044//1 2045//1 2011//1 +f 2011//1 2045//1 2012//1 +f 2045//1 2046//1 2012//1 +f 2012//1 2046//1 2013//1 +f 2046//1 2047//1 2013//1 +f 2013//1 2047//1 2014//1 +f 2047//1 2048//1 2014//1 +f 2014//1 2048//1 2015//1 +f 2048//1 2049//1 2015//1 +f 2015//1 2049//1 2016//1 +f 2049//1 2050//1 2016//1 +f 2016//1 2050//1 2017//1 +f 2050//1 2051//1 2017//1 +f 2017//1 2051//1 2018//1 +f 2051//1 2052//1 2018//1 +f 2018//1 2052//1 2019//1 +f 2052//1 2053//1 2019//1 +f 2019//1 2053//1 2020//1 +f 2053//1 2054//1 2020//1 +f 2020//1 2054//1 2021//1 +f 2054//1 2055//1 2021//1 +f 2021//1 2055//1 2022//1 +f 2055//1 2056//1 2022//1 +f 2022//1 2056//1 2023//1 +f 2056//1 2057//1 2023//1 +f 2023//1 2057//1 2024//1 +f 2057//1 2058//1 2024//1 +f 2024//1 2058//1 2025//1 +f 2058//1 2059//1 2025//1 +f 2025//1 2059//1 2026//1 +f 2059//1 2060//1 2026//1 +f 2026//1 2060//1 2027//1 +f 2060//1 2061//1 2027//1 +f 2027//1 2061//1 2028//1 +f 2061//1 2062//1 2028//1 +f 2028//1 2062//1 2029//1 +f 2062//1 2063//1 2029//1 +f 2029//1 2063//1 2030//1 +f 2063//1 2064//1 2030//1 +f 2030//1 2064//1 2031//1 +f 2064//1 2065//1 2031//1 +f 2031//1 2065//1 2032//1 +f 2065//1 2066//1 2032//1 +f 2032//1 2066//1 2033//1 +f 2066//1 2067//1 2033//1 +f 2033//1 2067//1 2034//1 +f 2067//1 2068//1 2034//1 +f 2034//1 2068//1 2035//1 +f 2068//1 2069//1 2035//1 +f 2035//1 2069//1 2036//1 +f 2069//1 2070//1 2036//1 +f 2036//1 2070//1 2037//1 +f 2070//1 2071//1 2037//1 +f 2037//1 2071//1 2038//1 +f 2071//1 2072//1 2038//1 +f 2038//1 2072//1 2039//1 +f 2072//1 2073//1 2039//1 +f 2039//1 2073//1 2040//1 +f 2073//1 2074//1 2040//1 +f 2040//1 2074//1 21//1 +f 2074//1 20//1 21//1 +f 89//1 2075//1 2041//1 +f 2075//1 2076//1 2041//1 +f 2041//1 2076//1 2042//1 +f 2076//1 2077//1 2042//1 +f 2042//1 2077//1 2043//1 +f 2077//1 2078//1 2043//1 +f 2043//1 2078//1 2044//1 +f 2078//1 2079//1 2044//1 +f 2044//1 2079//1 2045//1 +f 2079//1 2080//1 2045//1 +f 2045//1 2080//1 2046//1 +f 2080//1 2081//1 2046//1 +f 2046//1 2081//1 2047//1 +f 2081//1 2082//1 2047//1 +f 2047//1 2082//1 2048//1 +f 2082//1 2083//1 2048//1 +f 2048//1 2083//1 2049//1 +f 2083//1 2084//1 2049//1 +f 2049//1 2084//1 2050//1 +f 2084//1 2085//1 2050//1 +f 2050//1 2085//1 2051//1 +f 2085//1 2086//1 2051//1 +f 2051//1 2086//1 2052//1 +f 2086//1 2087//1 2052//1 +f 2052//1 2087//1 2053//1 +f 2087//1 2088//1 2053//1 +f 2053//1 2088//1 2054//1 +f 2088//1 2089//1 2054//1 +f 2054//1 2089//1 2055//1 +f 2089//1 2090//1 2055//1 +f 2055//1 2090//1 2056//1 +f 2090//1 2091//1 2056//1 +f 2056//1 2091//1 2057//1 +f 2091//1 2092//1 2057//1 +f 2057//1 2092//1 2058//1 +f 2092//1 2093//1 2058//1 +f 2058//1 2093//1 2059//1 +f 2093//1 2094//1 2059//1 +f 2059//1 2094//1 2060//1 +f 2094//1 2095//1 2060//1 +f 2060//1 2095//1 2061//1 +f 2095//1 2096//1 2061//1 +f 2061//1 2096//1 2062//1 +f 2096//1 2097//1 2062//1 +f 2062//1 2097//1 2063//1 +f 2097//1 2098//1 2063//1 +f 2063//1 2098//1 2064//1 +f 2098//1 2099//1 2064//1 +f 2064//1 2099//1 2065//1 +f 2099//1 2100//1 2065//1 +f 2065//1 2100//1 2066//1 +f 2100//1 2101//1 2066//1 +f 2066//1 2101//1 2067//1 +f 2101//1 2102//1 2067//1 +f 2067//1 2102//1 2068//1 +f 2102//1 2103//1 2068//1 +f 2068//1 2103//1 2069//1 +f 2103//1 2104//1 2069//1 +f 2069//1 2104//1 2070//1 +f 2104//1 2105//1 2070//1 +f 2070//1 2105//1 2071//1 +f 2105//1 2106//1 2071//1 +f 2071//1 2106//1 2072//1 +f 2106//1 2107//1 2072//1 +f 2072//1 2107//1 2073//1 +f 2107//1 2108//1 2073//1 +f 2073//1 2108//1 2074//1 +f 2108//1 2109//1 2074//1 +f 2074//1 2109//1 20//1 +f 2109//1 19//1 20//1 +f 90//1 2110//1 2075//1 +f 2110//1 2111//1 2075//1 +f 2075//1 2111//1 2076//1 +f 2111//1 2112//1 2076//1 +f 2076//1 2112//1 2077//1 +f 2112//1 2113//1 2077//1 +f 2077//1 2113//1 2078//1 +f 2113//1 2114//1 2078//1 +f 2078//1 2114//1 2079//1 +f 2114//1 2115//1 2079//1 +f 2079//1 2115//1 2080//1 +f 2115//1 2116//1 2080//1 +f 2080//1 2116//1 2081//1 +f 2116//1 2117//1 2081//1 +f 2081//1 2117//1 2082//1 +f 2117//1 2118//1 2082//1 +f 2082//1 2118//1 2083//1 +f 2118//1 2119//1 2083//1 +f 2083//1 2119//1 2084//1 +f 2119//1 2120//1 2084//1 +f 2084//1 2120//1 2085//1 +f 2120//1 2121//1 2085//1 +f 2085//1 2121//1 2086//1 +f 2121//1 2122//1 2086//1 +f 2086//1 2122//1 2087//1 +f 2122//1 2123//1 2087//1 +f 2087//1 2123//1 2088//1 +f 2123//1 2124//1 2088//1 +f 2088//1 2124//1 2089//1 +f 2124//1 2125//1 2089//1 +f 2089//1 2125//1 2090//1 +f 2125//1 2126//1 2090//1 +f 2090//1 2126//1 2091//1 +f 2126//1 2127//1 2091//1 +f 2091//1 2127//1 2092//1 +f 2127//1 2128//1 2092//1 +f 2092//1 2128//1 2093//1 +f 2128//1 2129//1 2093//1 +f 2093//1 2129//1 2094//1 +f 2129//1 2130//1 2094//1 +f 2094//1 2130//1 2095//1 +f 2130//1 2131//1 2095//1 +f 2095//1 2131//1 2096//1 +f 2131//1 2132//1 2096//1 +f 2096//1 2132//1 2097//1 +f 2132//1 2133//1 2097//1 +f 2097//1 2133//1 2098//1 +f 2133//1 2134//1 2098//1 +f 2098//1 2134//1 2099//1 +f 2134//1 2135//1 2099//1 +f 2099//1 2135//1 2100//1 +f 2135//1 2136//1 2100//1 +f 2100//1 2136//1 2101//1 +f 2136//1 2137//1 2101//1 +f 2101//1 2137//1 2102//1 +f 2137//1 2138//1 2102//1 +f 2102//1 2138//1 2103//1 +f 2138//1 2139//1 2103//1 +f 2103//1 2139//1 2104//1 +f 2139//1 2140//1 2104//1 +f 2104//1 2140//1 2105//1 +f 2140//1 2141//1 2105//1 +f 2105//1 2141//1 2106//1 +f 2141//1 2142//1 2106//1 +f 2106//1 2142//1 2107//1 +f 2142//1 2143//1 2107//1 +f 2107//1 2143//1 2108//1 +f 2143//1 2144//1 2108//1 +f 2108//1 2144//1 2109//1 +f 2144//1 2145//1 2109//1 +f 2109//1 2145//1 19//1 +f 2145//1 18//1 19//1 +f 91//1 2146//1 2110//1 +f 2146//1 2147//1 2110//1 +f 2110//1 2147//1 2111//1 +f 2147//1 2148//1 2111//1 +f 2111//1 2148//1 2112//1 +f 2148//1 2149//1 2112//1 +f 2112//1 2149//1 2113//1 +f 2149//1 2150//1 2113//1 +f 2113//1 2150//1 2114//1 +f 2150//1 2151//1 2114//1 +f 2114//1 2151//1 2115//1 +f 2151//1 2152//1 2115//1 +f 2115//1 2152//1 2116//1 +f 2152//1 2153//1 2116//1 +f 2116//1 2153//1 2117//1 +f 2153//1 2154//1 2117//1 +f 2117//1 2154//1 2118//1 +f 2154//1 2155//1 2118//1 +f 2118//1 2155//1 2119//1 +f 2155//1 2156//1 2119//1 +f 2119//1 2156//1 2120//1 +f 2156//1 2157//1 2120//1 +f 2120//1 2157//1 2121//1 +f 2157//1 2158//1 2121//1 +f 2121//1 2158//1 2122//1 +f 2158//1 2159//1 2122//1 +f 2122//1 2159//1 2123//1 +f 2159//1 2160//1 2123//1 +f 2123//1 2160//1 2124//1 +f 2160//1 2161//1 2124//1 +f 2124//1 2161//1 2125//1 +f 2161//1 2162//1 2125//1 +f 2125//1 2162//1 2126//1 +f 2162//1 2163//1 2126//1 +f 2126//1 2163//1 2127//1 +f 2163//1 2164//1 2127//1 +f 2127//1 2164//1 2128//1 +f 2164//1 2165//1 2128//1 +f 2128//1 2165//1 2129//1 +f 2165//1 2166//1 2129//1 +f 2129//1 2166//1 2130//1 +f 2166//1 2167//1 2130//1 +f 2130//1 2167//1 2131//1 +f 2167//1 2168//1 2131//1 +f 2131//1 2168//1 2132//1 +f 2168//1 2169//1 2132//1 +f 2132//1 2169//1 2133//1 +f 2169//1 2170//1 2133//1 +f 2133//1 2170//1 2134//1 +f 2170//1 2171//1 2134//1 +f 2134//1 2171//1 2135//1 +f 2171//1 2172//1 2135//1 +f 2135//1 2172//1 2136//1 +f 2172//1 2173//1 2136//1 +f 2136//1 2173//1 2137//1 +f 2173//1 2174//1 2137//1 +f 2137//1 2174//1 2138//1 +f 2174//1 2175//1 2138//1 +f 2138//1 2175//1 2139//1 +f 2175//1 2176//1 2139//1 +f 2139//1 2176//1 2140//1 +f 2176//1 2177//1 2140//1 +f 2140//1 2177//1 2141//1 +f 2177//1 2178//1 2141//1 +f 2141//1 2178//1 2142//1 +f 2178//1 2179//1 2142//1 +f 2142//1 2179//1 2143//1 +f 2179//1 2180//1 2143//1 +f 2143//1 2180//1 2144//1 +f 2180//1 2181//1 2144//1 +f 2144//1 2181//1 2145//1 +f 2181//1 2182//1 2145//1 +f 2145//1 2182//1 18//1 +f 2182//1 17//1 18//1 +f 92//1 2183//1 2146//1 +f 2183//1 2184//1 2146//1 +f 2146//1 2184//1 2147//1 +f 2184//1 2185//1 2147//1 +f 2147//1 2185//1 2148//1 +f 2185//1 2186//1 2148//1 +f 2148//1 2186//1 2149//1 +f 2186//1 2187//1 2149//1 +f 2149//1 2187//1 2150//1 +f 2187//1 2188//1 2150//1 +f 2150//1 2188//1 2151//1 +f 2188//1 2189//1 2151//1 +f 2151//1 2189//1 2152//1 +f 2189//1 2190//1 2152//1 +f 2152//1 2190//1 2153//1 +f 2190//1 2191//1 2153//1 +f 2153//1 2191//1 2154//1 +f 2191//1 2192//1 2154//1 +f 2154//1 2192//1 2155//1 +f 2192//1 2193//1 2155//1 +f 2155//1 2193//1 2156//1 +f 2193//1 2194//1 2156//1 +f 2156//1 2194//1 2157//1 +f 2194//1 2195//1 2157//1 +f 2157//1 2195//1 2158//1 +f 2195//1 2196//1 2158//1 +f 2158//1 2196//1 2159//1 +f 2196//1 2197//1 2159//1 +f 2159//1 2197//1 2160//1 +f 2197//1 2198//1 2160//1 +f 2160//1 2198//1 2161//1 +f 2198//1 2199//1 2161//1 +f 2161//1 2199//1 2162//1 +f 2199//1 2200//1 2162//1 +f 2162//1 2200//1 2163//1 +f 2200//1 2201//1 2163//1 +f 2163//1 2201//1 2164//1 +f 2201//1 2202//1 2164//1 +f 2164//1 2202//1 2165//1 +f 2202//1 2203//1 2165//1 +f 2165//1 2203//1 2166//1 +f 2203//1 2204//1 2166//1 +f 2166//1 2204//1 2167//1 +f 2204//1 2205//1 2167//1 +f 2167//1 2205//1 2168//1 +f 2205//1 2206//1 2168//1 +f 2168//1 2206//1 2169//1 +f 2206//1 2207//1 2169//1 +f 2169//1 2207//1 2170//1 +f 2207//1 2208//1 2170//1 +f 2170//1 2208//1 2171//1 +f 2208//1 2209//1 2171//1 +f 2171//1 2209//1 2172//1 +f 2209//1 2210//1 2172//1 +f 2172//1 2210//1 2173//1 +f 2210//1 2211//1 2173//1 +f 2173//1 2211//1 2174//1 +f 2211//1 2212//1 2174//1 +f 2174//1 2212//1 2175//1 +f 2212//1 2213//1 2175//1 +f 2175//1 2213//1 2176//1 +f 2213//1 2214//1 2176//1 +f 2176//1 2214//1 2177//1 +f 2214//1 2215//1 2177//1 +f 2177//1 2215//1 2178//1 +f 2215//1 2216//1 2178//1 +f 2178//1 2216//1 2179//1 +f 2216//1 2217//1 2179//1 +f 2179//1 2217//1 2180//1 +f 2217//1 2218//1 2180//1 +f 2180//1 2218//1 2181//1 +f 2218//1 2219//1 2181//1 +f 2181//1 2219//1 2182//1 +f 2219//1 2220//1 2182//1 +f 2182//1 2220//1 17//1 +f 2220//1 16//1 17//1 +f 93//1 2221//1 2183//1 +f 2221//1 2222//1 2183//1 +f 2183//1 2222//1 2184//1 +f 2222//1 2223//1 2184//1 +f 2184//1 2223//1 2185//1 +f 2223//1 2224//1 2185//1 +f 2185//1 2224//1 2186//1 +f 2224//1 2225//1 2186//1 +f 2186//1 2225//1 2187//1 +f 2225//1 2226//1 2187//1 +f 2187//1 2226//1 2188//1 +f 2226//1 2227//1 2188//1 +f 2188//1 2227//1 2189//1 +f 2227//1 2228//1 2189//1 +f 2189//1 2228//1 2190//1 +f 2228//1 2229//1 2190//1 +f 2190//1 2229//1 2191//1 +f 2229//1 2230//1 2191//1 +f 2191//1 2230//1 2192//1 +f 2230//1 2231//1 2192//1 +f 2192//1 2231//1 2193//1 +f 2231//1 2232//1 2193//1 +f 2193//1 2232//1 2194//1 +f 2232//1 2233//1 2194//1 +f 2194//1 2233//1 2195//1 +f 2233//1 2234//1 2195//1 +f 2195//1 2234//1 2196//1 +f 2234//1 2235//1 2196//1 +f 2196//1 2235//1 2197//1 +f 2235//1 2236//1 2197//1 +f 2197//1 2236//1 2198//1 +f 2236//1 2237//1 2198//1 +f 2198//1 2237//1 2199//1 +f 2237//1 2238//1 2199//1 +f 2199//1 2238//1 2200//1 +f 2238//1 2239//1 2200//1 +f 2200//1 2239//1 2201//1 +f 2239//1 2240//1 2201//1 +f 2201//1 2240//1 2202//1 +f 2240//1 2241//1 2202//1 +f 2202//1 2241//1 2203//1 +f 2241//1 2242//1 2203//1 +f 2203//1 2242//1 2204//1 +f 2242//1 2243//1 2204//1 +f 2204//1 2243//1 2205//1 +f 2243//1 2244//1 2205//1 +f 2205//1 2244//1 2206//1 +f 2244//1 2245//1 2206//1 +f 2206//1 2245//1 2207//1 +f 2245//1 2246//1 2207//1 +f 2207//1 2246//1 2208//1 +f 2246//1 2247//1 2208//1 +f 2208//1 2247//1 2209//1 +f 2247//1 2248//1 2209//1 +f 2209//1 2248//1 2210//1 +f 2248//1 2249//1 2210//1 +f 2210//1 2249//1 2211//1 +f 2249//1 2250//1 2211//1 +f 2211//1 2250//1 2212//1 +f 2250//1 2251//1 2212//1 +f 2212//1 2251//1 2213//1 +f 2251//1 2252//1 2213//1 +f 2213//1 2252//1 2214//1 +f 2252//1 2253//1 2214//1 +f 2214//1 2253//1 2215//1 +f 2253//1 2254//1 2215//1 +f 2215//1 2254//1 2216//1 +f 2254//1 2255//1 2216//1 +f 2216//1 2255//1 2217//1 +f 2255//1 2256//1 2217//1 +f 2217//1 2256//1 2218//1 +f 2256//1 2257//1 2218//1 +f 2218//1 2257//1 2219//1 +f 2257//1 2258//1 2219//1 +f 2219//1 2258//1 2220//1 +f 2258//1 2259//1 2220//1 +f 2220//1 2259//1 16//1 +f 2259//1 15//1 16//1 +f 94//1 2260//1 2221//1 +f 2260//1 2261//1 2221//1 +f 2221//1 2261//1 2222//1 +f 2261//1 2262//1 2222//1 +f 2222//1 2262//1 2223//1 +f 2262//1 2263//1 2223//1 +f 2223//1 2263//1 2224//1 +f 2263//1 2264//1 2224//1 +f 2224//1 2264//1 2225//1 +f 2264//1 2265//1 2225//1 +f 2225//1 2265//1 2226//1 +f 2265//1 2266//1 2226//1 +f 2226//1 2266//1 2227//1 +f 2266//1 2267//1 2227//1 +f 2227//1 2267//1 2228//1 +f 2267//1 2268//1 2228//1 +f 2228//1 2268//1 2229//1 +f 2268//1 2269//1 2229//1 +f 2229//1 2269//1 2230//1 +f 2269//1 2270//1 2230//1 +f 2230//1 2270//1 2231//1 +f 2270//1 2271//1 2231//1 +f 2231//1 2271//1 2232//1 +f 2271//1 2272//1 2232//1 +f 2232//1 2272//1 2233//1 +f 2272//1 2273//1 2233//1 +f 2233//1 2273//1 2234//1 +f 2273//1 2274//1 2234//1 +f 2234//1 2274//1 2235//1 +f 2274//1 2275//1 2235//1 +f 2235//1 2275//1 2236//1 +f 2275//1 2276//1 2236//1 +f 2236//1 2276//1 2237//1 +f 2276//1 2277//1 2237//1 +f 2237//1 2277//1 2238//1 +f 2277//1 2278//1 2238//1 +f 2238//1 2278//1 2239//1 +f 2278//1 2279//1 2239//1 +f 2239//1 2279//1 2240//1 +f 2279//1 2280//1 2240//1 +f 2240//1 2280//1 2241//1 +f 2280//1 2281//1 2241//1 +f 2241//1 2281//1 2242//1 +f 2281//1 2282//1 2242//1 +f 2242//1 2282//1 2243//1 +f 2282//1 2283//1 2243//1 +f 2243//1 2283//1 2244//1 +f 2283//1 2284//1 2244//1 +f 2244//1 2284//1 2245//1 +f 2284//1 2285//1 2245//1 +f 2245//1 2285//1 2246//1 +f 2285//1 2286//1 2246//1 +f 2246//1 2286//1 2247//1 +f 2286//1 2287//1 2247//1 +f 2247//1 2287//1 2248//1 +f 2287//1 2288//1 2248//1 +f 2248//1 2288//1 2249//1 +f 2288//1 2289//1 2249//1 +f 2249//1 2289//1 2250//1 +f 2289//1 2290//1 2250//1 +f 2250//1 2290//1 2251//1 +f 2290//1 2291//1 2251//1 +f 2251//1 2291//1 2252//1 +f 2291//1 2292//1 2252//1 +f 2252//1 2292//1 2253//1 +f 2292//1 2293//1 2253//1 +f 2253//1 2293//1 2254//1 +f 2293//1 2294//1 2254//1 +f 2254//1 2294//1 2255//1 +f 2294//1 2295//1 2255//1 +f 2255//1 2295//1 2256//1 +f 2295//1 2296//1 2256//1 +f 2256//1 2296//1 2257//1 +f 2296//1 2297//1 2257//1 +f 2257//1 2297//1 2258//1 +f 2297//1 2298//1 2258//1 +f 2258//1 2298//1 2259//1 +f 2298//1 2299//1 2259//1 +f 2259//1 2299//1 15//1 +f 2299//1 14//1 15//1 +f 95//1 2300//1 2260//1 +f 2300//1 2301//1 2260//1 +f 2260//1 2301//1 2261//1 +f 2301//1 2302//1 2261//1 +f 2261//1 2302//1 2262//1 +f 2302//1 2303//1 2262//1 +f 2262//1 2303//1 2263//1 +f 2303//1 2304//1 2263//1 +f 2263//1 2304//1 2264//1 +f 2304//1 2305//1 2264//1 +f 2264//1 2305//1 2265//1 +f 2305//1 2306//1 2265//1 +f 2265//1 2306//1 2266//1 +f 2306//1 2307//1 2266//1 +f 2266//1 2307//1 2267//1 +f 2307//1 2308//1 2267//1 +f 2267//1 2308//1 2268//1 +f 2308//1 2309//1 2268//1 +f 2268//1 2309//1 2269//1 +f 2309//1 2310//1 2269//1 +f 2269//1 2310//1 2270//1 +f 2310//1 2311//1 2270//1 +f 2270//1 2311//1 2271//1 +f 2311//1 2312//1 2271//1 +f 2271//1 2312//1 2272//1 +f 2312//1 2313//1 2272//1 +f 2272//1 2313//1 2273//1 +f 2313//1 2314//1 2273//1 +f 2273//1 2314//1 2274//1 +f 2314//1 2315//1 2274//1 +f 2274//1 2315//1 2275//1 +f 2315//1 2316//1 2275//1 +f 2275//1 2316//1 2276//1 +f 2316//1 2317//1 2276//1 +f 2276//1 2317//1 2277//1 +f 2317//1 2318//1 2277//1 +f 2277//1 2318//1 2278//1 +f 2318//1 2319//1 2278//1 +f 2278//1 2319//1 2279//1 +f 2319//1 2320//1 2279//1 +f 2279//1 2320//1 2280//1 +f 2320//1 2321//1 2280//1 +f 2280//1 2321//1 2281//1 +f 2321//1 2322//1 2281//1 +f 2281//1 2322//1 2282//1 +f 2322//1 2323//1 2282//1 +f 2282//1 2323//1 2283//1 +f 2323//1 2324//1 2283//1 +f 2283//1 2324//1 2284//1 +f 2324//1 2325//1 2284//1 +f 2284//1 2325//1 2285//1 +f 2325//1 2326//1 2285//1 +f 2285//1 2326//1 2286//1 +f 2326//1 2327//1 2286//1 +f 2286//1 2327//1 2287//1 +f 2327//1 2328//1 2287//1 +f 2287//1 2328//1 2288//1 +f 2328//1 2329//1 2288//1 +f 2288//1 2329//1 2289//1 +f 2329//1 2330//1 2289//1 +f 2289//1 2330//1 2290//1 +f 2330//1 2331//1 2290//1 +f 2290//1 2331//1 2291//1 +f 2331//1 2332//1 2291//1 +f 2291//1 2332//1 2292//1 +f 2332//1 2333//1 2292//1 +f 2292//1 2333//1 2293//1 +f 2333//1 2334//1 2293//1 +f 2293//1 2334//1 2294//1 +f 2334//1 2335//1 2294//1 +f 2294//1 2335//1 2295//1 +f 2335//1 2336//1 2295//1 +f 2295//1 2336//1 2296//1 +f 2336//1 2337//1 2296//1 +f 2296//1 2337//1 2297//1 +f 2337//1 2338//1 2297//1 +f 2297//1 2338//1 2298//1 +f 2338//1 2339//1 2298//1 +f 2298//1 2339//1 2299//1 +f 2339//1 2340//1 2299//1 +f 2299//1 2340//1 14//1 +f 2340//1 13//1 14//1 +f 96//1 2341//1 2300//1 +f 2341//1 2342//1 2300//1 +f 2300//1 2342//1 2301//1 +f 2342//1 2343//1 2301//1 +f 2301//1 2343//1 2302//1 +f 2343//1 2344//1 2302//1 +f 2302//1 2344//1 2303//1 +f 2344//1 2345//1 2303//1 +f 2303//1 2345//1 2304//1 +f 2345//1 2346//1 2304//1 +f 2304//1 2346//1 2305//1 +f 2346//1 2347//1 2305//1 +f 2305//1 2347//1 2306//1 +f 2347//1 2348//1 2306//1 +f 2306//1 2348//1 2307//1 +f 2348//1 2349//1 2307//1 +f 2307//1 2349//1 2308//1 +f 2349//1 2350//1 2308//1 +f 2308//1 2350//1 2309//1 +f 2350//1 2351//1 2309//1 +f 2309//1 2351//1 2310//1 +f 2351//1 2352//1 2310//1 +f 2310//1 2352//1 2311//1 +f 2352//1 2353//1 2311//1 +f 2311//1 2353//1 2312//1 +f 2353//1 2354//1 2312//1 +f 2312//1 2354//1 2313//1 +f 2354//1 2355//1 2313//1 +f 2313//1 2355//1 2314//1 +f 2355//1 2356//1 2314//1 +f 2314//1 2356//1 2315//1 +f 2356//1 2357//1 2315//1 +f 2315//1 2357//1 2316//1 +f 2357//1 2358//1 2316//1 +f 2316//1 2358//1 2317//1 +f 2358//1 2359//1 2317//1 +f 2317//1 2359//1 2318//1 +f 2359//1 2360//1 2318//1 +f 2318//1 2360//1 2319//1 +f 2360//1 2361//1 2319//1 +f 2319//1 2361//1 2320//1 +f 2361//1 2362//1 2320//1 +f 2320//1 2362//1 2321//1 +f 2362//1 2363//1 2321//1 +f 2321//1 2363//1 2322//1 +f 2363//1 2364//1 2322//1 +f 2322//1 2364//1 2323//1 +f 2364//1 2365//1 2323//1 +f 2323//1 2365//1 2324//1 +f 2365//1 2366//1 2324//1 +f 2324//1 2366//1 2325//1 +f 2366//1 2367//1 2325//1 +f 2325//1 2367//1 2326//1 +f 2367//1 2368//1 2326//1 +f 2326//1 2368//1 2327//1 +f 2368//1 2369//1 2327//1 +f 2327//1 2369//1 2328//1 +f 2369//1 2370//1 2328//1 +f 2328//1 2370//1 2329//1 +f 2370//1 2371//1 2329//1 +f 2329//1 2371//1 2330//1 +f 2371//1 2372//1 2330//1 +f 2330//1 2372//1 2331//1 +f 2372//1 2373//1 2331//1 +f 2331//1 2373//1 2332//1 +f 2373//1 2374//1 2332//1 +f 2332//1 2374//1 2333//1 +f 2374//1 2375//1 2333//1 +f 2333//1 2375//1 2334//1 +f 2375//1 2376//1 2334//1 +f 2334//1 2376//1 2335//1 +f 2376//1 2377//1 2335//1 +f 2335//1 2377//1 2336//1 +f 2377//1 2378//1 2336//1 +f 2336//1 2378//1 2337//1 +f 2378//1 2379//1 2337//1 +f 2337//1 2379//1 2338//1 +f 2379//1 2380//1 2338//1 +f 2338//1 2380//1 2339//1 +f 2380//1 2381//1 2339//1 +f 2339//1 2381//1 2340//1 +f 2381//1 2382//1 2340//1 +f 2340//1 2382//1 13//1 +f 2382//1 12//1 13//1 +f 97//1 2383//1 2341//1 +f 2383//1 2384//1 2341//1 +f 2341//1 2384//1 2342//1 +f 2384//1 2385//1 2342//1 +f 2342//1 2385//1 2343//1 +f 2385//1 2386//1 2343//1 +f 2343//1 2386//1 2344//1 +f 2386//1 2387//1 2344//1 +f 2344//1 2387//1 2345//1 +f 2387//1 2388//1 2345//1 +f 2345//1 2388//1 2346//1 +f 2388//1 2389//1 2346//1 +f 2346//1 2389//1 2347//1 +f 2389//1 2390//1 2347//1 +f 2347//1 2390//1 2348//1 +f 2390//1 2391//1 2348//1 +f 2348//1 2391//1 2349//1 +f 2391//1 2392//1 2349//1 +f 2349//1 2392//1 2350//1 +f 2392//1 2393//1 2350//1 +f 2350//1 2393//1 2351//1 +f 2393//1 2394//1 2351//1 +f 2351//1 2394//1 2352//1 +f 2394//1 2395//1 2352//1 +f 2352//1 2395//1 2353//1 +f 2395//1 2396//1 2353//1 +f 2353//1 2396//1 2354//1 +f 2396//1 2397//1 2354//1 +f 2354//1 2397//1 2355//1 +f 2397//1 2398//1 2355//1 +f 2355//1 2398//1 2356//1 +f 2398//1 2399//1 2356//1 +f 2356//1 2399//1 2357//1 +f 2399//1 2400//1 2357//1 +f 2357//1 2400//1 2358//1 +f 2400//1 2401//1 2358//1 +f 2358//1 2401//1 2359//1 +f 2401//1 2402//1 2359//1 +f 2359//1 2402//1 2360//1 +f 2402//1 2403//1 2360//1 +f 2360//1 2403//1 2361//1 +f 2403//1 2404//1 2361//1 +f 2361//1 2404//1 2362//1 +f 2404//1 2405//1 2362//1 +f 2362//1 2405//1 2363//1 +f 2405//1 2406//1 2363//1 +f 2363//1 2406//1 2364//1 +f 2406//1 2407//1 2364//1 +f 2364//1 2407//1 2365//1 +f 2407//1 2408//1 2365//1 +f 2365//1 2408//1 2366//1 +f 2408//1 2409//1 2366//1 +f 2366//1 2409//1 2367//1 +f 2409//1 2410//1 2367//1 +f 2367//1 2410//1 2368//1 +f 2410//1 2411//1 2368//1 +f 2368//1 2411//1 2369//1 +f 2411//1 2412//1 2369//1 +f 2369//1 2412//1 2370//1 +f 2412//1 2413//1 2370//1 +f 2370//1 2413//1 2371//1 +f 2413//1 2414//1 2371//1 +f 2371//1 2414//1 2372//1 +f 2414//1 2415//1 2372//1 +f 2372//1 2415//1 2373//1 +f 2415//1 2416//1 2373//1 +f 2373//1 2416//1 2374//1 +f 2416//1 2417//1 2374//1 +f 2374//1 2417//1 2375//1 +f 2417//1 2418//1 2375//1 +f 2375//1 2418//1 2376//1 +f 2418//1 2419//1 2376//1 +f 2376//1 2419//1 2377//1 +f 2419//1 2420//1 2377//1 +f 2377//1 2420//1 2378//1 +f 2420//1 2421//1 2378//1 +f 2378//1 2421//1 2379//1 +f 2421//1 2422//1 2379//1 +f 2379//1 2422//1 2380//1 +f 2422//1 2423//1 2380//1 +f 2380//1 2423//1 2381//1 +f 2423//1 2424//1 2381//1 +f 2381//1 2424//1 2382//1 +f 2424//1 2425//1 2382//1 +f 2382//1 2425//1 12//1 +f 2425//1 11//1 12//1 +f 98//1 2426//1 2383//1 +f 2426//1 2427//1 2383//1 +f 2383//1 2427//1 2384//1 +f 2427//1 2428//1 2384//1 +f 2384//1 2428//1 2385//1 +f 2428//1 2429//1 2385//1 +f 2385//1 2429//1 2386//1 +f 2429//1 2430//1 2386//1 +f 2386//1 2430//1 2387//1 +f 2430//1 2431//1 2387//1 +f 2387//1 2431//1 2388//1 +f 2431//1 2432//1 2388//1 +f 2388//1 2432//1 2389//1 +f 2432//1 2433//1 2389//1 +f 2389//1 2433//1 2390//1 +f 2433//1 2434//1 2390//1 +f 2390//1 2434//1 2391//1 +f 2434//1 2435//1 2391//1 +f 2391//1 2435//1 2392//1 +f 2435//1 2436//1 2392//1 +f 2392//1 2436//1 2393//1 +f 2436//1 2437//1 2393//1 +f 2393//1 2437//1 2394//1 +f 2437//1 2438//1 2394//1 +f 2394//1 2438//1 2395//1 +f 2438//1 2439//1 2395//1 +f 2395//1 2439//1 2396//1 +f 2439//1 2440//1 2396//1 +f 2396//1 2440//1 2397//1 +f 2440//1 2441//1 2397//1 +f 2397//1 2441//1 2398//1 +f 2441//1 2442//1 2398//1 +f 2398//1 2442//1 2399//1 +f 2442//1 2443//1 2399//1 +f 2399//1 2443//1 2400//1 +f 2443//1 2444//1 2400//1 +f 2400//1 2444//1 2401//1 +f 2444//1 2445//1 2401//1 +f 2401//1 2445//1 2402//1 +f 2445//1 2446//1 2402//1 +f 2402//1 2446//1 2403//1 +f 2446//1 2447//1 2403//1 +f 2403//1 2447//1 2404//1 +f 2447//1 2448//1 2404//1 +f 2404//1 2448//1 2405//1 +f 2448//1 2449//1 2405//1 +f 2405//1 2449//1 2406//1 +f 2449//1 2450//1 2406//1 +f 2406//1 2450//1 2407//1 +f 2450//1 2451//1 2407//1 +f 2407//1 2451//1 2408//1 +f 2451//1 2452//1 2408//1 +f 2408//1 2452//1 2409//1 +f 2452//1 2453//1 2409//1 +f 2409//1 2453//1 2410//1 +f 2453//1 2454//1 2410//1 +f 2410//1 2454//1 2411//1 +f 2454//1 2455//1 2411//1 +f 2411//1 2455//1 2412//1 +f 2455//1 2456//1 2412//1 +f 2412//1 2456//1 2413//1 +f 2456//1 2457//1 2413//1 +f 2413//1 2457//1 2414//1 +f 2457//1 2458//1 2414//1 +f 2414//1 2458//1 2415//1 +f 2458//1 2459//1 2415//1 +f 2415//1 2459//1 2416//1 +f 2459//1 2460//1 2416//1 +f 2416//1 2460//1 2417//1 +f 2460//1 2461//1 2417//1 +f 2417//1 2461//1 2418//1 +f 2461//1 2462//1 2418//1 +f 2418//1 2462//1 2419//1 +f 2462//1 2463//1 2419//1 +f 2419//1 2463//1 2420//1 +f 2463//1 2464//1 2420//1 +f 2420//1 2464//1 2421//1 +f 2464//1 2465//1 2421//1 +f 2421//1 2465//1 2422//1 +f 2465//1 2466//1 2422//1 +f 2422//1 2466//1 2423//1 +f 2466//1 2467//1 2423//1 +f 2423//1 2467//1 2424//1 +f 2467//1 2468//1 2424//1 +f 2424//1 2468//1 2425//1 +f 2468//1 2469//1 2425//1 +f 2425//1 2469//1 11//1 +f 2469//1 10//1 11//1 +f 99//1 2470//1 2426//1 +f 2470//1 2471//1 2426//1 +f 2426//1 2471//1 2427//1 +f 2471//1 2472//1 2427//1 +f 2427//1 2472//1 2428//1 +f 2472//1 2473//1 2428//1 +f 2428//1 2473//1 2429//1 +f 2473//1 2474//1 2429//1 +f 2429//1 2474//1 2430//1 +f 2474//1 2475//1 2430//1 +f 2430//1 2475//1 2431//1 +f 2475//1 2476//1 2431//1 +f 2431//1 2476//1 2432//1 +f 2476//1 2477//1 2432//1 +f 2432//1 2477//1 2433//1 +f 2477//1 2478//1 2433//1 +f 2433//1 2478//1 2434//1 +f 2478//1 2479//1 2434//1 +f 2434//1 2479//1 2435//1 +f 2479//1 2480//1 2435//1 +f 2435//1 2480//1 2436//1 +f 2480//1 2481//1 2436//1 +f 2436//1 2481//1 2437//1 +f 2481//1 2482//1 2437//1 +f 2437//1 2482//1 2438//1 +f 2482//1 2483//1 2438//1 +f 2438//1 2483//1 2439//1 +f 2483//1 2484//1 2439//1 +f 2439//1 2484//1 2440//1 +f 2484//1 2485//1 2440//1 +f 2440//1 2485//1 2441//1 +f 2485//1 2486//1 2441//1 +f 2441//1 2486//1 2442//1 +f 2486//1 2487//1 2442//1 +f 2442//1 2487//1 2443//1 +f 2487//1 2488//1 2443//1 +f 2443//1 2488//1 2444//1 +f 2488//1 2489//1 2444//1 +f 2444//1 2489//1 2445//1 +f 2489//1 2490//1 2445//1 +f 2445//1 2490//1 2446//1 +f 2490//1 2491//1 2446//1 +f 2446//1 2491//1 2447//1 +f 2491//1 2492//1 2447//1 +f 2447//1 2492//1 2448//1 +f 2492//1 2493//1 2448//1 +f 2448//1 2493//1 2449//1 +f 2493//1 2494//1 2449//1 +f 2449//1 2494//1 2450//1 +f 2494//1 2495//1 2450//1 +f 2450//1 2495//1 2451//1 +f 2495//1 2496//1 2451//1 +f 2451//1 2496//1 2452//1 +f 2496//1 2497//1 2452//1 +f 2452//1 2497//1 2453//1 +f 2497//1 2498//1 2453//1 +f 2453//1 2498//1 2454//1 +f 2498//1 2499//1 2454//1 +f 2454//1 2499//1 2455//1 +f 2499//1 2500//1 2455//1 +f 2455//1 2500//1 2456//1 +f 2500//1 2501//1 2456//1 +f 2456//1 2501//1 2457//1 +f 2501//1 2502//1 2457//1 +f 2457//1 2502//1 2458//1 +f 2502//1 2503//1 2458//1 +f 2458//1 2503//1 2459//1 +f 2503//1 2504//1 2459//1 +f 2459//1 2504//1 2460//1 +f 2504//1 2505//1 2460//1 +f 2460//1 2505//1 2461//1 +f 2505//1 2506//1 2461//1 +f 2461//1 2506//1 2462//1 +f 2506//1 2507//1 2462//1 +f 2462//1 2507//1 2463//1 +f 2507//1 2508//1 2463//1 +f 2463//1 2508//1 2464//1 +f 2508//1 2509//1 2464//1 +f 2464//1 2509//1 2465//1 +f 2509//1 2510//1 2465//1 +f 2465//1 2510//1 2466//1 +f 2510//1 2511//1 2466//1 +f 2466//1 2511//1 2467//1 +f 2511//1 2512//1 2467//1 +f 2467//1 2512//1 2468//1 +f 2512//1 2513//1 2468//1 +f 2468//1 2513//1 2469//1 +f 2513//1 2514//1 2469//1 +f 2469//1 2514//1 10//1 +f 2514//1 9//1 10//1 +f 100//1 2515//1 2470//1 +f 2515//1 2516//1 2470//1 +f 2470//1 2516//1 2471//1 +f 2516//1 2517//1 2471//1 +f 2471//1 2517//1 2472//1 +f 2517//1 2518//1 2472//1 +f 2472//1 2518//1 2473//1 +f 2518//1 2519//1 2473//1 +f 2473//1 2519//1 2474//1 +f 2519//1 2520//1 2474//1 +f 2474//1 2520//1 2475//1 +f 2520//1 2521//1 2475//1 +f 2475//1 2521//1 2476//1 +f 2521//1 2522//1 2476//1 +f 2476//1 2522//1 2477//1 +f 2522//1 2523//1 2477//1 +f 2477//1 2523//1 2478//1 +f 2523//1 2524//1 2478//1 +f 2478//1 2524//1 2479//1 +f 2524//1 2525//1 2479//1 +f 2479//1 2525//1 2480//1 +f 2525//1 2526//1 2480//1 +f 2480//1 2526//1 2481//1 +f 2526//1 2527//1 2481//1 +f 2481//1 2527//1 2482//1 +f 2527//1 2528//1 2482//1 +f 2482//1 2528//1 2483//1 +f 2528//1 2529//1 2483//1 +f 2483//1 2529//1 2484//1 +f 2529//1 2530//1 2484//1 +f 2484//1 2530//1 2485//1 +f 2530//1 2531//1 2485//1 +f 2485//1 2531//1 2486//1 +f 2531//1 2532//1 2486//1 +f 2486//1 2532//1 2487//1 +f 2532//1 2533//1 2487//1 +f 2487//1 2533//1 2488//1 +f 2533//1 2534//1 2488//1 +f 2488//1 2534//1 2489//1 +f 2534//1 2535//1 2489//1 +f 2489//1 2535//1 2490//1 +f 2535//1 2536//1 2490//1 +f 2490//1 2536//1 2491//1 +f 2536//1 2537//1 2491//1 +f 2491//1 2537//1 2492//1 +f 2537//1 2538//1 2492//1 +f 2492//1 2538//1 2493//1 +f 2538//1 2539//1 2493//1 +f 2493//1 2539//1 2494//1 +f 2539//1 2540//1 2494//1 +f 2494//1 2540//1 2495//1 +f 2540//1 2541//1 2495//1 +f 2495//1 2541//1 2496//1 +f 2541//1 2542//1 2496//1 +f 2496//1 2542//1 2497//1 +f 2542//1 2543//1 2497//1 +f 2497//1 2543//1 2498//1 +f 2543//1 2544//1 2498//1 +f 2498//1 2544//1 2499//1 +f 2544//1 2545//1 2499//1 +f 2499//1 2545//1 2500//1 +f 2545//1 2546//1 2500//1 +f 2500//1 2546//1 2501//1 +f 2546//1 2547//1 2501//1 +f 2501//1 2547//1 2502//1 +f 2547//1 2548//1 2502//1 +f 2502//1 2548//1 2503//1 +f 2548//1 2549//1 2503//1 +f 2503//1 2549//1 2504//1 +f 2549//1 2550//1 2504//1 +f 2504//1 2550//1 2505//1 +f 2550//1 2551//1 2505//1 +f 2505//1 2551//1 2506//1 +f 2551//1 2552//1 2506//1 +f 2506//1 2552//1 2507//1 +f 2552//1 2553//1 2507//1 +f 2507//1 2553//1 2508//1 +f 2553//1 2554//1 2508//1 +f 2508//1 2554//1 2509//1 +f 2554//1 2555//1 2509//1 +f 2509//1 2555//1 2510//1 +f 2555//1 2556//1 2510//1 +f 2510//1 2556//1 2511//1 +f 2556//1 2557//1 2511//1 +f 2511//1 2557//1 2512//1 +f 2557//1 2558//1 2512//1 +f 2512//1 2558//1 2513//1 +f 2558//1 2559//1 2513//1 +f 2513//1 2559//1 2514//1 +f 2559//1 2560//1 2514//1 +f 2514//1 2560//1 9//1 +f 2560//1 8//1 9//1 +f 101//1 2561//1 2515//1 +f 2561//1 2562//1 2515//1 +f 2515//1 2562//1 2516//1 +f 2562//1 2563//1 2516//1 +f 2516//1 2563//1 2517//1 +f 2563//1 2564//1 2517//1 +f 2517//1 2564//1 2518//1 +f 2564//1 2565//1 2518//1 +f 2518//1 2565//1 2519//1 +f 2565//1 2566//1 2519//1 +f 2519//1 2566//1 2520//1 +f 2566//1 2567//1 2520//1 +f 2520//1 2567//1 2521//1 +f 2567//1 2568//1 2521//1 +f 2521//1 2568//1 2522//1 +f 2568//1 2569//1 2522//1 +f 2522//1 2569//1 2523//1 +f 2569//1 2570//1 2523//1 +f 2523//1 2570//1 2524//1 +f 2570//1 2571//1 2524//1 +f 2524//1 2571//1 2525//1 +f 2571//1 2572//1 2525//1 +f 2525//1 2572//1 2526//1 +f 2572//1 2573//1 2526//1 +f 2526//1 2573//1 2527//1 +f 2573//1 2574//1 2527//1 +f 2527//1 2574//1 2528//1 +f 2574//1 2575//1 2528//1 +f 2528//1 2575//1 2529//1 +f 2575//1 2576//1 2529//1 +f 2529//1 2576//1 2530//1 +f 2576//1 2577//1 2530//1 +f 2530//1 2577//1 2531//1 +f 2577//1 2578//1 2531//1 +f 2531//1 2578//1 2532//1 +f 2578//1 2579//1 2532//1 +f 2532//1 2579//1 2533//1 +f 2579//1 2580//1 2533//1 +f 2533//1 2580//1 2534//1 +f 2580//1 2581//1 2534//1 +f 2534//1 2581//1 2535//1 +f 2581//1 2582//1 2535//1 +f 2535//1 2582//1 2536//1 +f 2582//1 2583//1 2536//1 +f 2536//1 2583//1 2537//1 +f 2583//1 2584//1 2537//1 +f 2537//1 2584//1 2538//1 +f 2584//1 2585//1 2538//1 +f 2538//1 2585//1 2539//1 +f 2585//1 2586//1 2539//1 +f 2539//1 2586//1 2540//1 +f 2586//1 2587//1 2540//1 +f 2540//1 2587//1 2541//1 +f 2587//1 2588//1 2541//1 +f 2541//1 2588//1 2542//1 +f 2588//1 2589//1 2542//1 +f 2542//1 2589//1 2543//1 +f 2589//1 2590//1 2543//1 +f 2543//1 2590//1 2544//1 +f 2590//1 2591//1 2544//1 +f 2544//1 2591//1 2545//1 +f 2591//1 2592//1 2545//1 +f 2545//1 2592//1 2546//1 +f 2592//1 2593//1 2546//1 +f 2546//1 2593//1 2547//1 +f 2593//1 2594//1 2547//1 +f 2547//1 2594//1 2548//1 +f 2594//1 2595//1 2548//1 +f 2548//1 2595//1 2549//1 +f 2595//1 2596//1 2549//1 +f 2549//1 2596//1 2550//1 +f 2596//1 2597//1 2550//1 +f 2550//1 2597//1 2551//1 +f 2597//1 2598//1 2551//1 +f 2551//1 2598//1 2552//1 +f 2598//1 2599//1 2552//1 +f 2552//1 2599//1 2553//1 +f 2599//1 2600//1 2553//1 +f 2553//1 2600//1 2554//1 +f 2600//1 2601//1 2554//1 +f 2554//1 2601//1 2555//1 +f 2601//1 2602//1 2555//1 +f 2555//1 2602//1 2556//1 +f 2602//1 2603//1 2556//1 +f 2556//1 2603//1 2557//1 +f 2603//1 2604//1 2557//1 +f 2557//1 2604//1 2558//1 +f 2604//1 2605//1 2558//1 +f 2558//1 2605//1 2559//1 +f 2605//1 2606//1 2559//1 +f 2559//1 2606//1 2560//1 +f 2606//1 2607//1 2560//1 +f 2560//1 2607//1 8//1 +f 2607//1 7//1 8//1 +f 102//1 2608//1 2561//1 +f 2608//1 2609//1 2561//1 +f 2561//1 2609//1 2562//1 +f 2609//1 2610//1 2562//1 +f 2562//1 2610//1 2563//1 +f 2610//1 2611//1 2563//1 +f 2563//1 2611//1 2564//1 +f 2611//1 2612//1 2564//1 +f 2564//1 2612//1 2565//1 +f 2612//1 2613//1 2565//1 +f 2565//1 2613//1 2566//1 +f 2613//1 2614//1 2566//1 +f 2566//1 2614//1 2567//1 +f 2614//1 2615//1 2567//1 +f 2567//1 2615//1 2568//1 +f 2615//1 2616//1 2568//1 +f 2568//1 2616//1 2569//1 +f 2616//1 2617//1 2569//1 +f 2569//1 2617//1 2570//1 +f 2617//1 2618//1 2570//1 +f 2570//1 2618//1 2571//1 +f 2618//1 2619//1 2571//1 +f 2571//1 2619//1 2572//1 +f 2619//1 2620//1 2572//1 +f 2572//1 2620//1 2573//1 +f 2620//1 2621//1 2573//1 +f 2573//1 2621//1 2574//1 +f 2621//1 2622//1 2574//1 +f 2574//1 2622//1 2575//1 +f 2622//1 2623//1 2575//1 +f 2575//1 2623//1 2576//1 +f 2623//1 2624//1 2576//1 +f 2576//1 2624//1 2577//1 +f 2624//1 2625//1 2577//1 +f 2577//1 2625//1 2578//1 +f 2625//1 2626//1 2578//1 +f 2578//1 2626//1 2579//1 +f 2626//1 2627//1 2579//1 +f 2579//1 2627//1 2580//1 +f 2627//1 2628//1 2580//1 +f 2580//1 2628//1 2581//1 +f 2628//1 2629//1 2581//1 +f 2581//1 2629//1 2582//1 +f 2629//1 2630//1 2582//1 +f 2582//1 2630//1 2583//1 +f 2630//1 2631//1 2583//1 +f 2583//1 2631//1 2584//1 +f 2631//1 2632//1 2584//1 +f 2584//1 2632//1 2585//1 +f 2632//1 2633//1 2585//1 +f 2585//1 2633//1 2586//1 +f 2633//1 2634//1 2586//1 +f 2586//1 2634//1 2587//1 +f 2634//1 2635//1 2587//1 +f 2587//1 2635//1 2588//1 +f 2635//1 2636//1 2588//1 +f 2588//1 2636//1 2589//1 +f 2636//1 2637//1 2589//1 +f 2589//1 2637//1 2590//1 +f 2637//1 2638//1 2590//1 +f 2590//1 2638//1 2591//1 +f 2638//1 2639//1 2591//1 +f 2591//1 2639//1 2592//1 +f 2639//1 2640//1 2592//1 +f 2592//1 2640//1 2593//1 +f 2640//1 2641//1 2593//1 +f 2593//1 2641//1 2594//1 +f 2641//1 2642//1 2594//1 +f 2594//1 2642//1 2595//1 +f 2642//1 2643//1 2595//1 +f 2595//1 2643//1 2596//1 +f 2643//1 2644//1 2596//1 +f 2596//1 2644//1 2597//1 +f 2644//1 2645//1 2597//1 +f 2597//1 2645//1 2598//1 +f 2645//1 2646//1 2598//1 +f 2598//1 2646//1 2599//1 +f 2646//1 2647//1 2599//1 +f 2599//1 2647//1 2600//1 +f 2647//1 2648//1 2600//1 +f 2600//1 2648//1 2601//1 +f 2648//1 2649//1 2601//1 +f 2601//1 2649//1 2602//1 +f 2649//1 2650//1 2602//1 +f 2602//1 2650//1 2603//1 +f 2650//1 2651//1 2603//1 +f 2603//1 2651//1 2604//1 +f 2651//1 2652//1 2604//1 +f 2604//1 2652//1 2605//1 +f 2652//1 2653//1 2605//1 +f 2605//1 2653//1 2606//1 +f 2653//1 2654//1 2606//1 +f 2606//1 2654//1 2607//1 +f 2654//1 2655//1 2607//1 +f 2607//1 2655//1 7//1 +f 2655//1 6//1 7//1 +f 103//1 2656//1 2608//1 +f 2656//1 2657//1 2608//1 +f 2608//1 2657//1 2609//1 +f 2657//1 2658//1 2609//1 +f 2609//1 2658//1 2610//1 +f 2658//1 2659//1 2610//1 +f 2610//1 2659//1 2611//1 +f 2659//1 2660//1 2611//1 +f 2611//1 2660//1 2612//1 +f 2660//1 2661//1 2612//1 +f 2612//1 2661//1 2613//1 +f 2661//1 2662//1 2613//1 +f 2613//1 2662//1 2614//1 +f 2662//1 2663//1 2614//1 +f 2614//1 2663//1 2615//1 +f 2663//1 2664//1 2615//1 +f 2615//1 2664//1 2616//1 +f 2664//1 2665//1 2616//1 +f 2616//1 2665//1 2617//1 +f 2665//1 2666//1 2617//1 +f 2617//1 2666//1 2618//1 +f 2666//1 2667//1 2618//1 +f 2618//1 2667//1 2619//1 +f 2667//1 2668//1 2619//1 +f 2619//1 2668//1 2620//1 +f 2668//1 2669//1 2620//1 +f 2620//1 2669//1 2621//1 +f 2669//1 2670//1 2621//1 +f 2621//1 2670//1 2622//1 +f 2670//1 2671//1 2622//1 +f 2622//1 2671//1 2623//1 +f 2671//1 2672//1 2623//1 +f 2623//1 2672//1 2624//1 +f 2672//1 2673//1 2624//1 +f 2624//1 2673//1 2625//1 +f 2673//1 2674//1 2625//1 +f 2625//1 2674//1 2626//1 +f 2674//1 2675//1 2626//1 +f 2626//1 2675//1 2627//1 +f 2675//1 2676//1 2627//1 +f 2627//1 2676//1 2628//1 +f 2676//1 2677//1 2628//1 +f 2628//1 2677//1 2629//1 +f 2677//1 2678//1 2629//1 +f 2629//1 2678//1 2630//1 +f 2678//1 2679//1 2630//1 +f 2630//1 2679//1 2631//1 +f 2679//1 2680//1 2631//1 +f 2631//1 2680//1 2632//1 +f 2680//1 2681//1 2632//1 +f 2632//1 2681//1 2633//1 +f 2681//1 2682//1 2633//1 +f 2633//1 2682//1 2634//1 +f 2682//1 2683//1 2634//1 +f 2634//1 2683//1 2635//1 +f 2683//1 2684//1 2635//1 +f 2635//1 2684//1 2636//1 +f 2684//1 2685//1 2636//1 +f 2636//1 2685//1 2637//1 +f 2685//1 2686//1 2637//1 +f 2637//1 2686//1 2638//1 +f 2686//1 2687//1 2638//1 +f 2638//1 2687//1 2639//1 +f 2687//1 2688//1 2639//1 +f 2639//1 2688//1 2640//1 +f 2688//1 2689//1 2640//1 +f 2640//1 2689//1 2641//1 +f 2689//1 2690//1 2641//1 +f 2641//1 2690//1 2642//1 +f 2690//1 2691//1 2642//1 +f 2642//1 2691//1 2643//1 +f 2691//1 2692//1 2643//1 +f 2643//1 2692//1 2644//1 +f 2692//1 2693//1 2644//1 +f 2644//1 2693//1 2645//1 +f 2693//1 2694//1 2645//1 +f 2645//1 2694//1 2646//1 +f 2694//1 2695//1 2646//1 +f 2646//1 2695//1 2647//1 +f 2695//1 2696//1 2647//1 +f 2647//1 2696//1 2648//1 +f 2696//1 2697//1 2648//1 +f 2648//1 2697//1 2649//1 +f 2697//1 2698//1 2649//1 +f 2649//1 2698//1 2650//1 +f 2698//1 2699//1 2650//1 +f 2650//1 2699//1 2651//1 +f 2699//1 2700//1 2651//1 +f 2651//1 2700//1 2652//1 +f 2700//1 2701//1 2652//1 +f 2652//1 2701//1 2653//1 +f 2701//1 2702//1 2653//1 +f 2653//1 2702//1 2654//1 +f 2702//1 2703//1 2654//1 +f 2654//1 2703//1 2655//1 +f 2703//1 2704//1 2655//1 +f 2655//1 2704//1 6//1 +f 2704//1 5//1 6//1 +f 104//1 254//1 2656//1 +f 254//1 253//1 2656//1 +f 2656//1 253//1 2657//1 +f 253//1 252//1 2657//1 +f 2657//1 252//1 2658//1 +f 252//1 251//1 2658//1 +f 2658//1 251//1 2659//1 +f 251//1 250//1 2659//1 +f 2659//1 250//1 2660//1 +f 250//1 249//1 2660//1 +f 2660//1 249//1 2661//1 +f 249//1 248//1 2661//1 +f 2661//1 248//1 2662//1 +f 248//1 247//1 2662//1 +f 2662//1 247//1 2663//1 +f 247//1 246//1 2663//1 +f 2663//1 246//1 2664//1 +f 246//1 245//1 2664//1 +f 2664//1 245//1 2665//1 +f 245//1 244//1 2665//1 +f 2665//1 244//1 2666//1 +f 244//1 243//1 2666//1 +f 2666//1 243//1 2667//1 +f 243//1 242//1 2667//1 +f 2667//1 242//1 2668//1 +f 242//1 241//1 2668//1 +f 2668//1 241//1 2669//1 +f 241//1 240//1 2669//1 +f 2669//1 240//1 2670//1 +f 240//1 239//1 2670//1 +f 2670//1 239//1 2671//1 +f 239//1 238//1 2671//1 +f 2671//1 238//1 2672//1 +f 238//1 237//1 2672//1 +f 2672//1 237//1 2673//1 +f 237//1 236//1 2673//1 +f 2673//1 236//1 2674//1 +f 236//1 235//1 2674//1 +f 2674//1 235//1 2675//1 +f 235//1 234//1 2675//1 +f 2675//1 234//1 2676//1 +f 234//1 233//1 2676//1 +f 2676//1 233//1 2677//1 +f 233//1 232//1 2677//1 +f 2677//1 232//1 2678//1 +f 232//1 231//1 2678//1 +f 2678//1 231//1 2679//1 +f 231//1 230//1 2679//1 +f 2679//1 230//1 2680//1 +f 230//1 229//1 2680//1 +f 2680//1 229//1 2681//1 +f 229//1 228//1 2681//1 +f 2681//1 228//1 2682//1 +f 228//1 227//1 2682//1 +f 2682//1 227//1 2683//1 +f 227//1 226//1 2683//1 +f 2683//1 226//1 2684//1 +f 226//1 225//1 2684//1 +f 2684//1 225//1 2685//1 +f 225//1 224//1 2685//1 +f 2685//1 224//1 2686//1 +f 224//1 223//1 2686//1 +f 2686//1 223//1 2687//1 +f 223//1 222//1 2687//1 +f 2687//1 222//1 2688//1 +f 222//1 221//1 2688//1 +f 2688//1 221//1 2689//1 +f 221//1 220//1 2689//1 +f 2689//1 220//1 2690//1 +f 220//1 219//1 2690//1 +f 2690//1 219//1 2691//1 +f 219//1 218//1 2691//1 +f 2691//1 218//1 2692//1 +f 218//1 217//1 2692//1 +f 2692//1 217//1 2693//1 +f 217//1 216//1 2693//1 +f 2693//1 216//1 2694//1 +f 216//1 215//1 2694//1 +f 2694//1 215//1 2695//1 +f 215//1 214//1 2695//1 +f 2695//1 214//1 2696//1 +f 214//1 213//1 2696//1 +f 2696//1 213//1 2697//1 +f 213//1 212//1 2697//1 +f 2697//1 212//1 2698//1 +f 212//1 211//1 2698//1 +f 2698//1 211//1 2699//1 +f 211//1 210//1 2699//1 +f 2699//1 210//1 2700//1 +f 210//1 209//1 2700//1 +f 2700//1 209//1 2701//1 +f 209//1 208//1 2701//1 +f 2701//1 208//1 2702//1 +f 208//1 207//1 2702//1 +f 2702//1 207//1 2703//1 +f 207//1 206//1 2703//1 +f 2703//1 206//1 2704//1 +f 206//1 205//1 2704//1 +f 2704//1 205//1 5//1 +f 205//1 3//1 5//1 diff --git a/data/torus/torus_only.mtl b/data/torus/torus_only.mtl new file mode 100644 index 000000000..5361e19b8 --- /dev/null +++ b/data/torus/torus_only.mtl @@ -0,0 +1,12 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl None +Ns 0.000000 +Ka 0.000000 0.000000 0.000000 +Kd 0.800000 0.800000 0.800000 +Ks 0.800000 0.800000 0.800000 +Ke 0.000000 0.000000 0.000000 +Ni 1.000000 +d 1.000000 +illum 2 diff --git a/data/torus/torus_only.obj b/data/torus/torus_only.obj new file mode 100644 index 000000000..a6776c93e --- /dev/null +++ b/data/torus/torus_only.obj @@ -0,0 +1,1474 @@ +# Blender v2.77 (sub 0) OBJ File: '' +# www.blender.org +mtllib torus_only.mtl +o Torus +v 1.269537 0.006289 1.359776 +v 1.258843 0.006289 1.196618 +v 1.225636 0.131289 1.200990 +v 1.236043 0.131289 1.359776 +v 1.134912 0.222796 1.212934 +v 1.144537 0.222796 1.359776 +v 1.010982 0.256289 1.229250 +v 1.019537 0.256289 1.359776 +v 0.887051 0.222796 1.245565 +v 0.894537 0.222796 1.359776 +v 0.796328 0.131289 1.257509 +v 0.803031 0.131289 1.359776 +v 0.763121 0.006289 1.261881 +v 0.769537 0.006289 1.359776 +v 0.796328 -0.118711 1.257509 +v 0.803031 -0.118711 1.359776 +v 0.887051 -0.210217 1.245565 +v 0.894537 -0.210217 1.359776 +v 1.010982 -0.243711 1.229250 +v 1.019537 -0.243711 1.359776 +v 1.134912 -0.210217 1.212934 +v 1.144537 -0.210217 1.359776 +v 1.225636 -0.118711 1.200990 +v 1.236043 -0.118711 1.359776 +v 1.226944 0.006289 1.036252 +v 1.194592 0.131289 1.044921 +v 1.106204 0.222796 1.068604 +v 0.985463 0.256289 1.100957 +v 0.864722 0.222796 1.133309 +v 0.776334 0.131289 1.156993 +v 0.743981 0.006289 1.165661 +v 0.776334 -0.118711 1.156993 +v 0.864722 -0.210217 1.133309 +v 0.985463 -0.243711 1.100957 +v 1.106204 -0.210217 1.068604 +v 1.194592 -0.118711 1.044921 +v 1.174387 0.006289 0.881421 +v 1.143442 0.131289 0.894239 +v 1.058902 0.222796 0.929257 +v 0.943417 0.256289 0.977092 +v 0.827932 0.222796 1.024928 +v 0.743391 0.131289 1.059946 +v 0.712447 0.006289 1.072763 +v 0.743391 -0.118711 1.059946 +v 0.827932 -0.210217 1.024928 +v 0.943417 -0.243711 0.977092 +v 1.058902 -0.210217 0.929257 +v 1.143442 -0.118711 0.894239 +v 1.102069 0.006289 0.734776 +v 1.073062 0.131289 0.751522 +v 0.993815 0.222796 0.797276 +v 0.885562 0.256289 0.859776 +v 0.777309 0.222796 0.922276 +v 0.698062 0.131289 0.968029 +v 0.669056 0.006289 0.984776 +v 0.698062 -0.118711 0.968029 +v 0.777309 -0.210217 0.922276 +v 0.885562 -0.243711 0.859776 +v 0.993815 -0.210217 0.797276 +v 1.073062 -0.118711 0.751522 +v 1.011229 0.006289 0.598824 +v 0.984656 0.131289 0.619214 +v 0.912059 0.222796 0.674919 +v 0.812890 0.256289 0.751014 +v 0.713721 0.222796 0.827109 +v 0.641124 0.131289 0.882815 +v 0.614552 0.006289 0.903205 +v 0.641124 -0.118711 0.882815 +v 0.713721 -0.210217 0.827109 +v 0.812890 -0.243711 0.751014 +v 0.912059 -0.210217 0.674919 +v 0.984656 -0.118711 0.619214 +v 0.903420 0.006289 0.475892 +v 0.879737 0.131289 0.499576 +v 0.815032 0.222796 0.564281 +v 0.726644 0.256289 0.652669 +v 0.638255 0.222796 0.741057 +v 0.573551 0.131289 0.805762 +v 0.549867 0.006289 0.829446 +v 0.573551 -0.118711 0.805762 +v 0.638255 -0.210217 0.741057 +v 0.726644 -0.243711 0.652669 +v 0.815032 -0.210217 0.564281 +v 0.879737 -0.118711 0.499576 +v 0.780489 0.006289 0.368084 +v 0.760099 0.131289 0.394656 +v 0.704394 0.222796 0.467253 +v 0.628298 0.256289 0.566423 +v 0.552203 0.222796 0.665592 +v 0.496498 0.131289 0.738188 +v 0.476108 0.006289 0.764761 +v 0.496498 -0.118711 0.738188 +v 0.552203 -0.210217 0.665592 +v 0.628298 -0.243711 0.566423 +v 0.704394 -0.210217 0.467253 +v 0.760099 -0.118711 0.394656 +v 0.644537 0.006289 0.277244 +v 0.627790 0.131289 0.306250 +v 0.582037 0.222796 0.385497 +v 0.519537 0.256289 0.493750 +v 0.457037 0.222796 0.602003 +v 0.411284 0.131289 0.681250 +v 0.394537 0.006289 0.710257 +v 0.411284 -0.118711 0.681250 +v 0.457037 -0.210217 0.602003 +v 0.519537 -0.243711 0.493750 +v 0.582037 -0.210217 0.385497 +v 0.627790 -0.118711 0.306250 +v 0.497891 0.006289 0.204926 +v 0.485074 0.131289 0.235871 +v 0.450056 0.222796 0.320411 +v 0.402221 0.256289 0.435896 +v 0.354385 0.222796 0.551381 +v 0.319367 0.131289 0.635922 +v 0.306550 0.006289 0.666866 +v 0.319367 -0.118711 0.635922 +v 0.354385 -0.210217 0.551381 +v 0.402221 -0.243711 0.435896 +v 0.450056 -0.210217 0.320411 +v 0.485074 -0.118711 0.235871 +v 0.343061 0.006289 0.152368 +v 0.334392 0.131289 0.184721 +v 0.310708 0.222796 0.273109 +v 0.278356 0.256289 0.393850 +v 0.246004 0.222796 0.514591 +v 0.222320 0.131289 0.602979 +v 0.213651 0.006289 0.635331 +v 0.222320 -0.118711 0.602979 +v 0.246004 -0.210217 0.514591 +v 0.278356 -0.243711 0.393850 +v 0.310708 -0.210217 0.273109 +v 0.334392 -0.118711 0.184721 +v 0.182694 0.006289 0.120470 +v 0.178323 0.131289 0.153677 +v 0.166379 0.222796 0.244400 +v 0.150063 0.256289 0.368331 +v 0.133747 0.222796 0.492261 +v 0.121803 0.131289 0.582985 +v 0.117431 0.006289 0.616192 +v 0.121803 -0.118711 0.582985 +v 0.133747 -0.210217 0.492261 +v 0.150063 -0.243711 0.368331 +v 0.166379 -0.210217 0.244400 +v 0.178323 -0.118711 0.153677 +v 0.019537 0.006289 0.109776 +v 0.019537 0.131289 0.143269 +v 0.019537 0.222796 0.234776 +v 0.019537 0.256289 0.359776 +v 0.019537 0.222796 0.484776 +v 0.019537 0.131289 0.576282 +v 0.019537 0.006289 0.609776 +v 0.019537 -0.118711 0.576282 +v 0.019537 -0.210217 0.484776 +v 0.019537 -0.243711 0.359776 +v 0.019537 -0.210217 0.234776 +v 0.019537 -0.118711 0.143269 +v -0.143621 0.006289 0.120470 +v -0.139249 0.131289 0.153677 +v -0.127305 0.222796 0.244400 +v -0.110989 0.256289 0.368331 +v -0.094674 0.222796 0.492261 +v -0.082730 0.131289 0.582985 +v -0.078358 0.006289 0.616192 +v -0.082730 -0.118711 0.582985 +v -0.094674 -0.210217 0.492261 +v -0.110989 -0.243711 0.368331 +v -0.127305 -0.210217 0.244400 +v -0.139249 -0.118711 0.153677 +v -0.303987 0.006289 0.152368 +v -0.295318 0.131289 0.184721 +v -0.271634 0.222796 0.273109 +v -0.239282 0.256289 0.393850 +v -0.206930 0.222796 0.514590 +v -0.183246 0.131289 0.602979 +v -0.174577 0.006289 0.635331 +v -0.183246 -0.118711 0.602979 +v -0.206930 -0.210217 0.514590 +v -0.239282 -0.243711 0.393850 +v -0.271634 -0.210217 0.273109 +v -0.295318 -0.118711 0.184721 +v -0.458818 0.006289 0.204926 +v -0.446000 0.131289 0.235870 +v -0.410982 0.222796 0.320411 +v -0.363147 0.256289 0.435896 +v -0.315311 0.222796 0.551381 +v -0.280293 0.131289 0.635922 +v -0.267476 0.006289 0.666866 +v -0.280293 -0.118711 0.635922 +v -0.315311 -0.210217 0.551381 +v -0.363147 -0.243711 0.435896 +v -0.410982 -0.210217 0.320411 +v -0.446000 -0.118711 0.235870 +v -0.605463 0.006289 0.277244 +v -0.588716 0.131289 0.306250 +v -0.542963 0.222796 0.385497 +v -0.480463 0.256289 0.493750 +v -0.417963 0.222796 0.602003 +v -0.372210 0.131289 0.681250 +v -0.355463 0.006289 0.710257 +v -0.372210 -0.118711 0.681250 +v -0.417963 -0.210217 0.602003 +v -0.480463 -0.243711 0.493750 +v -0.542963 -0.210217 0.385497 +v -0.588716 -0.118711 0.306250 +v -0.741415 0.006289 0.368084 +v -0.721025 0.131289 0.394656 +v -0.665320 0.222796 0.467253 +v -0.589225 0.256289 0.566422 +v -0.513129 0.222796 0.665592 +v -0.457424 0.131289 0.738188 +v -0.437034 0.006289 0.764761 +v -0.457424 -0.118711 0.738188 +v -0.513129 -0.210217 0.665592 +v -0.589225 -0.243711 0.566422 +v -0.665320 -0.210217 0.467253 +v -0.721025 -0.118711 0.394656 +v -0.864347 0.006289 0.475893 +v -0.840663 0.131289 0.499576 +v -0.775958 0.222796 0.564281 +v -0.687570 0.256289 0.652669 +v -0.599182 0.222796 0.741057 +v -0.534477 0.131289 0.805762 +v -0.510793 0.006289 0.829446 +v -0.534477 -0.118711 0.805762 +v -0.599182 -0.210217 0.741057 +v -0.687570 -0.243711 0.652669 +v -0.775958 -0.210217 0.564281 +v -0.840663 -0.118711 0.499576 +v -0.972155 0.006289 0.598824 +v -0.945583 0.131289 0.619214 +v -0.872986 0.222796 0.674919 +v -0.773816 0.256289 0.751014 +v -0.674647 0.222796 0.827109 +v -0.602050 0.131289 0.882815 +v -0.575478 0.006289 0.903205 +v -0.602050 -0.118711 0.882815 +v -0.674647 -0.210217 0.827109 +v -0.773816 -0.243711 0.751014 +v -0.872986 -0.210217 0.674919 +v -0.945583 -0.118711 0.619214 +v -1.062995 0.006289 0.734775 +v -1.033988 0.131289 0.751522 +v -0.954742 0.222796 0.797275 +v -0.846488 0.256289 0.859775 +v -0.738235 0.222796 0.922275 +v -0.658988 0.131289 0.968029 +v -0.629982 0.006289 0.984775 +v -0.658988 -0.118711 0.968029 +v -0.738235 -0.210217 0.922275 +v -0.846488 -0.243711 0.859775 +v -0.954742 -0.210217 0.797275 +v -1.033988 -0.118711 0.751522 +v -1.135312 0.006289 0.881421 +v -1.104368 0.131289 0.894239 +v -1.019827 0.222796 0.929257 +v -0.904343 0.256289 0.977092 +v -0.788858 0.222796 1.024928 +v -0.704317 0.131289 1.059946 +v -0.673373 0.006289 1.072763 +v -0.704317 -0.118711 1.059946 +v -0.788858 -0.210217 1.024928 +v -0.904343 -0.243711 0.977092 +v -1.019827 -0.210217 0.929257 +v -1.104368 -0.118711 0.894239 +v -1.187871 0.006289 1.036252 +v -1.155518 0.131289 1.044921 +v -1.067130 0.222796 1.068604 +v -0.946389 0.256289 1.100957 +v -0.825648 0.222796 1.133309 +v -0.737260 0.131289 1.156993 +v -0.704908 0.006289 1.165662 +v -0.737260 -0.118711 1.156993 +v -0.825648 -0.210217 1.133309 +v -0.946389 -0.243711 1.100957 +v -1.067130 -0.210217 1.068604 +v -1.155518 -0.118711 1.044921 +v -1.219769 0.006289 1.196618 +v -1.186562 0.131289 1.200990 +v -1.095839 0.222796 1.212934 +v -0.971908 0.256289 1.229249 +v -0.847977 0.222796 1.245565 +v -0.757254 0.131289 1.257509 +v -0.724047 0.006289 1.261881 +v -0.757254 -0.118711 1.257509 +v -0.847977 -0.210217 1.245565 +v -0.971908 -0.243711 1.229249 +v -1.095839 -0.210217 1.212934 +v -1.186562 -0.118711 1.200990 +v -1.230463 0.006289 1.359776 +v -1.196970 0.131289 1.359776 +v -1.105463 0.222796 1.359776 +v -0.980463 0.256289 1.359776 +v -0.855463 0.222796 1.359776 +v -0.763957 0.131289 1.359776 +v -0.730463 0.006289 1.359776 +v -0.763957 -0.118711 1.359776 +v -0.855463 -0.210217 1.359776 +v -0.980463 -0.243711 1.359776 +v -1.105463 -0.210217 1.359776 +v -1.196970 -0.118711 1.359776 +v -1.219769 0.006289 1.522934 +v -1.186562 0.131289 1.518562 +v -1.095839 0.222796 1.506618 +v -0.971908 0.256289 1.490302 +v -0.847977 0.222796 1.473986 +v -0.757254 0.131289 1.462042 +v -0.724047 0.006289 1.457670 +v -0.757254 -0.118711 1.462042 +v -0.847977 -0.210217 1.473986 +v -0.971908 -0.243711 1.490302 +v -1.095839 -0.210217 1.506618 +v -1.186562 -0.118711 1.518562 +v -1.187871 0.006289 1.683299 +v -1.155518 0.131289 1.674631 +v -1.067130 0.222796 1.650947 +v -0.946389 0.256289 1.618595 +v -0.825648 0.222796 1.586242 +v -0.737260 0.131289 1.562559 +v -0.704908 0.006289 1.553890 +v -0.737260 -0.118711 1.562559 +v -0.825648 -0.210217 1.586242 +v -0.946389 -0.243711 1.618595 +v -1.067130 -0.210217 1.650947 +v -1.155518 -0.118711 1.674631 +v -1.135313 0.006289 1.838130 +v -1.104369 0.131289 1.825312 +v -1.019828 0.222796 1.790294 +v -0.904343 0.256289 1.742459 +v -0.788858 0.222796 1.694623 +v -0.704317 0.131289 1.659605 +v -0.673373 0.006289 1.646788 +v -0.704317 -0.118711 1.659605 +v -0.788858 -0.210217 1.694623 +v -0.904343 -0.243711 1.742459 +v -1.019828 -0.210217 1.790294 +v -1.104369 -0.118711 1.825312 +v -1.062995 0.006289 1.984776 +v -1.033989 0.131289 1.968029 +v -0.954742 0.222796 1.922276 +v -0.846489 0.256289 1.859776 +v -0.738235 0.222796 1.797276 +v -0.658989 0.131289 1.751522 +v -0.629982 0.006289 1.734776 +v -0.658989 -0.118711 1.751522 +v -0.738235 -0.210217 1.797276 +v -0.846489 -0.243711 1.859776 +v -0.954742 -0.210217 1.922276 +v -1.033989 -0.118711 1.968029 +v -0.972155 0.006289 2.120728 +v -0.945583 0.131289 2.100338 +v -0.872986 0.222796 2.044632 +v -0.773816 0.256289 1.968537 +v -0.674647 0.222796 1.892442 +v -0.602050 0.131289 1.836736 +v -0.575478 0.006289 1.816347 +v -0.602050 -0.118711 1.836736 +v -0.674647 -0.210217 1.892442 +v -0.773816 -0.243711 1.968537 +v -0.872986 -0.210217 2.044632 +v -0.945583 -0.118711 2.100338 +v -0.864347 0.006289 2.243659 +v -0.840663 0.131289 2.219975 +v -0.775958 0.222796 2.155271 +v -0.687570 0.256289 2.066882 +v -0.599182 0.222796 1.978494 +v -0.534477 0.131289 1.913789 +v -0.510793 0.006289 1.890106 +v -0.534477 -0.118711 1.913789 +v -0.599182 -0.210217 1.978494 +v -0.687570 -0.243711 2.066882 +v -0.775958 -0.210217 2.155271 +v -0.840663 -0.118711 2.219975 +v -0.741416 0.006289 2.351467 +v -0.721026 0.131289 2.324895 +v -0.665320 0.222796 2.252298 +v -0.589225 0.256289 2.153129 +v -0.513130 0.222796 2.053960 +v -0.457424 0.131289 1.981363 +v -0.437034 0.006289 1.954791 +v -0.457424 -0.118711 1.981363 +v -0.513130 -0.210217 2.053960 +v -0.589225 -0.243711 2.153129 +v -0.665320 -0.210217 2.252298 +v -0.721026 -0.118711 2.324895 +v -0.605463 0.006289 2.442308 +v -0.588716 0.131289 2.413301 +v -0.542963 0.222796 2.334054 +v -0.480463 0.256289 2.225801 +v -0.417963 0.222796 2.117548 +v -0.372210 0.131289 2.038301 +v -0.355463 0.006289 2.009295 +v -0.372210 -0.118711 2.038301 +v -0.417963 -0.210217 2.117548 +v -0.480463 -0.243711 2.225801 +v -0.542963 -0.210217 2.334054 +v -0.588716 -0.118711 2.413301 +v -0.458818 0.006289 2.514625 +v -0.446000 0.131289 2.483681 +v -0.410982 0.222796 2.399140 +v -0.363147 0.256289 2.283655 +v -0.315311 0.222796 2.168170 +v -0.280293 0.131289 2.083629 +v -0.267476 0.006289 2.052685 +v -0.280293 -0.118711 2.083629 +v -0.315311 -0.210217 2.168170 +v -0.363147 -0.243711 2.283655 +v -0.410982 -0.210217 2.399140 +v -0.446000 -0.118711 2.483681 +v -0.303987 0.006289 2.567183 +v -0.295318 0.131289 2.534830 +v -0.271635 0.222796 2.446442 +v -0.239282 0.256289 2.325701 +v -0.206930 0.222796 2.204961 +v -0.183246 0.131289 2.116572 +v -0.174578 0.006289 2.084220 +v -0.183246 -0.118711 2.116572 +v -0.206930 -0.210217 2.204961 +v -0.239282 -0.243711 2.325701 +v -0.271635 -0.210217 2.446442 +v -0.295318 -0.118711 2.534830 +v -0.143622 0.006289 2.599082 +v -0.139250 0.131289 2.565874 +v -0.127306 0.222796 2.475151 +v -0.110990 0.256289 2.351220 +v -0.094674 0.222796 2.227290 +v -0.082730 0.131289 2.136566 +v -0.078358 0.006289 2.103359 +v -0.082730 -0.118711 2.136566 +v -0.094674 -0.210217 2.227290 +v -0.110990 -0.243711 2.351220 +v -0.127306 -0.210217 2.475151 +v -0.139250 -0.118711 2.565874 +v 0.019537 0.006289 2.609776 +v 0.019537 0.131289 2.576282 +v 0.019537 0.222796 2.484776 +v 0.019537 0.256289 2.359776 +v 0.019537 0.222796 2.234776 +v 0.019537 0.131289 2.143269 +v 0.019537 0.006289 2.109776 +v 0.019537 -0.118711 2.143269 +v 0.019537 -0.210217 2.234776 +v 0.019537 -0.243711 2.359776 +v 0.019537 -0.210217 2.484776 +v 0.019537 -0.118711 2.576282 +v 0.182694 0.006289 2.599082 +v 0.178323 0.131289 2.565875 +v 0.166379 0.222796 2.475151 +v 0.150063 0.256289 2.351221 +v 0.133747 0.222796 2.227290 +v 0.121803 0.131289 2.136566 +v 0.117431 0.006289 2.103359 +v 0.121803 -0.118711 2.136566 +v 0.133747 -0.210217 2.227290 +v 0.150063 -0.243711 2.351221 +v 0.166379 -0.210217 2.475151 +v 0.178323 -0.118711 2.565875 +v 0.343060 0.006289 2.567183 +v 0.334391 0.131289 2.534831 +v 0.310708 0.222796 2.446442 +v 0.278356 0.256289 2.325702 +v 0.246003 0.222796 2.204961 +v 0.222320 0.131289 2.116573 +v 0.213651 0.006289 2.084220 +v 0.222320 -0.118711 2.116573 +v 0.246003 -0.210217 2.204961 +v 0.278356 -0.243711 2.325702 +v 0.310708 -0.210217 2.446442 +v 0.334391 -0.118711 2.534831 +v 0.497891 0.006289 2.514625 +v 0.485074 0.131289 2.483681 +v 0.450056 0.222796 2.399140 +v 0.402221 0.256289 2.283655 +v 0.354385 0.222796 2.168170 +v 0.319367 0.131289 2.083629 +v 0.306550 0.006289 2.052685 +v 0.319367 -0.118711 2.083629 +v 0.354385 -0.210217 2.168170 +v 0.402221 -0.243711 2.283655 +v 0.450056 -0.210217 2.399140 +v 0.485074 -0.118711 2.483681 +v 0.644537 0.006289 2.442307 +v 0.627790 0.131289 2.413301 +v 0.582037 0.222796 2.334054 +v 0.519537 0.256289 2.225801 +v 0.457037 0.222796 2.117548 +v 0.411284 0.131289 2.038301 +v 0.394537 0.006289 2.009295 +v 0.411284 -0.118711 2.038301 +v 0.457037 -0.210217 2.117548 +v 0.519537 -0.243711 2.225801 +v 0.582037 -0.210217 2.334054 +v 0.627790 -0.118711 2.413301 +v 0.780488 0.006289 2.351468 +v 0.760099 0.131289 2.324895 +v 0.704393 0.222796 2.252298 +v 0.628298 0.256289 2.153129 +v 0.552203 0.222796 2.053960 +v 0.496497 0.131289 1.981363 +v 0.476108 0.006289 1.954791 +v 0.496497 -0.118711 1.981363 +v 0.552203 -0.210217 2.053960 +v 0.628298 -0.243711 2.153129 +v 0.704393 -0.210217 2.252298 +v 0.760099 -0.118711 2.324895 +v 0.903420 0.006289 2.243660 +v 0.879736 0.131289 2.219976 +v 0.815032 0.222796 2.155271 +v 0.726643 0.256289 2.066883 +v 0.638255 0.222796 1.978495 +v 0.573550 0.131289 1.913790 +v 0.549867 0.006289 1.890106 +v 0.573550 -0.118711 1.913790 +v 0.638255 -0.210217 1.978495 +v 0.726643 -0.243711 2.066883 +v 0.815032 -0.210217 2.155271 +v 0.879736 -0.118711 2.219976 +v 1.011229 0.006289 2.120727 +v 0.984656 0.131289 2.100338 +v 0.912059 0.222796 2.044632 +v 0.812890 0.256289 1.968537 +v 0.713721 0.222796 1.892442 +v 0.641124 0.131289 1.836736 +v 0.614552 0.006289 1.816347 +v 0.641124 -0.118711 1.836736 +v 0.713721 -0.210217 1.892442 +v 0.812890 -0.243711 1.968537 +v 0.912059 -0.210217 2.044632 +v 0.984656 -0.118711 2.100338 +v 1.102069 0.006289 1.984776 +v 1.073062 0.131289 1.968029 +v 0.993815 0.222796 1.922276 +v 0.885562 0.256289 1.859776 +v 0.777309 0.222796 1.797276 +v 0.698062 0.131289 1.751523 +v 0.669056 0.006289 1.734776 +v 0.698062 -0.118711 1.751523 +v 0.777309 -0.210217 1.797276 +v 0.885562 -0.243711 1.859776 +v 0.993815 -0.210217 1.922276 +v 1.073062 -0.118711 1.968029 +v 1.174386 0.006289 1.838130 +v 1.143442 0.131289 1.825313 +v 1.058901 0.222796 1.790295 +v 0.943416 0.256289 1.742460 +v 0.827931 0.222796 1.694624 +v 0.743391 0.131289 1.659606 +v 0.712446 0.006289 1.646789 +v 0.743391 -0.118711 1.659606 +v 0.827931 -0.210217 1.694624 +v 0.943416 -0.243711 1.742460 +v 1.058901 -0.210217 1.790295 +v 1.143442 -0.118711 1.825313 +v 1.226944 0.006289 1.683299 +v 1.194592 0.131289 1.674630 +v 1.106204 0.222796 1.650947 +v 0.985463 0.256289 1.618594 +v 0.864722 0.222796 1.586242 +v 0.776334 0.131289 1.562559 +v 0.743981 0.006289 1.553890 +v 0.776334 -0.118711 1.562559 +v 0.864722 -0.210217 1.586242 +v 0.985463 -0.243711 1.618594 +v 1.106204 -0.210217 1.650947 +v 1.194592 -0.118711 1.674630 +v 1.258843 0.006289 1.522933 +v 1.225636 0.131289 1.518562 +v 1.134912 0.222796 1.506618 +v 1.010982 0.256289 1.490302 +v 0.887051 0.222796 1.473986 +v 0.796328 0.131289 1.462042 +v 0.763121 0.006289 1.457670 +v 0.796328 -0.118711 1.462042 +v 0.887051 -0.210217 1.473986 +v 1.010982 -0.243711 1.490302 +v 1.134912 -0.210217 1.506618 +v 1.225636 -0.118711 1.518562 +vn 0.9640 0.2583 -0.0632 +vn 0.7064 0.7063 -0.0463 +vn 0.2588 0.9658 -0.0170 +vn -0.2588 0.9658 0.0170 +vn -0.7064 0.7063 0.0463 +vn -0.9640 0.2583 0.0632 +vn -0.9640 -0.2583 0.0632 +vn -0.7063 -0.7063 0.0463 +vn -0.2588 -0.9658 0.0170 +vn 0.2588 -0.9658 -0.0170 +vn 0.7063 -0.7064 -0.0463 +vn 0.9640 -0.2583 -0.0632 +vn 0.9475 0.2583 -0.1885 +vn 0.6943 0.7063 -0.1381 +vn 0.2543 0.9658 -0.0506 +vn -0.2543 0.9658 0.0506 +vn -0.6943 0.7063 0.1381 +vn -0.9475 0.2583 0.1885 +vn -0.9475 -0.2583 0.1885 +vn -0.6943 -0.7063 0.1381 +vn -0.2544 -0.9658 0.0506 +vn 0.2544 -0.9658 -0.0506 +vn 0.6943 -0.7063 -0.1381 +vn 0.9475 -0.2583 -0.1885 +vn 0.9148 0.2583 -0.3105 +vn 0.6703 0.7063 -0.2275 +vn 0.2456 0.9658 -0.0834 +vn -0.2456 0.9658 0.0834 +vn -0.6703 0.7063 0.2275 +vn -0.9148 0.2583 0.3105 +vn -0.9148 -0.2583 0.3105 +vn -0.6703 -0.7064 0.2275 +vn -0.2456 -0.9658 0.0834 +vn 0.2456 -0.9658 -0.0834 +vn 0.6703 -0.7063 -0.2275 +vn 0.9148 -0.2583 -0.3105 +vn 0.8664 0.2583 -0.4273 +vn 0.6349 0.7063 -0.3131 +vn 0.2326 0.9658 -0.1147 +vn -0.2326 0.9658 0.1147 +vn -0.6349 0.7063 0.3131 +vn -0.8664 0.2583 0.4273 +vn -0.8664 -0.2583 0.4273 +vn -0.6349 -0.7064 0.3131 +vn -0.2326 -0.9658 0.1147 +vn 0.2326 -0.9658 -0.1147 +vn 0.6349 -0.7064 -0.3131 +vn 0.8664 -0.2583 -0.4273 +vn 0.8033 0.2583 -0.5367 +vn 0.5886 0.7063 -0.3933 +vn 0.2156 0.9658 -0.1441 +vn -0.2156 0.9658 0.1441 +vn -0.5886 0.7063 0.3933 +vn -0.8033 0.2583 0.5367 +vn -0.8033 -0.2583 0.5367 +vn -0.5886 -0.7064 0.3933 +vn -0.2156 -0.9658 0.1441 +vn 0.2156 -0.9658 -0.1441 +vn 0.5886 -0.7063 -0.3933 +vn 0.8033 -0.2583 -0.5367 +vn 0.7263 0.2583 -0.6370 +vn 0.5322 0.7063 -0.4667 +vn 0.1950 0.9658 -0.1710 +vn -0.1950 0.9658 0.1710 +vn -0.5322 0.7063 0.4667 +vn -0.7263 0.2583 0.6370 +vn -0.7263 -0.2583 0.6370 +vn -0.5322 -0.7064 0.4667 +vn -0.1950 -0.9658 0.1710 +vn 0.1950 -0.9658 -0.1710 +vn 0.5322 -0.7063 -0.4667 +vn 0.7263 -0.2583 -0.6370 +vn 0.6370 0.2583 -0.7263 +vn 0.4667 0.7063 -0.5322 +vn 0.1710 0.9658 -0.1950 +vn -0.1710 0.9658 0.1950 +vn -0.4667 0.7063 0.5322 +vn -0.6370 0.2583 0.7263 +vn -0.6370 -0.2583 0.7263 +vn -0.4667 -0.7063 0.5322 +vn -0.1710 -0.9658 0.1950 +vn 0.1710 -0.9658 -0.1950 +vn 0.4667 -0.7064 -0.5322 +vn 0.6370 -0.2583 -0.7263 +vn 0.5367 0.2583 -0.8033 +vn 0.3933 0.7063 -0.5886 +vn 0.1441 0.9658 -0.2156 +vn -0.1441 0.9658 0.2156 +vn -0.3933 0.7063 0.5886 +vn -0.5367 0.2583 0.8033 +vn -0.5367 -0.2583 0.8033 +vn -0.3933 -0.7063 0.5886 +vn -0.1441 -0.9658 0.2156 +vn 0.1441 -0.9658 -0.2156 +vn 0.3933 -0.7063 -0.5886 +vn 0.5367 -0.2583 -0.8033 +vn 0.4273 0.2583 -0.8664 +vn 0.3131 0.7063 -0.6349 +vn 0.1147 0.9658 -0.2326 +vn -0.1147 0.9658 0.2326 +vn -0.3131 0.7063 0.6349 +vn -0.4273 0.2583 0.8664 +vn -0.4273 -0.2583 0.8664 +vn -0.3131 -0.7064 0.6349 +vn -0.1147 -0.9658 0.2326 +vn 0.1147 -0.9658 -0.2326 +vn 0.3131 -0.7063 -0.6349 +vn 0.4273 -0.2583 -0.8664 +vn 0.3105 0.2583 -0.9148 +vn 0.2275 0.7063 -0.6703 +vn 0.0834 0.9658 -0.2456 +vn -0.0834 0.9658 0.2456 +vn -0.2275 0.7063 0.6703 +vn -0.3105 0.2583 0.9148 +vn -0.3105 -0.2583 0.9148 +vn -0.2275 -0.7064 0.6703 +vn -0.0834 -0.9658 0.2456 +vn 0.0834 -0.9658 -0.2456 +vn 0.2275 -0.7063 -0.6703 +vn 0.3105 -0.2583 -0.9148 +vn 0.1885 0.2583 -0.9475 +vn 0.1381 0.7063 -0.6943 +vn 0.0506 0.9658 -0.2543 +vn -0.0506 0.9658 0.2543 +vn -0.1381 0.7063 0.6943 +vn -0.1885 0.2583 0.9475 +vn -0.1885 -0.2583 0.9475 +vn -0.1381 -0.7064 0.6943 +vn -0.0506 -0.9658 0.2544 +vn 0.0506 -0.9658 -0.2544 +vn 0.1381 -0.7063 -0.6943 +vn 0.1885 -0.2583 -0.9475 +vn 0.0632 0.2583 -0.9640 +vn 0.0463 0.7063 -0.7064 +vn 0.0170 0.9658 -0.2588 +vn -0.0170 0.9658 0.2588 +vn -0.0463 0.7063 0.7064 +vn -0.0632 0.2583 0.9640 +vn -0.0632 -0.2583 0.9640 +vn -0.0463 -0.7064 0.7063 +vn -0.0170 -0.9658 0.2588 +vn 0.0170 -0.9658 -0.2588 +vn 0.0463 -0.7064 -0.7063 +vn 0.0632 -0.2583 -0.9640 +vn -0.0632 0.2583 -0.9640 +vn -0.0463 0.7063 -0.7064 +vn -0.0170 0.9658 -0.2588 +vn 0.0170 0.9658 0.2588 +vn 0.0463 0.7063 0.7064 +vn 0.0632 0.2583 0.9640 +vn 0.0632 -0.2583 0.9640 +vn 0.0463 -0.7064 0.7063 +vn 0.0170 -0.9658 0.2588 +vn -0.0170 -0.9658 -0.2588 +vn -0.0463 -0.7064 -0.7063 +vn -0.0632 -0.2583 -0.9640 +vn -0.1885 0.2583 -0.9475 +vn -0.1381 0.7063 -0.6943 +vn -0.0506 0.9658 -0.2543 +vn 0.0506 0.9658 0.2544 +vn 0.1381 0.7063 0.6943 +vn 0.1885 0.2583 0.9475 +vn 0.1885 -0.2583 0.9475 +vn 0.1381 -0.7064 0.6943 +vn 0.0506 -0.9658 0.2544 +vn -0.0506 -0.9658 -0.2544 +vn -0.1381 -0.7063 -0.6943 +vn -0.1885 -0.2583 -0.9475 +vn -0.3105 0.2583 -0.9148 +vn -0.2275 0.7063 -0.6703 +vn -0.0834 0.9658 -0.2456 +vn 0.0834 0.9658 0.2456 +vn 0.2275 0.7063 0.6703 +vn 0.3105 0.2583 0.9148 +vn 0.3105 -0.2583 0.9148 +vn 0.2275 -0.7064 0.6703 +vn 0.0834 -0.9658 0.2456 +vn -0.0834 -0.9658 -0.2456 +vn -0.2275 -0.7063 -0.6703 +vn -0.3105 -0.2583 -0.9148 +vn -0.4273 0.2583 -0.8664 +vn -0.3131 0.7063 -0.6349 +vn -0.1147 0.9658 -0.2326 +vn 0.1147 0.9658 0.2326 +vn 0.3131 0.7063 0.6349 +vn 0.4273 0.2583 0.8664 +vn 0.4273 -0.2583 0.8664 +vn 0.3131 -0.7064 0.6349 +vn 0.1147 -0.9658 0.2326 +vn -0.1147 -0.9658 -0.2326 +vn -0.3131 -0.7064 -0.6349 +vn -0.4273 -0.2583 -0.8664 +vn -0.5367 0.2583 -0.8033 +vn -0.3933 0.7063 -0.5886 +vn -0.1441 0.9658 -0.2156 +vn 0.1441 0.9658 0.2156 +vn 0.3933 0.7063 0.5886 +vn 0.5367 0.2583 0.8033 +vn 0.5367 -0.2583 0.8033 +vn 0.3933 -0.7063 0.5886 +vn 0.1441 -0.9658 0.2156 +vn -0.1441 -0.9658 -0.2156 +vn -0.3933 -0.7063 -0.5886 +vn -0.5367 -0.2583 -0.8033 +vn -0.6370 0.2583 -0.7263 +vn -0.4667 0.7063 -0.5322 +vn -0.1710 0.9658 -0.1950 +vn 0.1710 0.9658 0.1950 +vn 0.4667 0.7063 0.5322 +vn 0.6370 0.2583 0.7263 +vn 0.6370 -0.2583 0.7263 +vn 0.4667 -0.7063 0.5322 +vn 0.1710 -0.9658 0.1950 +vn -0.1710 -0.9658 -0.1950 +vn -0.4667 -0.7063 -0.5322 +vn -0.6370 -0.2583 -0.7263 +vn -0.7263 0.2583 -0.6370 +vn -0.5322 0.7063 -0.4667 +vn -0.1950 0.9658 -0.1710 +vn 0.1950 0.9658 0.1710 +vn 0.5322 0.7063 0.4667 +vn 0.7263 0.2583 0.6370 +vn 0.7263 -0.2583 0.6370 +vn 0.5322 -0.7064 0.4667 +vn 0.1950 -0.9658 0.1710 +vn -0.1950 -0.9658 -0.1710 +vn -0.5322 -0.7063 -0.4667 +vn -0.7263 -0.2583 -0.6370 +vn -0.8033 0.2583 -0.5367 +vn -0.5886 0.7063 -0.3933 +vn -0.2156 0.9658 -0.1441 +vn 0.2156 0.9658 0.1441 +vn 0.5886 0.7063 0.3933 +vn 0.8033 0.2583 0.5367 +vn 0.8033 -0.2583 0.5367 +vn 0.5886 -0.7064 0.3933 +vn 0.2156 -0.9658 0.1441 +vn -0.2156 -0.9658 -0.1441 +vn -0.5886 -0.7063 -0.3933 +vn -0.8033 -0.2583 -0.5367 +vn -0.8664 0.2583 -0.4273 +vn -0.6349 0.7063 -0.3131 +vn -0.2326 0.9658 -0.1147 +vn 0.2326 0.9658 0.1147 +vn 0.6349 0.7063 0.3131 +vn 0.8664 0.2583 0.4273 +vn 0.8664 -0.2583 0.4273 +vn 0.6349 -0.7064 0.3131 +vn 0.2326 -0.9658 0.1147 +vn -0.2326 -0.9658 -0.1147 +vn -0.6349 -0.7063 -0.3131 +vn -0.8664 -0.2583 -0.4273 +vn -0.9148 0.2583 -0.3105 +vn -0.6703 0.7063 -0.2275 +vn -0.2456 0.9658 -0.0834 +vn 0.2456 0.9658 0.0834 +vn 0.6703 0.7063 0.2275 +vn 0.9148 0.2583 0.3105 +vn 0.9148 -0.2583 0.3105 +vn 0.6703 -0.7064 0.2275 +vn 0.2456 -0.9658 0.0834 +vn -0.2456 -0.9658 -0.0834 +vn -0.6703 -0.7063 -0.2275 +vn -0.9148 -0.2583 -0.3105 +vn -0.9475 0.2583 -0.1885 +vn -0.6943 0.7063 -0.1381 +vn -0.2543 0.9658 -0.0506 +vn 0.2543 0.9658 0.0506 +vn 0.6943 0.7063 0.1381 +vn 0.9475 0.2583 0.1885 +vn 0.9475 -0.2583 0.1885 +vn 0.6943 -0.7063 0.1381 +vn 0.2544 -0.9658 0.0506 +vn -0.2544 -0.9658 -0.0506 +vn -0.6943 -0.7063 -0.1381 +vn -0.9475 -0.2583 -0.1885 +vn -0.9640 0.2583 -0.0632 +vn -0.7064 0.7063 -0.0463 +vn -0.2588 0.9658 -0.0170 +vn 0.2588 0.9658 0.0170 +vn 0.7064 0.7063 0.0463 +vn 0.9640 0.2583 0.0632 +vn 0.9640 -0.2583 0.0632 +vn 0.7063 -0.7063 0.0463 +vn 0.2588 -0.9658 0.0170 +vn -0.2588 -0.9658 -0.0170 +vn -0.7063 -0.7064 -0.0463 +vn -0.9640 -0.2583 -0.0632 +vn 0.7063 -0.7063 -0.0463 +vn -0.7063 -0.7064 0.0463 +vn 0.6349 -0.7063 -0.3131 +vn 0.5886 -0.7064 -0.3933 +vn 0.5322 -0.7064 -0.4667 +vn -0.4667 -0.7064 0.5322 +vn 0.3933 -0.7064 -0.5886 +vn -0.3933 -0.7064 0.5886 +vn 0.3131 -0.7064 -0.6349 +vn 0.2275 -0.7064 -0.6703 +vn -0.2275 -0.7063 0.6703 +vn 0.0506 0.9658 -0.2544 +vn 0.1381 -0.7064 -0.6943 +vn -0.1381 -0.7063 0.6943 +vn 0.0463 0.7063 -0.7063 +vn -0.0463 -0.7063 0.7063 +vn -0.0463 0.7063 -0.7063 +vn -0.3933 -0.7064 -0.5886 +vn 0.3933 -0.7064 0.5886 +vn -0.4667 -0.7064 -0.5322 +vn 0.4667 -0.7064 0.5322 +vn -0.5322 -0.7064 -0.4667 +vn -0.5886 -0.7064 -0.3933 +vn 0.6703 -0.7063 0.2275 +vn 0.2544 0.9658 0.0506 +vn 0.6943 -0.7064 0.1381 +vn -0.7063 -0.7063 -0.0463 +vn 0.7063 -0.7064 0.0463 +usemtl None +s 1 +f 1//1 2//1 3//1 4//1 +f 4//2 3//2 5//2 6//2 +f 6//3 5//3 7//3 8//3 +f 8//4 7//4 9//4 10//4 +f 10//5 9//5 11//5 12//5 +f 12//6 11//6 13//6 14//6 +f 14//7 13//7 15//7 16//7 +f 16//8 15//8 17//8 18//8 +f 18//9 17//9 19//9 20//9 +f 20//10 19//10 21//10 22//10 +f 22//11 21//11 23//11 24//11 +f 1//12 24//12 23//12 2//12 +f 2//13 25//13 26//13 3//13 +f 3//14 26//14 27//14 5//14 +f 5//15 27//15 28//15 7//15 +f 7//16 28//16 29//16 9//16 +f 9//17 29//17 30//17 11//17 +f 11//18 30//18 31//18 13//18 +f 13//19 31//19 32//19 15//19 +f 15//20 32//20 33//20 17//20 +f 17//21 33//21 34//21 19//21 +f 19//22 34//22 35//22 21//22 +f 21//23 35//23 36//23 23//23 +f 23//24 36//24 25//24 2//24 +f 25//25 37//25 38//25 26//25 +f 26//26 38//26 39//26 27//26 +f 27//27 39//27 40//27 28//27 +f 28//28 40//28 41//28 29//28 +f 29//29 41//29 42//29 30//29 +f 30//30 42//30 43//30 31//30 +f 31//31 43//31 44//31 32//31 +f 32//32 44//32 45//32 33//32 +f 33//33 45//33 46//33 34//33 +f 34//34 46//34 47//34 35//34 +f 35//35 47//35 48//35 36//35 +f 36//36 48//36 37//36 25//36 +f 37//37 49//37 50//37 38//37 +f 38//38 50//38 51//38 39//38 +f 39//39 51//39 52//39 40//39 +f 40//40 52//40 53//40 41//40 +f 41//41 53//41 54//41 42//41 +f 42//42 54//42 55//42 43//42 +f 43//43 55//43 56//43 44//43 +f 44//44 56//44 57//44 45//44 +f 45//45 57//45 58//45 46//45 +f 46//46 58//46 59//46 47//46 +f 47//47 59//47 60//47 48//47 +f 48//48 60//48 49//48 37//48 +f 49//49 61//49 62//49 50//49 +f 50//50 62//50 63//50 51//50 +f 51//51 63//51 64//51 52//51 +f 52//52 64//52 65//52 53//52 +f 53//53 65//53 66//53 54//53 +f 54//54 66//54 67//54 55//54 +f 55//55 67//55 68//55 56//55 +f 56//56 68//56 69//56 57//56 +f 57//57 69//57 70//57 58//57 +f 58//58 70//58 71//58 59//58 +f 59//59 71//59 72//59 60//59 +f 60//60 72//60 61//60 49//60 +f 61//61 73//61 74//61 62//61 +f 62//62 74//62 75//62 63//62 +f 63//63 75//63 76//63 64//63 +f 64//64 76//64 77//64 65//64 +f 65//65 77//65 78//65 66//65 +f 66//66 78//66 79//66 67//66 +f 67//67 79//67 80//67 68//67 +f 68//68 80//68 81//68 69//68 +f 69//69 81//69 82//69 70//69 +f 70//70 82//70 83//70 71//70 +f 71//71 83//71 84//71 72//71 +f 72//72 84//72 73//72 61//72 +f 73//73 85//73 86//73 74//73 +f 74//74 86//74 87//74 75//74 +f 75//75 87//75 88//75 76//75 +f 76//76 88//76 89//76 77//76 +f 77//77 89//77 90//77 78//77 +f 78//78 90//78 91//78 79//78 +f 79//79 91//79 92//79 80//79 +f 80//80 92//80 93//80 81//80 +f 81//81 93//81 94//81 82//81 +f 82//82 94//82 95//82 83//82 +f 83//83 95//83 96//83 84//83 +f 84//84 96//84 85//84 73//84 +f 85//85 97//85 98//85 86//85 +f 86//86 98//86 99//86 87//86 +f 87//87 99//87 100//87 88//87 +f 88//88 100//88 101//88 89//88 +f 89//89 101//89 102//89 90//89 +f 90//90 102//90 103//90 91//90 +f 91//91 103//91 104//91 92//91 +f 92//92 104//92 105//92 93//92 +f 93//93 105//93 106//93 94//93 +f 94//94 106//94 107//94 95//94 +f 95//95 107//95 108//95 96//95 +f 96//96 108//96 97//96 85//96 +f 97//97 109//97 110//97 98//97 +f 98//98 110//98 111//98 99//98 +f 99//99 111//99 112//99 100//99 +f 100//100 112//100 113//100 101//100 +f 101//101 113//101 114//101 102//101 +f 102//102 114//102 115//102 103//102 +f 103//103 115//103 116//103 104//103 +f 104//104 116//104 117//104 105//104 +f 105//105 117//105 118//105 106//105 +f 106//106 118//106 119//106 107//106 +f 107//107 119//107 120//107 108//107 +f 108//108 120//108 109//108 97//108 +f 109//109 121//109 122//109 110//109 +f 110//110 122//110 123//110 111//110 +f 111//111 123//111 124//111 112//111 +f 112//112 124//112 125//112 113//112 +f 113//113 125//113 126//113 114//113 +f 114//114 126//114 127//114 115//114 +f 115//115 127//115 128//115 116//115 +f 116//116 128//116 129//116 117//116 +f 117//117 129//117 130//117 118//117 +f 118//118 130//118 131//118 119//118 +f 119//119 131//119 132//119 120//119 +f 120//120 132//120 121//120 109//120 +f 121//121 133//121 134//121 122//121 +f 122//122 134//122 135//122 123//122 +f 123//123 135//123 136//123 124//123 +f 124//124 136//124 137//124 125//124 +f 125//125 137//125 138//125 126//125 +f 126//126 138//126 139//126 127//126 +f 127//127 139//127 140//127 128//127 +f 128//128 140//128 141//128 129//128 +f 129//129 141//129 142//129 130//129 +f 130//130 142//130 143//130 131//130 +f 131//131 143//131 144//131 132//131 +f 132//132 144//132 133//132 121//132 +f 133//133 145//133 146//133 134//133 +f 134//134 146//134 147//134 135//134 +f 135//135 147//135 148//135 136//135 +f 136//136 148//136 149//136 137//136 +f 137//137 149//137 150//137 138//137 +f 138//138 150//138 151//138 139//138 +f 139//139 151//139 152//139 140//139 +f 140//140 152//140 153//140 141//140 +f 141//141 153//141 154//141 142//141 +f 142//142 154//142 155//142 143//142 +f 143//143 155//143 156//143 144//143 +f 144//144 156//144 145//144 133//144 +f 145//145 157//145 158//145 146//145 +f 146//146 158//146 159//146 147//146 +f 147//147 159//147 160//147 148//147 +f 148//148 160//148 161//148 149//148 +f 149//149 161//149 162//149 150//149 +f 150//150 162//150 163//150 151//150 +f 151//151 163//151 164//151 152//151 +f 152//152 164//152 165//152 153//152 +f 153//153 165//153 166//153 154//153 +f 154//154 166//154 167//154 155//154 +f 155//155 167//155 168//155 156//155 +f 156//156 168//156 157//156 145//156 +f 157//157 169//157 170//157 158//157 +f 158//158 170//158 171//158 159//158 +f 159//159 171//159 172//159 160//159 +f 160//160 172//160 173//160 161//160 +f 161//161 173//161 174//161 162//161 +f 162//162 174//162 175//162 163//162 +f 163//163 175//163 176//163 164//163 +f 164//164 176//164 177//164 165//164 +f 165//165 177//165 178//165 166//165 +f 166//166 178//166 179//166 167//166 +f 167//167 179//167 180//167 168//167 +f 168//168 180//168 169//168 157//168 +f 169//169 181//169 182//169 170//169 +f 170//170 182//170 183//170 171//170 +f 171//171 183//171 184//171 172//171 +f 172//172 184//172 185//172 173//172 +f 173//173 185//173 186//173 174//173 +f 174//174 186//174 187//174 175//174 +f 175//175 187//175 188//175 176//175 +f 176//176 188//176 189//176 177//176 +f 177//177 189//177 190//177 178//177 +f 178//178 190//178 191//178 179//178 +f 179//179 191//179 192//179 180//179 +f 180//180 192//180 181//180 169//180 +f 181//181 193//181 194//181 182//181 +f 182//182 194//182 195//182 183//182 +f 183//183 195//183 196//183 184//183 +f 184//184 196//184 197//184 185//184 +f 185//185 197//185 198//185 186//185 +f 186//186 198//186 199//186 187//186 +f 187//187 199//187 200//187 188//187 +f 188//188 200//188 201//188 189//188 +f 189//189 201//189 202//189 190//189 +f 190//190 202//190 203//190 191//190 +f 191//191 203//191 204//191 192//191 +f 192//192 204//192 193//192 181//192 +f 193//193 205//193 206//193 194//193 +f 194//194 206//194 207//194 195//194 +f 195//195 207//195 208//195 196//195 +f 196//196 208//196 209//196 197//196 +f 197//197 209//197 210//197 198//197 +f 198//198 210//198 211//198 199//198 +f 199//199 211//199 212//199 200//199 +f 200//200 212//200 213//200 201//200 +f 201//201 213//201 214//201 202//201 +f 202//202 214//202 215//202 203//202 +f 203//203 215//203 216//203 204//203 +f 204//204 216//204 205//204 193//204 +f 205//205 217//205 218//205 206//205 +f 206//206 218//206 219//206 207//206 +f 207//207 219//207 220//207 208//207 +f 208//208 220//208 221//208 209//208 +f 209//209 221//209 222//209 210//209 +f 210//210 222//210 223//210 211//210 +f 211//211 223//211 224//211 212//211 +f 212//212 224//212 225//212 213//212 +f 213//213 225//213 226//213 214//213 +f 214//214 226//214 227//214 215//214 +f 215//215 227//215 228//215 216//215 +f 216//216 228//216 217//216 205//216 +f 217//217 229//217 230//217 218//217 +f 218//218 230//218 231//218 219//218 +f 219//219 231//219 232//219 220//219 +f 220//220 232//220 233//220 221//220 +f 221//221 233//221 234//221 222//221 +f 222//222 234//222 235//222 223//222 +f 223//223 235//223 236//223 224//223 +f 224//224 236//224 237//224 225//224 +f 225//225 237//225 238//225 226//225 +f 226//226 238//226 239//226 227//226 +f 227//227 239//227 240//227 228//227 +f 228//228 240//228 229//228 217//228 +f 229//229 241//229 242//229 230//229 +f 230//230 242//230 243//230 231//230 +f 231//231 243//231 244//231 232//231 +f 232//232 244//232 245//232 233//232 +f 233//233 245//233 246//233 234//233 +f 234//234 246//234 247//234 235//234 +f 235//235 247//235 248//235 236//235 +f 236//236 248//236 249//236 237//236 +f 237//237 249//237 250//237 238//237 +f 238//238 250//238 251//238 239//238 +f 239//239 251//239 252//239 240//239 +f 240//240 252//240 241//240 229//240 +f 241//241 253//241 254//241 242//241 +f 242//242 254//242 255//242 243//242 +f 243//243 255//243 256//243 244//243 +f 244//244 256//244 257//244 245//244 +f 245//245 257//245 258//245 246//245 +f 246//246 258//246 259//246 247//246 +f 247//247 259//247 260//247 248//247 +f 248//248 260//248 261//248 249//248 +f 249//249 261//249 262//249 250//249 +f 250//250 262//250 263//250 251//250 +f 251//251 263//251 264//251 252//251 +f 252//252 264//252 253//252 241//252 +f 253//253 265//253 266//253 254//253 +f 254//254 266//254 267//254 255//254 +f 255//255 267//255 268//255 256//255 +f 256//256 268//256 269//256 257//256 +f 257//257 269//257 270//257 258//257 +f 258//258 270//258 271//258 259//258 +f 259//259 271//259 272//259 260//259 +f 260//260 272//260 273//260 261//260 +f 261//261 273//261 274//261 262//261 +f 262//262 274//262 275//262 263//262 +f 263//263 275//263 276//263 264//263 +f 264//264 276//264 265//264 253//264 +f 265//265 277//265 278//265 266//265 +f 266//266 278//266 279//266 267//266 +f 267//267 279//267 280//267 268//267 +f 268//268 280//268 281//268 269//268 +f 269//269 281//269 282//269 270//269 +f 270//270 282//270 283//270 271//270 +f 271//271 283//271 284//271 272//271 +f 272//272 284//272 285//272 273//272 +f 273//273 285//273 286//273 274//273 +f 274//274 286//274 287//274 275//274 +f 275//275 287//275 288//275 276//275 +f 276//276 288//276 277//276 265//276 +f 277//277 289//277 290//277 278//277 +f 278//278 290//278 291//278 279//278 +f 279//279 291//279 292//279 280//279 +f 280//280 292//280 293//280 281//280 +f 281//281 293//281 294//281 282//281 +f 282//282 294//282 295//282 283//282 +f 283//283 295//283 296//283 284//283 +f 284//284 296//284 297//284 285//284 +f 285//285 297//285 298//285 286//285 +f 286//286 298//286 299//286 287//286 +f 287//287 299//287 300//287 288//287 +f 288//288 300//288 289//288 277//288 +f 289//6 301//6 302//6 290//6 +f 290//5 302//5 303//5 291//5 +f 291//4 303//4 304//4 292//4 +f 292//3 304//3 305//3 293//3 +f 293//2 305//2 306//2 294//2 +f 294//1 306//1 307//1 295//1 +f 295//12 307//12 308//12 296//12 +f 296//289 308//289 309//289 297//289 +f 297//10 309//10 310//10 298//10 +f 298//9 310//9 311//9 299//9 +f 299//290 311//290 312//290 300//290 +f 300//7 312//7 301//7 289//7 +f 301//18 313//18 314//18 302//18 +f 302//17 314//17 315//17 303//17 +f 303//16 315//16 316//16 304//16 +f 304//15 316//15 317//15 305//15 +f 305//14 317//14 318//14 306//14 +f 306//13 318//13 319//13 307//13 +f 307//24 319//24 320//24 308//24 +f 308//23 320//23 321//23 309//23 +f 309//22 321//22 322//22 310//22 +f 310//21 322//21 323//21 311//21 +f 311//20 323//20 324//20 312//20 +f 312//19 324//19 313//19 301//19 +f 313//30 325//30 326//30 314//30 +f 314//29 326//29 327//29 315//29 +f 315//28 327//28 328//28 316//28 +f 316//27 328//27 329//27 317//27 +f 317//26 329//26 330//26 318//26 +f 318//25 330//25 331//25 319//25 +f 319//36 331//36 332//36 320//36 +f 320//35 332//35 333//35 321//35 +f 321//34 333//34 334//34 322//34 +f 322//33 334//33 335//33 323//33 +f 323//32 335//32 336//32 324//32 +f 324//31 336//31 325//31 313//31 +f 325//42 337//42 338//42 326//42 +f 326//41 338//41 339//41 327//41 +f 327//40 339//40 340//40 328//40 +f 328//39 340//39 341//39 329//39 +f 329//38 341//38 342//38 330//38 +f 330//37 342//37 343//37 331//37 +f 331//48 343//48 344//48 332//48 +f 332//291 344//291 345//291 333//291 +f 333//46 345//46 346//46 334//46 +f 334//45 346//45 347//45 335//45 +f 335//44 347//44 348//44 336//44 +f 336//43 348//43 337//43 325//43 +f 337//54 349//54 350//54 338//54 +f 338//53 350//53 351//53 339//53 +f 339//52 351//52 352//52 340//52 +f 340//51 352//51 353//51 341//51 +f 341//50 353//50 354//50 342//50 +f 342//49 354//49 355//49 343//49 +f 343//60 355//60 356//60 344//60 +f 344//292 356//292 357//292 345//292 +f 345//58 357//58 358//58 346//58 +f 346//57 358//57 359//57 347//57 +f 347//56 359//56 360//56 348//56 +f 348//55 360//55 349//55 337//55 +f 349//66 361//66 362//66 350//66 +f 350//65 362//65 363//65 351//65 +f 351//64 363//64 364//64 352//64 +f 352//63 364//63 365//63 353//63 +f 353//62 365//62 366//62 354//62 +f 354//61 366//61 367//61 355//61 +f 355//72 367//72 368//72 356//72 +f 356//293 368//293 369//293 357//293 +f 357//70 369//70 370//70 358//70 +f 358//69 370//69 371//69 359//69 +f 359//68 371//68 372//68 360//68 +f 360//67 372//67 361//67 349//67 +f 361//78 373//78 374//78 362//78 +f 362//77 374//77 375//77 363//77 +f 363//76 375//76 376//76 364//76 +f 364//75 376//75 377//75 365//75 +f 365//74 377//74 378//74 366//74 +f 366//73 378//73 379//73 367//73 +f 367//84 379//84 380//84 368//84 +f 368//83 380//83 381//83 369//83 +f 369//82 381//82 382//82 370//82 +f 370//81 382//81 383//81 371//81 +f 371//294 383//294 384//294 372//294 +f 372//79 384//79 373//79 361//79 +f 373//90 385//90 386//90 374//90 +f 374//89 386//89 387//89 375//89 +f 375//88 387//88 388//88 376//88 +f 376//87 388//87 389//87 377//87 +f 377//86 389//86 390//86 378//86 +f 378//85 390//85 391//85 379//85 +f 379//96 391//96 392//96 380//96 +f 380//295 392//295 393//295 381//295 +f 381//94 393//94 394//94 382//94 +f 382//93 394//93 395//93 383//93 +f 383//296 395//296 396//296 384//296 +f 384//91 396//91 385//91 373//91 +f 385//102 397//102 398//102 386//102 +f 386//101 398//101 399//101 387//101 +f 387//100 399//100 400//100 388//100 +f 388//99 400//99 401//99 389//99 +f 389//98 401//98 402//98 390//98 +f 390//97 402//97 403//97 391//97 +f 391//108 403//108 404//108 392//108 +f 392//297 404//297 405//297 393//297 +f 393//106 405//106 406//106 394//106 +f 394//105 406//105 407//105 395//105 +f 395//104 407//104 408//104 396//104 +f 396//103 408//103 397//103 385//103 +f 397//114 409//114 410//114 398//114 +f 398//113 410//113 411//113 399//113 +f 399//112 411//112 412//112 400//112 +f 400//111 412//111 413//111 401//111 +f 401//110 413//110 414//110 402//110 +f 402//109 414//109 415//109 403//109 +f 403//120 415//120 416//120 404//120 +f 404//298 416//298 417//298 405//298 +f 405//118 417//118 418//118 406//118 +f 406//117 418//117 419//117 407//117 +f 407//299 419//299 420//299 408//299 +f 408//115 420//115 409//115 397//115 +f 409//126 421//126 422//126 410//126 +f 410//125 422//125 423//125 411//125 +f 411//124 423//124 424//124 412//124 +f 412//300 424//300 425//300 413//300 +f 413//122 425//122 426//122 414//122 +f 414//121 426//121 427//121 415//121 +f 415//132 427//132 428//132 416//132 +f 416//301 428//301 429//301 417//301 +f 417//130 429//130 430//130 418//130 +f 418//129 430//129 431//129 419//129 +f 419//302 431//302 432//302 420//302 +f 420//127 432//127 421//127 409//127 +f 421//138 433//138 434//138 422//138 +f 422//137 434//137 435//137 423//137 +f 423//136 435//136 436//136 424//136 +f 424//135 436//135 437//135 425//135 +f 425//303 437//303 438//303 426//303 +f 426//133 438//133 439//133 427//133 +f 427//144 439//144 440//144 428//144 +f 428//143 440//143 441//143 429//143 +f 429//142 441//142 442//142 430//142 +f 430//141 442//141 443//141 431//141 +f 431//304 443//304 444//304 432//304 +f 432//139 444//139 433//139 421//139 +f 433//150 445//150 446//150 434//150 +f 434//149 446//149 447//149 435//149 +f 435//148 447//148 448//148 436//148 +f 436//147 448//147 449//147 437//147 +f 437//305 449//305 450//305 438//305 +f 438//145 450//145 451//145 439//145 +f 439//156 451//156 452//156 440//156 +f 440//155 452//155 453//155 441//155 +f 441//154 453//154 454//154 442//154 +f 442//153 454//153 455//153 443//153 +f 443//152 455//152 456//152 444//152 +f 444//151 456//151 445//151 433//151 +f 445//162 457//162 458//162 446//162 +f 446//161 458//161 459//161 447//161 +f 447//160 459//160 460//160 448//160 +f 448//159 460//159 461//159 449//159 +f 449//158 461//158 462//158 450//158 +f 450//157 462//157 463//157 451//157 +f 451//168 463//168 464//168 452//168 +f 452//167 464//167 465//167 453//167 +f 453//166 465//166 466//166 454//166 +f 454//165 466//165 467//165 455//165 +f 455//164 467//164 468//164 456//164 +f 456//163 468//163 457//163 445//163 +f 457//174 469//174 470//174 458//174 +f 458//173 470//173 471//173 459//173 +f 459//172 471//172 472//172 460//172 +f 460//171 472//171 473//171 461//171 +f 461//170 473//170 474//170 462//170 +f 462//169 474//169 475//169 463//169 +f 463//180 475//180 476//180 464//180 +f 464//179 476//179 477//179 465//179 +f 465//178 477//178 478//178 466//178 +f 466//177 478//177 479//177 467//177 +f 467//176 479//176 480//176 468//176 +f 468//175 480//175 469//175 457//175 +f 469//186 481//186 482//186 470//186 +f 470//185 482//185 483//185 471//185 +f 471//184 483//184 484//184 472//184 +f 472//183 484//183 485//183 473//183 +f 473//182 485//182 486//182 474//182 +f 474//181 486//181 487//181 475//181 +f 475//192 487//192 488//192 476//192 +f 476//191 488//191 489//191 477//191 +f 477//190 489//190 490//190 478//190 +f 478//189 490//189 491//189 479//189 +f 479//188 491//188 492//188 480//188 +f 480//187 492//187 481//187 469//187 +f 481//198 493//198 494//198 482//198 +f 482//197 494//197 495//197 483//197 +f 483//196 495//196 496//196 484//196 +f 484//195 496//195 497//195 485//195 +f 485//194 497//194 498//194 486//194 +f 486//193 498//193 499//193 487//193 +f 487//204 499//204 500//204 488//204 +f 488//306 500//306 501//306 489//306 +f 489//202 501//202 502//202 490//202 +f 490//201 502//201 503//201 491//201 +f 491//307 503//307 504//307 492//307 +f 492//199 504//199 493//199 481//199 +f 493//210 505//210 506//210 494//210 +f 494//209 506//209 507//209 495//209 +f 495//208 507//208 508//208 496//208 +f 496//207 508//207 509//207 497//207 +f 497//206 509//206 510//206 498//206 +f 498//205 510//205 511//205 499//205 +f 499//216 511//216 512//216 500//216 +f 500//308 512//308 513//308 501//308 +f 501//214 513//214 514//214 502//214 +f 502//213 514//213 515//213 503//213 +f 503//309 515//309 516//309 504//309 +f 504//211 516//211 505//211 493//211 +f 505//222 517//222 518//222 506//222 +f 506//221 518//221 519//221 507//221 +f 507//220 519//220 520//220 508//220 +f 508//219 520//219 521//219 509//219 +f 509//218 521//218 522//218 510//218 +f 510//217 522//217 523//217 511//217 +f 511//228 523//228 524//228 512//228 +f 512//310 524//310 525//310 513//310 +f 513//226 525//226 526//226 514//226 +f 514//225 526//225 527//225 515//225 +f 515//224 527//224 528//224 516//224 +f 516//223 528//223 517//223 505//223 +f 517//234 529//234 530//234 518//234 +f 518//233 530//233 531//233 519//233 +f 519//232 531//232 532//232 520//232 +f 520//231 532//231 533//231 521//231 +f 521//230 533//230 534//230 522//230 +f 522//229 534//229 535//229 523//229 +f 523//240 535//240 536//240 524//240 +f 524//311 536//311 537//311 525//311 +f 525//238 537//238 538//238 526//238 +f 526//237 538//237 539//237 527//237 +f 527//236 539//236 540//236 528//236 +f 528//235 540//235 529//235 517//235 +f 529//246 541//246 542//246 530//246 +f 530//245 542//245 543//245 531//245 +f 531//244 543//244 544//244 532//244 +f 532//243 544//243 545//243 533//243 +f 533//242 545//242 546//242 534//242 +f 534//241 546//241 547//241 535//241 +f 535//252 547//252 548//252 536//252 +f 536//251 548//251 549//251 537//251 +f 537//250 549//250 550//250 538//250 +f 538//249 550//249 551//249 539//249 +f 539//248 551//248 552//248 540//248 +f 540//247 552//247 541//247 529//247 +f 541//258 553//258 554//258 542//258 +f 542//257 554//257 555//257 543//257 +f 543//256 555//256 556//256 544//256 +f 544//255 556//255 557//255 545//255 +f 545//254 557//254 558//254 546//254 +f 546//253 558//253 559//253 547//253 +f 547//264 559//264 560//264 548//264 +f 548//263 560//263 561//263 549//263 +f 549//262 561//262 562//262 550//262 +f 550//261 562//261 563//261 551//261 +f 551//312 563//312 564//312 552//312 +f 552//259 564//259 553//259 541//259 +f 553//270 565//270 566//270 554//270 +f 554//269 566//269 567//269 555//269 +f 555//313 567//313 568//313 556//313 +f 556//267 568//267 569//267 557//267 +f 557//266 569//266 570//266 558//266 +f 558//265 570//265 571//265 559//265 +f 559//276 571//276 572//276 560//276 +f 560//275 572//275 573//275 561//275 +f 561//274 573//274 574//274 562//274 +f 562//273 574//273 575//273 563//273 +f 563//314 575//314 576//314 564//314 +f 564//271 576//271 565//271 553//271 +f 565//282 1//282 4//282 566//282 +f 566//281 4//281 6//281 567//281 +f 567//280 6//280 8//280 568//280 +f 568//279 8//279 10//279 569//279 +f 569//278 10//278 12//278 570//278 +f 570//277 12//277 14//277 571//277 +f 571//288 14//288 16//288 572//288 +f 572//315 16//315 18//315 573//315 +f 573//286 18//286 20//286 574//286 +f 574//285 20//285 22//285 575//285 +f 575//316 22//316 24//316 576//316 +f 576//283 24//283 1//283 565//283 diff --git a/data/torus/torus_with_plane.mtl b/data/torus/torus_with_plane.mtl new file mode 100644 index 000000000..70d3ba1da --- /dev/null +++ b/data/torus/torus_with_plane.mtl @@ -0,0 +1,10 @@ +# Blender MTL File: 'None' +# Material Count: 1 + +newmtl None +Ns 0 +Ka 0.000000 0.000000 0.000000 +Kd 0.8 0.8 0.8 +Ks 0.8 0.8 0.8 +d 1 +illum 2 diff --git a/data/torus/torus_with_plane.obj b/data/torus/torus_with_plane.obj new file mode 100644 index 000000000..b036d9fdd --- /dev/null +++ b/data/torus/torus_with_plane.obj @@ -0,0 +1,9384 @@ +# Blender v2.77 (sub 0) OBJ File: '' +# www.blender.org +mtllib torus_with_plane.mtl +o Plane +v -2.312398 -6.126618 0.566384 +v 6.032325 -2.575601 0.280679 +v -5.874205 2.203907 0.074895 +v 2.470518 5.754926 -0.210810 +v -5.804365 2.040563 0.084532 +v -5.734526 1.877220 0.094169 +v -5.664686 1.713876 0.103806 +v -5.594847 1.550532 0.113443 +v -5.525007 1.387189 0.123080 +v -5.455168 1.223845 0.132717 +v -5.385328 1.060502 0.142354 +v -5.315490 0.897157 0.151991 +v -5.245650 0.733814 0.161628 +v -5.175811 0.570470 0.171265 +v -5.105971 0.407127 0.180902 +v -5.036132 0.243783 0.190539 +v -4.966292 0.080439 0.200176 +v -4.896453 -0.082904 0.209813 +v -4.826613 -0.246248 0.219450 +v -4.756775 -0.409592 0.229087 +v -4.686935 -0.572935 0.238724 +v -4.617096 -0.736279 0.248362 +v -4.547256 -0.899623 0.257998 +v -4.477417 -1.062966 0.267636 +v -4.407578 -1.226310 0.277273 +v -4.337738 -1.389654 0.286910 +v -4.267900 -1.552997 0.296547 +v -4.198060 -1.716341 0.306184 +v -4.128221 -1.879685 0.315821 +v -4.058381 -2.043028 0.325458 +v -3.988542 -2.206372 0.335095 +v -3.918703 -2.369716 0.344732 +v -3.848863 -2.533059 0.354369 +v -3.779024 -2.696403 0.364006 +v -3.709185 -2.859747 0.373643 +v -3.639345 -3.023091 0.383280 +v -3.569506 -3.186434 0.392917 +v -3.499667 -3.349777 0.402554 +v -3.429827 -3.513121 0.412191 +v -3.359988 -3.676465 0.421829 +v -3.290149 -3.839808 0.431465 +v -3.220309 -4.003152 0.441103 +v -3.150470 -4.166496 0.450740 +v -3.080631 -4.329839 0.460377 +v -3.010791 -4.493183 0.470014 +v -2.940952 -4.656527 0.479651 +v -2.871112 -4.819870 0.489288 +v -2.801273 -4.983214 0.498925 +v -2.731434 -5.146557 0.508562 +v -2.661594 -5.309901 0.518199 +v -2.591755 -5.473244 0.527836 +v -2.521916 -5.636589 0.537473 +v -2.452076 -5.799932 0.547110 +v -2.382237 -5.963276 0.556747 +v -2.148776 -6.056991 0.560782 +v -1.985154 -5.987363 0.555180 +v -1.821532 -5.917735 0.549578 +v -1.657910 -5.848107 0.543976 +v -1.494288 -5.778480 0.538374 +v -1.330665 -5.708852 0.532772 +v -1.167043 -5.639224 0.527170 +v -1.003422 -5.569596 0.521568 +v -0.839799 -5.499969 0.515965 +v -0.676177 -5.430341 0.510363 +v -0.512555 -5.360713 0.504761 +v -0.348933 -5.291085 0.499159 +v -0.185311 -5.221457 0.493557 +v -0.021689 -5.151829 0.487955 +v 0.141933 -5.082201 0.482353 +v 0.305555 -5.012573 0.476751 +v 0.469177 -4.942945 0.471149 +v 0.632799 -4.873318 0.465547 +v 0.796421 -4.803690 0.459945 +v 0.960043 -4.734062 0.454343 +v 1.123665 -4.664434 0.448741 +v 1.287287 -4.594807 0.443139 +v 1.450909 -4.525179 0.437537 +v 1.614531 -4.455551 0.431935 +v 1.778153 -4.385922 0.426333 +v 1.941775 -4.316295 0.420731 +v 2.105397 -4.246667 0.415129 +v 2.269019 -4.177039 0.409527 +v 2.432641 -4.107412 0.403924 +v 2.596263 -4.037785 0.398322 +v 2.759885 -3.968157 0.392720 +v 2.923507 -3.898529 0.387118 +v 3.087129 -3.828902 0.381516 +v 3.250751 -3.759273 0.375914 +v 3.414372 -3.689645 0.370312 +v 3.577994 -3.620018 0.364710 +v 3.741616 -3.550390 0.359108 +v 3.905239 -3.480762 0.353506 +v 4.068861 -3.411134 0.347904 +v 4.232483 -3.341506 0.342302 +v 4.396105 -3.271878 0.336700 +v 4.559727 -3.202251 0.331098 +v 4.723349 -3.132623 0.325496 +v 4.886971 -3.062995 0.319894 +v 5.050592 -2.993367 0.314292 +v 5.214214 -2.923740 0.308690 +v 5.377837 -2.854112 0.303087 +v 5.541458 -2.784484 0.297485 +v 5.705081 -2.714856 0.291883 +v 5.868702 -2.645229 0.286281 +v 5.962485 -2.412257 0.271042 +v 5.892646 -2.248913 0.261405 +v 5.822806 -2.085569 0.251768 +v 5.752967 -1.922226 0.242131 +v 5.683127 -1.758882 0.232494 +v 5.613288 -1.595538 0.222857 +v 5.543449 -1.432195 0.213220 +v 5.473610 -1.268851 0.203583 +v 5.403770 -1.105507 0.193946 +v 5.333931 -0.942164 0.184309 +v 5.264091 -0.778820 0.174672 +v 5.194252 -0.615476 0.165035 +v 5.124413 -0.452132 0.155398 +v 5.054573 -0.288789 0.145761 +v 4.984735 -0.125445 0.136124 +v 4.914895 0.037898 0.126487 +v 4.845056 0.201242 0.116849 +v 4.775216 0.364586 0.107213 +v 4.705377 0.527929 0.097575 +v 4.635537 0.691273 0.087938 +v 4.565698 0.854617 0.078301 +v 4.495859 1.017960 0.068664 +v 4.426020 1.181304 0.059027 +v 4.356180 1.344648 0.049390 +v 4.286341 1.507991 0.039753 +v 4.216501 1.671335 0.030116 +v 4.146662 1.834678 0.020479 +v 4.076822 1.998022 0.010842 +v 4.006983 2.161365 0.001205 +v 3.937144 2.324709 -0.008432 +v 3.867305 2.488053 -0.018069 +v 3.797465 2.651397 -0.027706 +v 3.727626 2.814740 -0.037343 +v 3.657787 2.978083 -0.046980 +v 3.587947 3.141428 -0.056617 +v 3.518108 3.304771 -0.066254 +v 3.448268 3.468114 -0.075891 +v 3.378429 3.631458 -0.085528 +v 3.308590 3.794802 -0.095165 +v 3.238750 3.958145 -0.104803 +v 3.168911 4.121490 -0.114440 +v 3.099072 4.284833 -0.124077 +v 3.029233 4.448177 -0.133714 +v 2.959393 4.611520 -0.143351 +v 2.889554 4.774864 -0.152988 +v 2.819715 4.938208 -0.162625 +v 2.749875 5.101552 -0.172262 +v 2.680036 5.264896 -0.181899 +v 2.610196 5.428238 -0.191536 +v 2.540357 5.591582 -0.201173 +v 2.306895 5.685298 -0.205208 +v 2.143273 5.615670 -0.199606 +v 1.979651 5.546042 -0.194004 +v 1.816030 5.476415 -0.188402 +v 1.652407 5.406787 -0.182800 +v 1.488786 5.337159 -0.177198 +v 1.325163 5.267531 -0.171596 +v 1.161541 5.197904 -0.165994 +v 0.997919 5.128276 -0.160392 +v 0.834297 5.058648 -0.154789 +v 0.670675 4.989020 -0.149187 +v 0.507053 4.919393 -0.143585 +v 0.343431 4.849765 -0.137983 +v 0.179809 4.780137 -0.132381 +v 0.016187 4.710509 -0.126779 +v -0.147435 4.640882 -0.121177 +v -0.311057 4.571253 -0.115575 +v -0.474679 4.501625 -0.109973 +v -0.638301 4.431997 -0.104371 +v -0.801923 4.362370 -0.098769 +v -0.965545 4.292742 -0.093167 +v -1.129167 4.223114 -0.087565 +v -1.292789 4.153486 -0.081963 +v -1.456411 4.083858 -0.076361 +v -1.620033 4.014231 -0.070759 +v -1.783655 3.944603 -0.065157 +v -1.947277 3.874975 -0.059554 +v -2.110899 3.805346 -0.053952 +v -2.274521 3.735718 -0.048350 +v -2.438143 3.666091 -0.042748 +v -2.601765 3.596463 -0.037146 +v -2.765387 3.526835 -0.031544 +v -2.929009 3.457207 -0.025942 +v -3.092631 3.387580 -0.020340 +v -3.256253 3.317952 -0.014738 +v -3.419875 3.248324 -0.009136 +v -3.583497 3.178696 -0.003534 +v -3.747118 3.109069 0.002068 +v -3.910740 3.039441 0.007670 +v -4.074363 2.969813 0.013272 +v -4.237985 2.900185 0.018874 +v -4.401607 2.830558 0.024476 +v -4.565228 2.760930 0.030078 +v -4.728850 2.691302 0.035680 +v -4.892472 2.621674 0.041282 +v -5.056094 2.552047 0.046885 +v -5.219716 2.482419 0.052487 +v -5.383339 2.412791 0.058089 +v -5.546961 2.343162 0.063691 +v -5.710583 2.273535 0.069293 +v -5.640743 2.110191 0.078930 +v -5.407282 2.016475 0.082965 +v -5.173820 1.922760 0.087000 +v -4.940358 1.829044 0.091035 +v -4.706897 1.735328 0.095070 +v -4.473435 1.641612 0.099105 +v -4.239974 1.547897 0.103140 +v -4.006513 1.454180 0.107175 +v -3.773051 1.360465 0.111210 +v -3.539590 1.266749 0.115245 +v -3.306129 1.173033 0.119280 +v -3.072667 1.079317 0.123315 +v -2.839206 0.985601 0.127350 +v -2.605745 0.891885 0.131385 +v -2.372283 0.798169 0.135420 +v -2.138822 0.704454 0.139455 +v -1.905361 0.610738 0.143490 +v -1.671899 0.517022 0.147525 +v -1.438438 0.423306 0.151560 +v -1.204977 0.329590 0.155595 +v -0.971515 0.235874 0.159630 +v -0.738054 0.142159 0.163665 +v -0.504593 0.048443 0.167700 +v -0.271131 -0.045273 0.171735 +v -0.037670 -0.138989 0.175770 +v 0.195791 -0.232705 0.179805 +v 0.429253 -0.326421 0.183840 +v 0.662714 -0.420136 0.187875 +v 0.896175 -0.513852 0.191910 +v 1.129637 -0.607568 0.195945 +v 1.363098 -0.701284 0.199980 +v 1.596559 -0.795000 0.204015 +v 1.830021 -0.888716 0.208049 +v 2.063482 -0.982431 0.212084 +v 2.296943 -1.076147 0.216119 +v 2.530405 -1.169863 0.220154 +v 2.763866 -1.263579 0.224189 +v 2.997327 -1.357295 0.228224 +v 3.230788 -1.451011 0.232259 +v 3.464250 -1.544726 0.236294 +v 3.697711 -1.638442 0.240329 +v 3.931173 -1.732158 0.244364 +v 4.164635 -1.825874 0.248399 +v 4.398096 -1.919590 0.252434 +v 4.631557 -2.013306 0.256469 +v 4.865018 -2.107021 0.260504 +v 5.098479 -2.200737 0.264539 +v 5.331941 -2.294453 0.268574 +v 5.565402 -2.388169 0.272609 +v 5.798862 -2.481885 0.276644 +v -5.477121 2.179819 0.073328 +v -5.243659 2.086103 0.077363 +v -5.313498 2.249447 0.067726 +v -5.010198 1.992388 0.081398 +v -5.080037 2.155731 0.071761 +v -5.149877 2.319074 0.062124 +v -4.776736 1.898672 0.085433 +v -4.846576 2.062015 0.075796 +v -4.916415 2.225359 0.066159 +v -4.986255 2.388702 0.056522 +v -4.543275 1.804956 0.089468 +v -4.613114 1.968299 0.079831 +v -4.682954 2.131643 0.070194 +v -4.752793 2.294986 0.060557 +v -4.822633 2.458330 0.050920 +v -4.309813 1.711240 0.093503 +v -4.379653 1.874583 0.083866 +v -4.449492 2.037927 0.074229 +v -4.519332 2.201271 0.064592 +v -4.589171 2.364614 0.054955 +v -4.659011 2.527958 0.045318 +v -4.076352 1.617524 0.097538 +v -4.146192 1.780868 0.087901 +v -4.216031 1.944211 0.078264 +v -4.285871 2.107555 0.068627 +v -4.355710 2.270899 0.058990 +v -4.425550 2.434242 0.049352 +v -4.495389 2.597585 0.039715 +v -3.842891 1.523808 0.101573 +v -3.912730 1.687152 0.091936 +v -3.982570 1.850495 0.082299 +v -4.052409 2.013839 0.072662 +v -4.122249 2.177183 0.063025 +v -4.192088 2.340526 0.053387 +v -4.261928 2.503870 0.043751 +v -4.331767 2.667213 0.034113 +v -3.609429 1.430092 0.105608 +v -3.679269 1.593436 0.095971 +v -3.749108 1.756780 0.086334 +v -3.818948 1.920124 0.076697 +v -3.888787 2.083467 0.067060 +v -3.958627 2.246810 0.057422 +v -4.028465 2.410154 0.047786 +v -4.098306 2.573498 0.038148 +v -4.168145 2.736841 0.028511 +v -3.375968 1.336377 0.109643 +v -3.445807 1.499720 0.100006 +v -3.515647 1.663064 0.090369 +v -3.585486 1.826408 0.080732 +v -3.655326 1.989751 0.071095 +v -3.725165 2.153095 0.061457 +v -3.795005 2.316438 0.051821 +v -3.864844 2.479782 0.042183 +v -3.934684 2.643125 0.032546 +v -4.004523 2.806469 0.022909 +v -3.142507 1.242661 0.113678 +v -3.212346 1.406005 0.104041 +v -3.282185 1.569348 0.094404 +v -3.352025 1.732692 0.084767 +v -3.421864 1.896036 0.075130 +v -3.491704 2.059379 0.065492 +v -3.561543 2.222723 0.055856 +v -3.631382 2.386066 0.046218 +v -3.701222 2.549410 0.036581 +v -3.771061 2.712753 0.026944 +v -3.840901 2.876097 0.017307 +v -2.909045 1.148945 0.117713 +v -2.978885 1.312288 0.108076 +v -3.048724 1.475632 0.098439 +v -3.118563 1.638976 0.088801 +v -3.188403 1.802320 0.079165 +v -3.258242 1.965663 0.069527 +v -3.328082 2.129007 0.059891 +v -3.397921 2.292350 0.050253 +v -3.467761 2.455694 0.040616 +v -3.537600 2.619037 0.030979 +v -3.607439 2.782381 0.021342 +v -3.677279 2.945725 0.011705 +v -2.675584 1.055229 0.121748 +v -2.745423 1.218573 0.112111 +v -2.815263 1.381916 0.102473 +v -2.885102 1.545260 0.092836 +v -2.954941 1.708604 0.083200 +v -3.024781 1.871947 0.073562 +v -3.094620 2.035291 0.063925 +v -3.164460 2.198635 0.054288 +v -3.234299 2.361978 0.044651 +v -3.304139 2.525321 0.035014 +v -3.373978 2.688665 0.025377 +v -3.443818 2.852009 0.015740 +v -3.513657 3.015353 0.006103 +v -2.442123 0.961513 0.125782 +v -2.511962 1.124857 0.116146 +v -2.581802 1.288201 0.106508 +v -2.651641 1.451544 0.096871 +v -2.721480 1.614888 0.087234 +v -2.791320 1.778232 0.077597 +v -2.861159 1.941575 0.067960 +v -2.930999 2.104919 0.058323 +v -3.000838 2.268262 0.048686 +v -3.070677 2.431606 0.039049 +v -3.140517 2.594950 0.029412 +v -3.210356 2.758293 0.019775 +v -3.280196 2.921637 0.010138 +v -3.350035 3.084981 0.000501 +v -2.208661 0.867797 0.129817 +v -2.278501 1.031141 0.120181 +v -2.348340 1.194485 0.110543 +v -2.418180 1.357828 0.100906 +v -2.488019 1.521172 0.091269 +v -2.557858 1.684516 0.081632 +v -2.627698 1.847859 0.071995 +v -2.697537 2.011203 0.062358 +v -2.767377 2.174546 0.052721 +v -2.837216 2.337890 0.043084 +v -2.907056 2.501234 0.033447 +v -2.976895 2.664578 0.023810 +v -3.046734 2.827921 0.014173 +v -3.116574 2.991265 0.004536 +v -3.186413 3.154608 -0.005101 +v -1.975200 0.774081 0.133852 +v -2.045039 0.937425 0.124216 +v -2.114879 1.100769 0.114578 +v -2.184718 1.264112 0.104941 +v -2.254558 1.427456 0.095304 +v -2.324397 1.590800 0.085667 +v -2.394237 1.754144 0.076030 +v -2.464076 1.917487 0.066393 +v -2.533916 2.080831 0.056756 +v -2.603755 2.244174 0.047119 +v -2.673594 2.407518 0.037482 +v -2.743433 2.570862 0.027845 +v -2.813273 2.734205 0.018208 +v -2.883112 2.897548 0.008571 +v -2.952952 3.060892 -0.001066 +v -3.022791 3.224236 -0.010703 +v -1.741739 0.680366 0.137887 +v -1.811578 0.843709 0.128251 +v -1.881418 1.007053 0.118613 +v -1.951257 1.170397 0.108976 +v -2.021096 1.333740 0.099339 +v -2.090936 1.497084 0.089702 +v -2.160775 1.660428 0.080065 +v -2.230615 1.823772 0.070428 +v -2.300454 1.987115 0.060791 +v -2.370294 2.150458 0.051154 +v -2.440133 2.313802 0.041517 +v -2.509972 2.477146 0.031880 +v -2.579812 2.640490 0.022243 +v -2.649651 2.803833 0.012606 +v -2.719491 2.967177 0.002969 +v -2.789330 3.130521 -0.006668 +v -2.859169 3.293864 -0.016305 +v -1.508277 0.586650 0.141922 +v -1.578117 0.749993 0.132286 +v -1.647956 0.913337 0.122648 +v -1.717796 1.076681 0.113011 +v -1.787635 1.240025 0.103374 +v -1.857474 1.403368 0.093737 +v -1.927314 1.566712 0.084100 +v -1.997153 1.730055 0.074463 +v -2.066993 1.893399 0.064826 +v -2.136832 2.056743 0.055189 +v -2.206672 2.220086 0.045552 +v -2.276511 2.383430 0.035915 +v -2.346350 2.546774 0.026278 +v -2.416190 2.710117 0.016641 +v -2.486029 2.873461 0.007004 +v -2.555869 3.036804 -0.002633 +v -2.625708 3.200148 -0.012270 +v -2.695547 3.363492 -0.021907 +v -1.274816 0.492934 0.145957 +v -1.344656 0.656278 0.136321 +v -1.414495 0.819621 0.126683 +v -1.484334 0.982965 0.117046 +v -1.554174 1.146308 0.107409 +v -1.624013 1.309652 0.097772 +v -1.693853 1.472996 0.088135 +v -1.763692 1.636340 0.078498 +v -1.833531 1.799683 0.068861 +v -1.903371 1.963027 0.059224 +v -1.973210 2.126370 0.049587 +v -2.043050 2.289714 0.039950 +v -2.112889 2.453058 0.030313 +v -2.182729 2.616402 0.020676 +v -2.252568 2.779745 0.011039 +v -2.322407 2.943089 0.001402 +v -2.392247 3.106432 -0.008235 +v -2.462086 3.269776 -0.017872 +v -2.531925 3.433120 -0.027509 +v -1.041355 0.399218 0.149992 +v -1.111194 0.562562 0.140356 +v -1.181034 0.725905 0.130718 +v -1.250873 0.889249 0.121081 +v -1.320712 1.052593 0.111444 +v -1.390552 1.215936 0.101807 +v -1.460391 1.379280 0.092170 +v -1.530231 1.542624 0.082533 +v -1.600070 1.705968 0.072896 +v -1.669910 1.869311 0.063259 +v -1.739749 2.032655 0.053622 +v -1.809589 2.195998 0.043985 +v -1.879428 2.359342 0.034348 +v -1.949267 2.522686 0.024711 +v -2.019107 2.686029 0.015074 +v -2.088946 2.849373 0.005437 +v -2.158785 3.012717 -0.004200 +v -2.228625 3.176060 -0.013837 +v -2.298464 3.339404 -0.023474 +v -2.368304 3.502747 -0.033111 +v -0.807893 0.305502 0.154027 +v -0.877733 0.468846 0.144391 +v -0.947572 0.632190 0.134753 +v -1.017412 0.795533 0.125116 +v -1.087251 0.958877 0.115479 +v -1.157091 1.122221 0.105842 +v -1.226930 1.285564 0.096205 +v -1.296769 1.448908 0.086568 +v -1.366609 1.612251 0.076931 +v -1.436448 1.775595 0.067294 +v -1.506288 1.938939 0.057657 +v -1.576127 2.102283 0.048020 +v -1.645967 2.265626 0.038383 +v -1.715806 2.428969 0.028746 +v -1.785645 2.592313 0.019109 +v -1.855485 2.755657 0.009472 +v -1.925324 2.919001 -0.000165 +v -1.995163 3.082345 -0.009802 +v -2.065003 3.245688 -0.019439 +v -2.134842 3.409032 -0.029076 +v -2.204681 3.572375 -0.038713 +v -0.574432 0.211786 0.158062 +v -0.644271 0.375130 0.148426 +v -0.714111 0.538474 0.138788 +v -0.783950 0.701817 0.129151 +v -0.853790 0.865161 0.119514 +v -0.923629 1.028505 0.109877 +v -0.993469 1.191848 0.100240 +v -1.063308 1.355192 0.090603 +v -1.133147 1.518536 0.080966 +v -1.202987 1.681879 0.071329 +v -1.272826 1.845223 0.061692 +v -1.342666 2.008567 0.052055 +v -1.412505 2.171911 0.042418 +v -1.482344 2.335254 0.032781 +v -1.552184 2.498598 0.023144 +v -1.622023 2.661941 0.013507 +v -1.691863 2.825285 0.003870 +v -1.761702 2.988628 -0.005767 +v -1.831541 3.151972 -0.015404 +v -1.901381 3.315316 -0.025041 +v -1.971220 3.478660 -0.034678 +v -2.041059 3.642003 -0.044315 +v -0.340971 0.118071 0.162097 +v -0.410810 0.281414 0.152461 +v -0.480650 0.444758 0.142823 +v -0.550489 0.608102 0.133186 +v -0.620328 0.771445 0.123549 +v -0.690168 0.934789 0.113912 +v -0.760007 1.098133 0.104275 +v -0.829847 1.261476 0.094638 +v -0.899686 1.424820 0.085001 +v -0.969525 1.588164 0.075364 +v -1.039365 1.751507 0.065727 +v -1.109204 1.914851 0.056090 +v -1.179044 2.078194 0.046453 +v -1.248883 2.241538 0.036816 +v -1.318722 2.404882 0.027179 +v -1.388562 2.568226 0.017542 +v -1.458401 2.731569 0.007905 +v -1.528241 2.894913 -0.001732 +v -1.598080 3.058257 -0.011369 +v -1.667919 3.221600 -0.021006 +v -1.737759 3.384944 -0.030643 +v -1.807598 3.548288 -0.040280 +v -1.877437 3.711631 -0.049917 +v -0.107509 0.024355 0.166132 +v -0.177349 0.187698 0.156495 +v -0.247188 0.351042 0.146858 +v -0.317028 0.514386 0.137221 +v -0.386867 0.677729 0.127584 +v -0.456706 0.841073 0.117947 +v -0.526546 1.004417 0.108310 +v -0.596385 1.167760 0.098673 +v -0.666225 1.331104 0.089036 +v -0.736064 1.494448 0.079399 +v -0.805903 1.657791 0.069762 +v -0.875743 1.821135 0.060125 +v -0.945582 1.984479 0.050488 +v -1.015422 2.147822 0.040851 +v -1.085261 2.311166 0.031214 +v -1.155100 2.474510 0.021577 +v -1.224940 2.637853 0.011940 +v -1.294779 2.801197 0.002303 +v -1.364619 2.964541 -0.007334 +v -1.434458 3.127884 -0.016971 +v -1.504297 3.291228 -0.026608 +v -1.574137 3.454572 -0.036245 +v -1.643976 3.617915 -0.045882 +v -1.713815 3.781258 -0.055519 +v 0.125952 -0.069361 0.170167 +v 0.056113 0.093983 0.160530 +v -0.013727 0.257326 0.150893 +v -0.083566 0.420670 0.141256 +v -0.153406 0.584014 0.131619 +v -0.223245 0.747357 0.121982 +v -0.293084 0.910701 0.112345 +v -0.362924 1.074044 0.102708 +v -0.432763 1.237388 0.093071 +v -0.502603 1.400732 0.083434 +v -0.572442 1.564076 0.073797 +v -0.642281 1.727419 0.064160 +v -0.712121 1.890763 0.054523 +v -0.781960 2.054106 0.044886 +v -0.851800 2.217450 0.035249 +v -0.921639 2.380794 0.025612 +v -0.991478 2.544138 0.015975 +v -1.061318 2.707481 0.006338 +v -1.131157 2.870825 -0.003299 +v -1.200997 3.034168 -0.012936 +v -1.270836 3.197512 -0.022573 +v -1.340675 3.360856 -0.032210 +v -1.410515 3.524200 -0.041847 +v -1.480354 3.687543 -0.051485 +v -1.550194 3.850887 -0.061122 +v 0.359413 -0.163077 0.174202 +v 0.289574 0.000267 0.164565 +v 0.219735 0.163610 0.154928 +v 0.149895 0.326954 0.145291 +v 0.080056 0.490298 0.135654 +v 0.010216 0.653641 0.126017 +v -0.059623 0.816985 0.116380 +v -0.129462 0.980329 0.106743 +v -0.199302 1.143672 0.097106 +v -0.269141 1.307016 0.087469 +v -0.338981 1.470360 0.077832 +v -0.408820 1.633703 0.068195 +v -0.478659 1.797047 0.058558 +v -0.548499 1.960391 0.048921 +v -0.618338 2.123734 0.039284 +v -0.688178 2.287078 0.029647 +v -0.758017 2.450422 0.020010 +v -0.827856 2.613765 0.010373 +v -0.897696 2.777109 0.000736 +v -0.967535 2.940452 -0.008901 +v -1.037375 3.103796 -0.018538 +v -1.107214 3.267140 -0.028175 +v -1.177053 3.430484 -0.037812 +v -1.246893 3.593827 -0.047450 +v -1.316732 3.757171 -0.057087 +v -1.386572 3.920515 -0.066724 +v 0.592875 -0.256793 0.178237 +v 0.523035 -0.093449 0.168600 +v 0.453196 0.069894 0.158963 +v 0.383356 0.233238 0.149326 +v 0.313517 0.396582 0.139689 +v 0.243678 0.559926 0.130052 +v 0.173838 0.723269 0.120415 +v 0.103999 0.886613 0.110778 +v 0.034160 1.049956 0.101141 +v -0.035680 1.213300 0.091504 +v -0.105519 1.376644 0.081867 +v -0.175359 1.539987 0.072230 +v -0.245198 1.703331 0.062593 +v -0.315037 1.866675 0.052956 +v -0.384877 2.030019 0.043319 +v -0.454716 2.193362 0.033682 +v -0.524556 2.356706 0.024045 +v -0.594395 2.520050 0.014408 +v -0.664234 2.683393 0.004771 +v -0.734074 2.846737 -0.004866 +v -0.803913 3.010080 -0.014503 +v -0.873753 3.173424 -0.024140 +v -0.943592 3.336768 -0.033778 +v -1.013431 3.500112 -0.043415 +v -1.083271 3.663455 -0.053052 +v -1.153110 3.826799 -0.062689 +v -1.222950 3.990143 -0.072326 +v 0.826336 -0.350509 0.182272 +v 0.756497 -0.187165 0.172635 +v 0.686657 -0.023821 0.162998 +v 0.616818 0.139522 0.153361 +v 0.546978 0.302866 0.143724 +v 0.477139 0.466210 0.134087 +v 0.407299 0.629553 0.124450 +v 0.337460 0.792897 0.114813 +v 0.267621 0.956241 0.105176 +v 0.197781 1.119584 0.095539 +v 0.127942 1.282928 0.085902 +v 0.058103 1.446272 0.076265 +v -0.011737 1.609615 0.066628 +v -0.081576 1.772959 0.056991 +v -0.151416 1.936302 0.047354 +v -0.221255 2.099646 0.037717 +v -0.291094 2.262990 0.028080 +v -0.360934 2.426333 0.018443 +v -0.430773 2.589677 0.008806 +v -0.500613 2.753021 -0.000831 +v -0.570452 2.916364 -0.010468 +v -0.640291 3.079708 -0.020105 +v -0.710131 3.243052 -0.029743 +v -0.779970 3.406395 -0.039380 +v -0.849809 3.569739 -0.049017 +v -0.919649 3.733083 -0.058654 +v -0.989488 3.896427 -0.068291 +v -1.059328 4.059771 -0.077928 +v 1.059797 -0.444224 0.186307 +v 0.989958 -0.280881 0.176670 +v 0.920118 -0.117537 0.167033 +v 0.850279 0.045806 0.157396 +v 0.780440 0.209150 0.147759 +v 0.710600 0.372494 0.138122 +v 0.640761 0.535838 0.128485 +v 0.570921 0.699181 0.118848 +v 0.501082 0.862525 0.109211 +v 0.431243 1.025868 0.099574 +v 0.361403 1.189212 0.089937 +v 0.291564 1.352556 0.080300 +v 0.221724 1.515899 0.070663 +v 0.151885 1.679243 0.061026 +v 0.082046 1.842587 0.051389 +v 0.012206 2.005930 0.041752 +v -0.057633 2.169274 0.032115 +v -0.127473 2.332618 0.022478 +v -0.197312 2.495961 0.012841 +v -0.267151 2.659305 0.003203 +v -0.336991 2.822649 -0.006433 +v -0.406830 2.985992 -0.016070 +v -0.476670 3.149336 -0.025708 +v -0.546509 3.312680 -0.035345 +v -0.616348 3.476023 -0.044982 +v -0.686188 3.639367 -0.054619 +v -0.756027 3.802711 -0.064256 +v -0.825866 3.966055 -0.073893 +v -0.895706 4.129398 -0.083530 +v 1.293259 -0.537940 0.190342 +v 1.223419 -0.374597 0.180705 +v 1.153580 -0.211253 0.171068 +v 1.083740 -0.047909 0.161431 +v 1.013901 0.115434 0.151794 +v 0.944062 0.278778 0.142157 +v 0.874222 0.442122 0.132520 +v 0.804383 0.605465 0.122883 +v 0.734543 0.768809 0.113246 +v 0.664704 0.932153 0.103609 +v 0.594865 1.095496 0.093972 +v 0.525025 1.258840 0.084335 +v 0.455186 1.422184 0.074698 +v 0.385347 1.585527 0.065061 +v 0.315507 1.748871 0.055424 +v 0.245668 1.912214 0.045787 +v 0.175828 2.075558 0.036150 +v 0.105989 2.238902 0.026513 +v 0.036150 2.402245 0.016876 +v -0.033690 2.565589 0.007238 +v -0.103529 2.728933 -0.002398 +v -0.173369 2.892277 -0.012035 +v -0.243208 3.055620 -0.021673 +v -0.313048 3.218964 -0.031310 +v -0.382887 3.382308 -0.040947 +v -0.452726 3.545651 -0.050584 +v -0.522565 3.708995 -0.060221 +v -0.592405 3.872339 -0.069858 +v -0.662244 4.035683 -0.079495 +v -0.732084 4.199026 -0.089132 +v 1.526720 -0.631656 0.194377 +v 1.456881 -0.468312 0.184740 +v 1.387041 -0.304969 0.175103 +v 1.317202 -0.141625 0.165466 +v 1.247363 0.021719 0.155829 +v 1.177523 0.185062 0.146192 +v 1.107684 0.348406 0.136555 +v 1.037845 0.511750 0.126918 +v 0.968005 0.675093 0.117281 +v 0.898166 0.838437 0.107644 +v 0.828327 1.001781 0.098007 +v 0.758487 1.165124 0.088370 +v 0.688648 1.328468 0.078733 +v 0.618808 1.491812 0.069096 +v 0.548969 1.655155 0.059459 +v 0.479130 1.818499 0.049822 +v 0.409290 1.981842 0.040185 +v 0.339451 2.145186 0.030548 +v 0.269611 2.308530 0.020911 +v 0.199772 2.471873 0.011274 +v 0.129933 2.635217 0.001636 +v 0.060093 2.798561 -0.008000 +v -0.009746 2.961904 -0.017638 +v -0.079586 3.125248 -0.027275 +v -0.149425 3.288592 -0.036912 +v -0.219265 3.451936 -0.046549 +v -0.289104 3.615279 -0.056186 +v -0.358943 3.778623 -0.065823 +v -0.428783 3.941966 -0.075460 +v -0.498622 4.105311 -0.085097 +v -0.568462 4.268654 -0.094734 +v 1.760181 -0.725372 0.198412 +v 1.690342 -0.562028 0.188775 +v 1.620502 -0.398685 0.179138 +v 1.550663 -0.235341 0.169501 +v 1.480824 -0.071997 0.159864 +v 1.410985 0.091346 0.150227 +v 1.341145 0.254690 0.140590 +v 1.271306 0.418034 0.130953 +v 1.201466 0.581377 0.121316 +v 1.131627 0.744721 0.111679 +v 1.061788 0.908065 0.102042 +v 0.991948 1.071408 0.092405 +v 0.922109 1.234752 0.082768 +v 0.852270 1.398096 0.073131 +v 0.782430 1.561439 0.063494 +v 0.712591 1.724783 0.053857 +v 0.642752 1.888126 0.044220 +v 0.572912 2.051470 0.034583 +v 0.503073 2.214814 0.024946 +v 0.433233 2.378157 0.015309 +v 0.363394 2.541501 0.005672 +v 0.293555 2.704845 -0.003965 +v 0.223715 2.868189 -0.013603 +v 0.153876 3.031532 -0.023240 +v 0.084036 3.194876 -0.032877 +v 0.014197 3.358220 -0.042514 +v -0.055643 3.521563 -0.052151 +v -0.125482 3.684907 -0.061788 +v -0.195321 3.848251 -0.071425 +v -0.265161 4.011594 -0.081062 +v -0.335000 4.174939 -0.090699 +v -0.404840 4.338282 -0.100336 +v 1.993642 -0.819088 0.202447 +v 1.923803 -0.655744 0.192810 +v 1.853964 -0.492400 0.183173 +v 1.784124 -0.329057 0.173536 +v 1.714285 -0.165713 0.163899 +v 1.644446 -0.002369 0.154262 +v 1.574606 0.160974 0.144625 +v 1.504767 0.324318 0.134988 +v 1.434928 0.487662 0.125351 +v 1.365088 0.651005 0.115714 +v 1.295249 0.814349 0.106077 +v 1.225410 0.977692 0.096440 +v 1.155570 1.141036 0.086803 +v 1.085731 1.304380 0.077166 +v 1.015892 1.467724 0.067529 +v 0.946052 1.631067 0.057892 +v 0.876213 1.794411 0.048255 +v 0.806373 1.957754 0.038618 +v 0.736534 2.121098 0.028981 +v 0.666695 2.284442 0.019344 +v 0.596855 2.447785 0.009706 +v 0.527016 2.611129 0.000069 +v 0.457176 2.774473 -0.009568 +v 0.387337 2.937817 -0.019205 +v 0.317498 3.101161 -0.028842 +v 0.247658 3.264504 -0.038479 +v 0.177819 3.427847 -0.048116 +v 0.107979 3.591191 -0.057753 +v 0.038140 3.754535 -0.067390 +v -0.031699 3.917878 -0.077027 +v -0.101539 4.081222 -0.086664 +v -0.171378 4.244566 -0.096301 +v -0.241217 4.407909 -0.105938 +v 2.227104 -0.912804 0.206482 +v 2.157264 -0.749460 0.196845 +v 2.087425 -0.586116 0.187208 +v 2.017586 -0.422773 0.177571 +v 1.947746 -0.259429 0.167934 +v 1.877907 -0.096085 0.158297 +v 1.808068 0.067258 0.148660 +v 1.738228 0.230602 0.139023 +v 1.668389 0.393946 0.129386 +v 1.598550 0.557289 0.119749 +v 1.528710 0.720633 0.110112 +v 1.458871 0.883977 0.100475 +v 1.389032 1.047320 0.090838 +v 1.319192 1.210664 0.081201 +v 1.249353 1.374008 0.071564 +v 1.179514 1.537351 0.061927 +v 1.109674 1.700695 0.052290 +v 1.039835 1.864038 0.042653 +v 0.969995 2.027382 0.033016 +v 0.900156 2.190726 0.023379 +v 0.830317 2.354070 0.013741 +v 0.760477 2.517413 0.004105 +v 0.690638 2.680757 -0.005533 +v 0.620798 2.844100 -0.015170 +v 0.550959 3.007444 -0.024807 +v 0.481119 3.170788 -0.034444 +v 0.411280 3.334132 -0.044081 +v 0.341441 3.497475 -0.053718 +v 0.271601 3.660819 -0.063355 +v 0.201762 3.824162 -0.072992 +v 0.131922 3.987506 -0.082629 +v 0.062083 4.150850 -0.092266 +v -0.007756 4.314194 -0.101903 +v -0.077596 4.477537 -0.111540 +v 2.460565 -1.006519 0.210517 +v 2.390726 -0.843176 0.200880 +v 2.320886 -0.679832 0.191243 +v 2.251047 -0.516488 0.181606 +v 2.181208 -0.353145 0.171969 +v 2.111368 -0.189801 0.162332 +v 2.041529 -0.026457 0.152695 +v 1.971690 0.136886 0.143058 +v 1.901850 0.300230 0.133421 +v 1.832011 0.463574 0.123784 +v 1.762172 0.626917 0.114147 +v 1.692332 0.790261 0.104510 +v 1.622493 0.953604 0.094873 +v 1.552653 1.116948 0.085236 +v 1.482814 1.280292 0.075599 +v 1.412975 1.443635 0.065962 +v 1.343135 1.606979 0.056325 +v 1.273296 1.770323 0.046688 +v 1.203457 1.933666 0.037051 +v 1.133617 2.097010 0.027414 +v 1.063778 2.260354 0.017776 +v 0.993939 2.423697 0.008140 +v 0.924099 2.587041 -0.001498 +v 0.854260 2.750385 -0.011135 +v 0.784420 2.913728 -0.020772 +v 0.714581 3.077072 -0.030409 +v 0.644741 3.240416 -0.040046 +v 0.574902 3.403759 -0.049683 +v 0.505063 3.567103 -0.059320 +v 0.435223 3.730447 -0.068957 +v 0.365384 3.893790 -0.078594 +v 0.295545 4.057134 -0.088231 +v 0.225705 4.220478 -0.097868 +v 0.155866 4.383822 -0.107505 +v 0.086026 4.547165 -0.117142 +v 2.694026 -1.100235 0.214552 +v 2.624187 -0.936891 0.204915 +v 2.554348 -0.773548 0.195278 +v 2.484508 -0.610204 0.185641 +v 2.414669 -0.446860 0.176004 +v 2.344830 -0.283517 0.166367 +v 2.274990 -0.120173 0.156730 +v 2.205151 0.043171 0.147093 +v 2.135312 0.206514 0.137456 +v 2.065472 0.369858 0.127819 +v 1.995633 0.533202 0.118182 +v 1.925793 0.696545 0.108545 +v 1.855954 0.859889 0.098908 +v 1.786115 1.023233 0.089271 +v 1.716275 1.186576 0.079634 +v 1.646436 1.349920 0.069997 +v 1.576597 1.513264 0.060360 +v 1.506757 1.676607 0.050723 +v 1.436918 1.839951 0.041086 +v 1.367079 2.003294 0.031449 +v 1.297239 2.166638 0.021811 +v 1.227400 2.329982 0.012175 +v 1.157561 2.493325 0.002537 +v 1.087721 2.656669 -0.007100 +v 1.017882 2.820013 -0.016737 +v 0.948043 2.983356 -0.026374 +v 0.878203 3.146700 -0.036011 +v 0.808364 3.310044 -0.045648 +v 0.738524 3.473387 -0.055285 +v 0.668685 3.636731 -0.064922 +v 0.598846 3.800074 -0.074559 +v 0.529006 3.963418 -0.084196 +v 0.459167 4.126763 -0.093833 +v 0.389327 4.290105 -0.103470 +v 0.319488 4.453450 -0.113107 +v 0.249648 4.616793 -0.122744 +v 2.927488 -1.193951 0.218587 +v 2.857649 -1.030607 0.208950 +v 2.787809 -0.867264 0.199313 +v 2.717970 -0.703920 0.189676 +v 2.648130 -0.540576 0.180039 +v 2.578291 -0.377233 0.170402 +v 2.508452 -0.213889 0.160765 +v 2.438612 -0.050545 0.151128 +v 2.368773 0.112799 0.141491 +v 2.298934 0.276142 0.131854 +v 2.229095 0.439486 0.122217 +v 2.159255 0.602829 0.112580 +v 2.089416 0.766173 0.102943 +v 2.019576 0.929517 0.093306 +v 1.949737 1.092860 0.083669 +v 1.879898 1.256204 0.074032 +v 1.810058 1.419548 0.064395 +v 1.740219 1.582891 0.054758 +v 1.670380 1.746235 0.045121 +v 1.600540 1.909578 0.035484 +v 1.530701 2.072922 0.025846 +v 1.460862 2.236266 0.016210 +v 1.391022 2.399609 0.006572 +v 1.321183 2.562953 -0.003065 +v 1.251343 2.726297 -0.012702 +v 1.181504 2.889640 -0.022339 +v 1.111665 3.052984 -0.031976 +v 1.041825 3.216328 -0.041613 +v 0.971986 3.379672 -0.051250 +v 0.902147 3.543015 -0.060887 +v 0.832307 3.706359 -0.070524 +v 0.762468 3.869703 -0.080161 +v 0.692628 4.033046 -0.089798 +v 0.622789 4.196391 -0.099435 +v 0.552949 4.359733 -0.109072 +v 0.483110 4.523077 -0.118709 +v 0.413270 4.686420 -0.128346 +v 3.160949 -1.287667 0.222622 +v 3.091110 -1.124323 0.212985 +v 3.021271 -0.960980 0.203348 +v 2.951431 -0.797636 0.193711 +v 2.881592 -0.634292 0.184074 +v 2.811752 -0.470948 0.174437 +v 2.741913 -0.307605 0.164800 +v 2.672074 -0.144261 0.155163 +v 2.602234 0.019083 0.145526 +v 2.532395 0.182426 0.135889 +v 2.462556 0.345770 0.126252 +v 2.392716 0.509114 0.116615 +v 2.322877 0.672457 0.106978 +v 2.253038 0.835801 0.097341 +v 2.183198 0.999145 0.087704 +v 2.113359 1.162488 0.078067 +v 2.043519 1.325832 0.068430 +v 1.973680 1.489176 0.058793 +v 1.903841 1.652519 0.049156 +v 1.834001 1.815863 0.039519 +v 1.764162 1.979206 0.029881 +v 1.694323 2.142550 0.020245 +v 1.624483 2.305894 0.010607 +v 1.554644 2.469237 0.000970 +v 1.484805 2.632581 -0.008667 +v 1.414965 2.795925 -0.018304 +v 1.345126 2.959268 -0.027941 +v 1.275287 3.122612 -0.037578 +v 1.205447 3.285956 -0.047215 +v 1.135608 3.449299 -0.056852 +v 1.065768 3.612643 -0.066489 +v 0.995929 3.775987 -0.076126 +v 0.926090 3.939330 -0.085763 +v 0.856250 4.102675 -0.095400 +v 0.786411 4.266018 -0.105037 +v 0.716572 4.429361 -0.114674 +v 0.646732 4.592705 -0.124311 +v 0.576893 4.756048 -0.133948 +v 3.394411 -1.381383 0.226657 +v 3.324571 -1.218039 0.217020 +v 3.254732 -1.054695 0.207383 +v 3.184893 -0.891352 0.197746 +v 3.115053 -0.728008 0.188109 +v 3.045214 -0.564664 0.178472 +v 2.975374 -0.401321 0.168835 +v 2.905535 -0.237977 0.159198 +v 2.835696 -0.074633 0.149561 +v 2.765857 0.088711 0.139924 +v 2.696017 0.252054 0.130287 +v 2.626178 0.415398 0.120650 +v 2.556339 0.578741 0.111013 +v 2.486499 0.742085 0.101376 +v 2.416660 0.905429 0.091739 +v 2.346820 1.068772 0.082102 +v 2.276981 1.232116 0.072465 +v 2.207142 1.395460 0.062828 +v 2.137302 1.558803 0.053190 +v 2.067463 1.722147 0.043554 +v 1.997624 1.885490 0.033916 +v 1.927784 2.048834 0.024279 +v 1.857945 2.212178 0.014642 +v 1.788106 2.375521 0.005005 +v 1.718266 2.538865 -0.004632 +v 1.648427 2.702209 -0.014269 +v 1.578587 2.865552 -0.023906 +v 1.508748 3.028896 -0.033543 +v 1.438909 3.192240 -0.043180 +v 1.369069 3.355584 -0.052817 +v 1.299230 3.518927 -0.062454 +v 1.229391 3.682271 -0.072091 +v 1.159551 3.845615 -0.081728 +v 1.089712 4.008958 -0.091365 +v 1.019872 4.172303 -0.101002 +v 0.950033 4.335646 -0.110639 +v 0.880193 4.498990 -0.120276 +v 0.810354 4.662333 -0.129913 +v 0.740515 4.825676 -0.139550 +v 3.627872 -1.475098 0.230692 +v 3.558033 -1.311755 0.221055 +v 3.488194 -1.148411 0.211418 +v 3.418354 -0.985067 0.201781 +v 3.348515 -0.821724 0.192144 +v 3.278676 -0.658380 0.182507 +v 3.208836 -0.495036 0.172870 +v 3.138997 -0.331693 0.163233 +v 3.069157 -0.168349 0.153596 +v 2.999318 -0.005005 0.143959 +v 2.929479 0.158338 0.134322 +v 2.859639 0.321682 0.124685 +v 2.789800 0.485026 0.115048 +v 2.719961 0.648369 0.105411 +v 2.650121 0.811713 0.095774 +v 2.580282 0.975057 0.086137 +v 2.510442 1.138400 0.076500 +v 2.440603 1.301744 0.066863 +v 2.370764 1.465088 0.057225 +v 2.300925 1.628431 0.047589 +v 2.231085 1.791775 0.037951 +v 2.161246 1.955118 0.028314 +v 2.091406 2.118462 0.018677 +v 2.021567 2.281806 0.009040 +v 1.951728 2.445150 -0.000597 +v 1.881888 2.608493 -0.010234 +v 1.812049 2.771837 -0.019871 +v 1.742210 2.935180 -0.029508 +v 1.672370 3.098524 -0.039145 +v 1.602531 3.261868 -0.048782 +v 1.532691 3.425211 -0.058419 +v 1.462852 3.588555 -0.068056 +v 1.393013 3.751899 -0.077693 +v 1.323173 3.915242 -0.087330 +v 1.253334 4.078587 -0.096967 +v 1.183494 4.241930 -0.106604 +v 1.113655 4.405274 -0.116241 +v 1.043816 4.568617 -0.125878 +v 0.973976 4.731961 -0.135515 +v 0.904137 4.895304 -0.145152 +v 3.861333 -1.568815 0.234727 +v 3.791494 -1.405471 0.225090 +v 3.721655 -1.242127 0.215453 +v 3.651815 -1.078783 0.205816 +v 3.581976 -0.915440 0.196179 +v 3.512137 -0.752096 0.186542 +v 3.442297 -0.588752 0.176905 +v 3.372458 -0.425409 0.167268 +v 3.302619 -0.262065 0.157631 +v 3.232779 -0.098721 0.147994 +v 3.162940 0.064623 0.138357 +v 3.093101 0.227966 0.128720 +v 3.023261 0.391310 0.119083 +v 2.953422 0.554654 0.109446 +v 2.883583 0.717997 0.099809 +v 2.813743 0.881341 0.090172 +v 2.743904 1.044684 0.080535 +v 2.674064 1.208028 0.070898 +v 2.604225 1.371372 0.061260 +v 2.534386 1.534715 0.051624 +v 2.464546 1.698059 0.041986 +v 2.394707 1.861402 0.032349 +v 2.324868 2.024746 0.022712 +v 2.255028 2.188090 0.013075 +v 2.185189 2.351433 0.003438 +v 2.115350 2.514777 -0.006199 +v 2.045510 2.678120 -0.015836 +v 1.975671 2.841465 -0.025473 +v 1.905831 3.004808 -0.035110 +v 1.835992 3.168152 -0.044747 +v 1.766153 3.331496 -0.054384 +v 1.696313 3.494839 -0.064021 +v 1.626474 3.658183 -0.073658 +v 1.556635 3.821527 -0.083295 +v 1.486795 3.984870 -0.092932 +v 1.416956 4.148214 -0.102569 +v 1.347116 4.311558 -0.112206 +v 1.277277 4.474902 -0.121843 +v 1.207438 4.638245 -0.131480 +v 1.137598 4.801589 -0.141117 +v 1.067759 4.964931 -0.150754 +v 4.094795 -1.662530 0.238762 +v 4.024956 -1.499186 0.229125 +v 3.955116 -1.335843 0.219488 +v 3.885277 -1.172499 0.209851 +v 3.815438 -1.009155 0.200214 +v 3.745598 -0.845812 0.190577 +v 3.675759 -0.682468 0.180940 +v 3.605919 -0.519124 0.171303 +v 3.536080 -0.355781 0.161666 +v 3.466241 -0.192437 0.152029 +v 3.396401 -0.029093 0.142392 +v 3.326562 0.134250 0.132755 +v 3.256723 0.297594 0.123118 +v 3.186883 0.460938 0.113481 +v 3.117044 0.624281 0.103844 +v 3.047205 0.787625 0.094207 +v 2.977365 0.950969 0.084570 +v 2.907526 1.114312 0.074933 +v 2.837687 1.277656 0.065295 +v 2.767847 1.440999 0.055659 +v 2.698008 1.604343 0.046021 +v 2.628169 1.767687 0.036384 +v 2.558329 1.931030 0.026747 +v 2.488490 2.094374 0.017110 +v 2.418651 2.257718 0.007473 +v 2.348811 2.421061 -0.002164 +v 2.278972 2.584405 -0.011801 +v 2.209132 2.747748 -0.021438 +v 2.139293 2.911092 -0.031075 +v 2.069454 3.074436 -0.040712 +v 1.999614 3.237780 -0.050349 +v 1.929775 3.401124 -0.059986 +v 1.859936 3.564467 -0.069623 +v 1.790096 3.727811 -0.079260 +v 1.720257 3.891155 -0.088897 +v 1.650417 4.054498 -0.098534 +v 1.580578 4.217842 -0.108171 +v 1.510738 4.381186 -0.117808 +v 1.440899 4.544529 -0.127445 +v 1.371060 4.707873 -0.137082 +v 1.301220 4.871216 -0.146720 +v 1.231381 5.034559 -0.156357 +v 4.328257 -1.756246 0.242797 +v 4.258417 -1.592903 0.233160 +v 4.188578 -1.429559 0.223523 +v 4.118738 -1.266215 0.213886 +v 4.048899 -1.102871 0.204249 +v 3.979060 -0.939528 0.194612 +v 3.909220 -0.776184 0.184975 +v 3.839381 -0.612840 0.175338 +v 3.769542 -0.449497 0.165701 +v 3.699702 -0.286153 0.156064 +v 3.629863 -0.122809 0.146427 +v 3.560024 0.040535 0.136790 +v 3.490184 0.203878 0.127153 +v 3.420345 0.367222 0.117516 +v 3.350505 0.530566 0.107879 +v 3.280666 0.693909 0.098242 +v 3.210827 0.857253 0.088605 +v 3.140987 1.020596 0.078968 +v 3.071148 1.183940 0.069330 +v 3.001309 1.347284 0.059694 +v 2.931469 1.510627 0.050056 +v 2.861630 1.673971 0.040419 +v 2.791791 1.837314 0.030782 +v 2.721951 2.000658 0.021145 +v 2.652112 2.164002 0.011508 +v 2.582273 2.327345 0.001871 +v 2.512433 2.490689 -0.007766 +v 2.442594 2.654033 -0.017403 +v 2.372755 2.817376 -0.027040 +v 2.302915 2.980720 -0.036677 +v 2.233076 3.144064 -0.046314 +v 2.163237 3.307407 -0.055951 +v 2.093397 3.470751 -0.065588 +v 2.023558 3.634095 -0.075225 +v 1.953718 3.797439 -0.084862 +v 1.883879 3.960782 -0.094499 +v 1.814040 4.124126 -0.104136 +v 1.744200 4.287470 -0.113773 +v 1.674361 4.450814 -0.123410 +v 1.604521 4.614157 -0.133048 +v 1.534682 4.777501 -0.142685 +v 1.464842 4.940844 -0.152322 +v 1.395003 5.104187 -0.161959 +v 4.561718 -1.849962 0.246832 +v 4.491879 -1.686618 0.237195 +v 4.422039 -1.523275 0.227558 +v 4.352200 -1.359931 0.217921 +v 4.282360 -1.196587 0.208284 +v 4.212521 -1.033243 0.198647 +v 4.142681 -0.869900 0.189010 +v 4.072842 -0.706556 0.179373 +v 4.003003 -0.543212 0.169736 +v 3.933163 -0.379869 0.160099 +v 3.863324 -0.216525 0.150462 +v 3.793484 -0.053181 0.140825 +v 3.723645 0.110162 0.131188 +v 3.653806 0.273506 0.121551 +v 3.583966 0.436850 0.111914 +v 3.514127 0.600194 0.102277 +v 3.444288 0.763537 0.092639 +v 3.374448 0.926881 0.083003 +v 3.304609 1.090224 0.073365 +v 3.234770 1.253568 0.063729 +v 3.164930 1.416912 0.054091 +v 3.095091 1.580255 0.044454 +v 3.025252 1.743599 0.034817 +v 2.955412 1.906943 0.025180 +v 2.885573 2.070286 0.015543 +v 2.815734 2.233629 0.005906 +v 2.745894 2.396973 -0.003731 +v 2.676055 2.560317 -0.013368 +v 2.606216 2.723661 -0.023005 +v 2.536376 2.887004 -0.032642 +v 2.466537 3.050348 -0.042279 +v 2.396698 3.213691 -0.051916 +v 2.326858 3.377035 -0.061553 +v 2.257019 3.540379 -0.071190 +v 2.187180 3.703722 -0.080827 +v 2.117340 3.867067 -0.090464 +v 2.047501 4.030410 -0.100101 +v 1.977661 4.193754 -0.109738 +v 1.907822 4.357098 -0.119375 +v 1.837982 4.520442 -0.129013 +v 1.768143 4.683785 -0.138650 +v 1.698304 4.847129 -0.148287 +v 1.628464 5.010472 -0.157924 +v 1.558625 5.173815 -0.167561 +v 4.795178 -1.943678 0.250867 +v 4.725339 -1.780334 0.241230 +v 4.655500 -1.616990 0.231593 +v 4.585661 -1.453647 0.221956 +v 4.515821 -1.290303 0.212319 +v 4.445982 -1.126959 0.202682 +v 4.376143 -0.963615 0.193045 +v 4.306303 -0.800272 0.183408 +v 4.236464 -0.636928 0.173771 +v 4.166625 -0.473584 0.164134 +v 4.096786 -0.310241 0.154497 +v 4.026946 -0.146897 0.144860 +v 3.957106 0.016446 0.135223 +v 3.887267 0.179790 0.125586 +v 3.817428 0.343134 0.115949 +v 3.747588 0.506478 0.106312 +v 3.677749 0.669821 0.096674 +v 3.607910 0.833165 0.087038 +v 3.538070 0.996508 0.077400 +v 3.468231 1.159852 0.067763 +v 3.398391 1.323196 0.058126 +v 3.328552 1.486539 0.048489 +v 3.258713 1.649883 0.038852 +v 3.188874 1.813227 0.029215 +v 3.119034 1.976570 0.019578 +v 3.049195 2.139914 0.009941 +v 2.979356 2.303257 0.000304 +v 2.909516 2.466601 -0.009333 +v 2.839677 2.629944 -0.018970 +v 2.769838 2.793288 -0.028607 +v 2.699998 2.956631 -0.038244 +v 2.630159 3.119976 -0.047881 +v 2.560319 3.283319 -0.057518 +v 2.490480 3.446663 -0.067155 +v 2.420641 3.610007 -0.076792 +v 2.350801 3.773350 -0.086429 +v 2.280962 3.936694 -0.096066 +v 2.211123 4.100038 -0.105703 +v 2.141283 4.263381 -0.115340 +v 2.071444 4.426725 -0.124978 +v 2.001605 4.590069 -0.134615 +v 1.931765 4.753413 -0.144252 +v 1.861926 4.916757 -0.153889 +v 1.792086 5.080100 -0.163526 +v 1.722247 5.243443 -0.173163 +v 5.028641 -2.037393 0.254902 +v 4.958801 -1.874050 0.245265 +v 4.888962 -1.710706 0.235628 +v 4.819122 -1.547362 0.225991 +v 4.749283 -1.384019 0.216354 +v 4.679443 -1.220675 0.206717 +v 4.609604 -1.057331 0.197080 +v 4.539764 -0.893988 0.187443 +v 4.469925 -0.730644 0.177806 +v 4.400086 -0.567300 0.168169 +v 4.330247 -0.403957 0.158532 +v 4.260407 -0.240613 0.148895 +v 4.190568 -0.077269 0.139258 +v 4.120728 0.086074 0.129621 +v 4.050889 0.249418 0.119984 +v 3.981050 0.412762 0.110347 +v 3.911211 0.576105 0.100709 +v 3.841371 0.739449 0.091073 +v 3.771532 0.902793 0.081435 +v 3.701692 1.066136 0.071798 +v 3.631853 1.229480 0.062161 +v 3.562014 1.392824 0.052524 +v 3.492174 1.556167 0.042887 +v 3.422335 1.719511 0.033250 +v 3.352496 1.882854 0.023613 +v 3.282656 2.046198 0.013976 +v 3.212817 2.209542 0.004339 +v 3.142978 2.372885 -0.005298 +v 3.073138 2.536229 -0.014935 +v 3.003299 2.699573 -0.024572 +v 2.933460 2.862916 -0.034209 +v 2.863620 3.026260 -0.043846 +v 2.793781 3.189603 -0.053483 +v 2.723942 3.352947 -0.063120 +v 2.654102 3.516291 -0.072757 +v 2.584263 3.679635 -0.082394 +v 2.514423 3.842979 -0.092031 +v 2.444584 4.006322 -0.101668 +v 2.374745 4.169666 -0.111305 +v 2.304905 4.333009 -0.120943 +v 2.235066 4.496353 -0.130580 +v 2.165227 4.659697 -0.140217 +v 2.095387 4.823040 -0.149854 +v 2.025548 4.986385 -0.159491 +v 1.955708 5.149727 -0.169128 +v 1.885869 5.313070 -0.178765 +v 5.262101 -2.131109 0.258937 +v 5.192262 -1.967766 0.249300 +v 5.122422 -1.804422 0.239663 +v 5.052583 -1.641078 0.230026 +v 4.982744 -1.477734 0.220389 +v 4.912905 -1.314391 0.210752 +v 4.843065 -1.151047 0.201115 +v 4.773226 -0.987703 0.191478 +v 4.703386 -0.824360 0.181841 +v 4.633547 -0.661016 0.172204 +v 4.563707 -0.497672 0.162567 +v 4.493869 -0.334329 0.152930 +v 4.424029 -0.170985 0.143293 +v 4.354190 -0.007642 0.133656 +v 4.284350 0.155702 0.124019 +v 4.214511 0.319046 0.114382 +v 4.144671 0.482390 0.104744 +v 4.074832 0.645733 0.095108 +v 4.004992 0.809077 0.085470 +v 3.935153 0.972420 0.075833 +v 3.865314 1.135764 0.066196 +v 3.795475 1.299108 0.056559 +v 3.725635 1.462451 0.046922 +v 3.655796 1.625795 0.037285 +v 3.585957 1.789138 0.027648 +v 3.516117 1.952482 0.018011 +v 3.446278 2.115826 0.008374 +v 3.376439 2.279169 -0.001263 +v 3.306599 2.442513 -0.010900 +v 3.236760 2.605856 -0.020537 +v 3.166921 2.769200 -0.030174 +v 3.097081 2.932544 -0.039811 +v 3.027242 3.095887 -0.049448 +v 2.957403 3.259231 -0.059085 +v 2.887563 3.422575 -0.068722 +v 2.817724 3.585918 -0.078359 +v 2.747885 3.749262 -0.087996 +v 2.678045 3.912606 -0.097633 +v 2.608206 4.075950 -0.107270 +v 2.538366 4.239294 -0.116908 +v 2.468527 4.402637 -0.126545 +v 2.398688 4.565981 -0.136182 +v 2.328848 4.729325 -0.145819 +v 2.259009 4.892668 -0.155456 +v 2.189170 5.056013 -0.165093 +v 2.119330 5.219355 -0.174730 +v 2.049491 5.382698 -0.184367 +v 5.495563 -2.224826 0.262972 +v 5.425723 -2.061481 0.253335 +v 5.355885 -1.898138 0.243698 +v 5.286045 -1.734794 0.234061 +v 5.216206 -1.571451 0.224424 +v 5.146366 -1.408107 0.214787 +v 5.076527 -1.244763 0.205150 +v 5.006687 -1.081420 0.195513 +v 4.936848 -0.918076 0.185876 +v 4.867008 -0.754732 0.176239 +v 4.797169 -0.591388 0.166602 +v 4.727330 -0.428045 0.156965 +v 4.657491 -0.264701 0.147328 +v 4.587651 -0.101357 0.137691 +v 4.517812 0.061986 0.128054 +v 4.447972 0.225330 0.118417 +v 4.378133 0.388674 0.108779 +v 4.308293 0.552017 0.099143 +v 4.238455 0.715361 0.089505 +v 4.168615 0.878705 0.079868 +v 4.098776 1.042048 0.070231 +v 4.028936 1.205392 0.060594 +v 3.959097 1.368735 0.050957 +v 3.889257 1.532079 0.041320 +v 3.819418 1.695423 0.031683 +v 3.749579 1.858766 0.022046 +v 3.679739 2.022110 0.012409 +v 3.609900 2.185454 0.002772 +v 3.540061 2.348797 -0.006865 +v 3.470222 2.512141 -0.016502 +v 3.400382 2.675484 -0.026139 +v 3.330543 2.838828 -0.035776 +v 3.260704 3.002172 -0.045413 +v 3.190864 3.165515 -0.055050 +v 3.121025 3.328859 -0.064687 +v 3.051185 3.492203 -0.074324 +v 2.981346 3.655546 -0.083961 +v 2.911507 3.818890 -0.093598 +v 2.841667 3.982234 -0.103236 +v 2.771828 4.145578 -0.112873 +v 2.701989 4.308921 -0.122510 +v 2.632149 4.472265 -0.132147 +v 2.562310 4.635609 -0.141784 +v 2.492471 4.798953 -0.151421 +v 2.422631 4.962296 -0.161058 +v 2.352792 5.125640 -0.170695 +v 2.282953 5.288983 -0.180332 +v 2.213113 5.452327 -0.189969 +v 5.729023 -2.318541 0.267007 +v 5.659184 -2.155197 0.257370 +v 5.589345 -1.991854 0.247733 +v 5.519506 -1.828510 0.238096 +v 5.449666 -1.665166 0.228459 +v 5.379827 -1.501822 0.218822 +v 5.309987 -1.338479 0.209185 +v 5.240148 -1.175135 0.199548 +v 5.170308 -1.011791 0.189911 +v 5.100470 -0.848448 0.180274 +v 5.030630 -0.685104 0.170637 +v 4.960791 -0.521760 0.161000 +v 4.890951 -0.358416 0.151363 +v 4.821112 -0.195073 0.141726 +v 4.751272 -0.031729 0.132089 +v 4.681433 0.131614 0.122452 +v 4.611594 0.294958 0.112814 +v 4.541755 0.458302 0.103178 +v 4.471915 0.621645 0.093540 +v 4.402076 0.784989 0.083903 +v 4.332236 0.948332 0.074266 +v 4.262397 1.111676 0.064629 +v 4.192557 1.275020 0.054992 +v 4.122719 1.438363 0.045355 +v 4.052879 1.601707 0.035718 +v 3.983040 1.765051 0.026081 +v 3.913200 1.928394 0.016444 +v 3.843361 2.091738 0.006807 +v 3.773521 2.255081 -0.002830 +v 3.703682 2.418425 -0.012467 +v 3.633843 2.581769 -0.022104 +v 3.564003 2.745112 -0.031741 +v 3.494164 2.908456 -0.041378 +v 3.424325 3.071799 -0.051015 +v 3.354486 3.235143 -0.060652 +v 3.284646 3.398487 -0.070289 +v 3.214807 3.561830 -0.079926 +v 3.144968 3.725174 -0.089563 +v 3.075128 3.888518 -0.099200 +v 3.005289 4.051861 -0.108838 +v 2.935449 4.215206 -0.118475 +v 2.865610 4.378549 -0.128112 +v 2.795771 4.541893 -0.137749 +v 2.725931 4.705236 -0.147386 +v 2.656092 4.868580 -0.157023 +v 2.586253 5.031924 -0.166660 +v 2.516413 5.195268 -0.176297 +v 2.446574 5.358611 -0.185934 +v 2.376735 5.521955 -0.195571 +v -2.218616 -5.893647 0.551145 +v -2.054993 -5.824019 0.545543 +v -2.288455 -5.730304 0.541508 +v -1.891371 -5.754392 0.539941 +v -2.124833 -5.660676 0.535906 +v -2.358294 -5.566959 0.531871 +v -1.727749 -5.684764 0.534339 +v -1.961210 -5.591048 0.530304 +v -2.194672 -5.497332 0.526269 +v -2.428133 -5.403617 0.522234 +v -1.564127 -5.615136 0.528737 +v -1.797588 -5.521420 0.524702 +v -2.031050 -5.427704 0.520667 +v -2.264511 -5.333989 0.516632 +v -2.497972 -5.240272 0.512597 +v -1.400505 -5.545508 0.523135 +v -1.633966 -5.451793 0.519100 +v -1.867428 -5.358076 0.515065 +v -2.100889 -5.264361 0.511030 +v -2.334351 -5.170644 0.506995 +v -2.567812 -5.076930 0.502960 +v -1.236883 -5.475881 0.517533 +v -1.470344 -5.382164 0.513498 +v -1.703806 -5.288448 0.509463 +v -1.937267 -5.194733 0.505428 +v -2.170728 -5.101017 0.501393 +v -2.404190 -5.007302 0.497358 +v -2.637651 -4.913586 0.493323 +v -1.073261 -5.406252 0.511930 +v -1.306722 -5.312536 0.507895 +v -1.540184 -5.218821 0.503860 +v -1.773645 -5.125105 0.499825 +v -2.007106 -5.031389 0.495791 +v -2.240568 -4.937673 0.491756 +v -2.474029 -4.843958 0.487721 +v -2.707490 -4.750243 0.483686 +v -0.909639 -5.336624 0.506329 +v -1.143100 -5.242908 0.502294 +v -1.376562 -5.149193 0.498259 +v -1.610023 -5.055477 0.494224 +v -1.843484 -4.961761 0.490189 +v -2.076945 -4.868045 0.486154 +v -2.310407 -4.774330 0.482119 +v -2.543869 -4.680614 0.478084 +v -2.777330 -4.586899 0.474049 +v -0.746017 -5.266996 0.500726 +v -0.979478 -5.173281 0.496691 +v -1.212940 -5.079565 0.492656 +v -1.446401 -4.985850 0.488621 +v -1.679862 -4.892134 0.484586 +v -1.913324 -4.798418 0.480551 +v -2.146785 -4.704702 0.476516 +v -2.380247 -4.610986 0.472481 +v -2.613708 -4.517271 0.468446 +v -2.847169 -4.423555 0.464411 +v -0.582395 -5.197369 0.495124 +v -0.815856 -5.103653 0.491089 +v -1.049317 -5.009937 0.487054 +v -1.282779 -4.916221 0.483019 +v -1.516240 -4.822505 0.478984 +v -1.749701 -4.728789 0.474949 +v -1.983163 -4.635074 0.470914 +v -2.216624 -4.541358 0.466880 +v -2.450086 -4.447642 0.462845 +v -2.683547 -4.353927 0.458810 +v -2.917009 -4.260211 0.454775 +v -0.418772 -5.127741 0.489522 +v -0.652234 -5.034025 0.485487 +v -0.885695 -4.940310 0.481452 +v -1.119157 -4.846593 0.477417 +v -1.352618 -4.752878 0.473382 +v -1.586080 -4.659162 0.469347 +v -1.819541 -4.565446 0.465312 +v -2.053002 -4.471730 0.461277 +v -2.286463 -4.378014 0.457242 +v -2.519925 -4.284298 0.453207 +v -2.753386 -4.190583 0.449172 +v -2.986848 -4.096868 0.445138 +v -0.255151 -5.058113 0.483920 +v -0.488612 -4.964397 0.479885 +v -0.722073 -4.870682 0.475850 +v -0.955535 -4.776966 0.471815 +v -1.188996 -4.683250 0.467780 +v -1.422458 -4.589534 0.463745 +v -1.655919 -4.495819 0.459710 +v -1.889380 -4.402102 0.455675 +v -2.122842 -4.308386 0.451640 +v -2.356303 -4.214671 0.447605 +v -2.589765 -4.120955 0.443570 +v -2.823226 -4.027239 0.439535 +v -3.056687 -3.933524 0.435500 +v -0.091529 -4.988485 0.478318 +v -0.324990 -4.894770 0.474283 +v -0.558451 -4.801054 0.470248 +v -0.791913 -4.707338 0.466213 +v -1.025374 -4.613622 0.462178 +v -1.258836 -4.519907 0.458143 +v -1.492297 -4.426191 0.454108 +v -1.725758 -4.332475 0.450073 +v -1.959220 -4.238759 0.446038 +v -2.192681 -4.145043 0.442003 +v -2.426142 -4.051328 0.437968 +v -2.659604 -3.957612 0.433933 +v -2.893065 -3.863896 0.429899 +v -3.126527 -3.770180 0.425864 +v 0.072093 -4.918858 0.472716 +v -0.161368 -4.825142 0.468681 +v -0.394830 -4.731426 0.464646 +v -0.628291 -4.637710 0.460611 +v -0.861752 -4.543994 0.456576 +v -1.095214 -4.450279 0.452541 +v -1.328675 -4.356562 0.448506 +v -1.562136 -4.262847 0.444471 +v -1.795598 -4.169131 0.440436 +v -2.029059 -4.075416 0.436401 +v -2.262521 -3.981699 0.432366 +v -2.495982 -3.887984 0.428331 +v -2.729443 -3.794269 0.424296 +v -2.962905 -3.700552 0.420261 +v -3.196366 -3.606837 0.416226 +v 0.235715 -4.849230 0.467114 +v 0.002254 -4.755514 0.463079 +v -0.231208 -4.661798 0.459044 +v -0.464669 -4.568082 0.455009 +v -0.698130 -4.474367 0.450974 +v -0.931592 -4.380651 0.446939 +v -1.165053 -4.286934 0.442904 +v -1.398514 -4.193219 0.438869 +v -1.631976 -4.099504 0.434834 +v -1.865437 -4.005788 0.430799 +v -2.098898 -3.912072 0.426764 +v -2.332360 -3.818356 0.422729 +v -2.565821 -3.724640 0.418694 +v -2.799283 -3.630925 0.414659 +v -3.032744 -3.537209 0.410624 +v -3.266205 -3.443493 0.406589 +v 0.399337 -4.779602 0.461512 +v 0.165876 -4.685886 0.457477 +v -0.067586 -4.592171 0.453442 +v -0.301047 -4.498455 0.449407 +v -0.534508 -4.404739 0.445372 +v -0.767970 -4.311023 0.441337 +v -1.001431 -4.217307 0.437302 +v -1.234892 -4.123591 0.433267 +v -1.468354 -4.029876 0.429232 +v -1.701815 -3.936160 0.425197 +v -1.935277 -3.842444 0.421162 +v -2.168738 -3.748729 0.417127 +v -2.402199 -3.655013 0.413092 +v -2.635661 -3.561297 0.409057 +v -2.869122 -3.467582 0.405022 +v -3.102583 -3.373866 0.400987 +v -3.336045 -3.280150 0.396952 +v 0.562959 -4.709974 0.455910 +v 0.329498 -4.616258 0.451875 +v 0.096036 -4.522543 0.447840 +v -0.137425 -4.428827 0.443805 +v -0.370887 -4.335111 0.439770 +v -0.604348 -4.241395 0.435735 +v -0.837809 -4.147679 0.431700 +v -1.071271 -4.053964 0.427665 +v -1.304732 -3.960248 0.423630 +v -1.538193 -3.866532 0.419595 +v -1.771655 -3.772816 0.415560 +v -2.005116 -3.679101 0.411525 +v -2.238577 -3.585385 0.407490 +v -2.472039 -3.491669 0.403455 +v -2.705500 -3.397954 0.399420 +v -2.938962 -3.304238 0.395385 +v -3.172423 -3.210522 0.391350 +v -3.405884 -3.116806 0.387315 +v 0.726581 -4.640347 0.450308 +v 0.493120 -4.546630 0.446273 +v 0.259658 -4.452915 0.442238 +v 0.026197 -4.359199 0.438203 +v -0.207264 -4.265483 0.434168 +v -0.440726 -4.171768 0.430133 +v -0.674187 -4.078052 0.426098 +v -0.907648 -3.984335 0.422063 +v -1.141110 -3.890620 0.418028 +v -1.374571 -3.796905 0.413993 +v -1.608033 -3.703188 0.409958 +v -1.841494 -3.609473 0.405923 +v -2.074955 -3.515757 0.401888 +v -2.308417 -3.422041 0.397853 +v -2.541878 -3.328326 0.393818 +v -2.775339 -3.234610 0.389783 +v -3.008801 -3.140894 0.385748 +v -3.242262 -3.047179 0.381713 +v -3.475723 -2.953463 0.377678 +v 0.890203 -4.570719 0.444706 +v 0.656742 -4.477002 0.440671 +v 0.423280 -4.383287 0.436636 +v 0.189819 -4.289571 0.432601 +v -0.043642 -4.195856 0.428566 +v -0.277104 -4.102139 0.424531 +v -0.510565 -4.008424 0.420496 +v -0.744026 -3.914708 0.416461 +v -0.977488 -3.820992 0.412426 +v -1.210949 -3.727276 0.408391 +v -1.444410 -3.633561 0.404356 +v -1.677872 -3.539845 0.400321 +v -1.911333 -3.446129 0.396286 +v -2.144794 -3.352414 0.392251 +v -2.378256 -3.258698 0.388216 +v -2.611717 -3.164982 0.384181 +v -2.845179 -3.071266 0.380146 +v -3.078640 -2.977550 0.376111 +v -3.312101 -2.883835 0.372076 +v -3.545563 -2.790119 0.368041 +v 1.053825 -4.501091 0.439104 +v 0.820364 -4.407374 0.435069 +v 0.586903 -4.313660 0.431034 +v 0.353441 -4.219944 0.426999 +v 0.119980 -4.126228 0.422964 +v -0.113482 -4.032512 0.418929 +v -0.346943 -3.938796 0.414894 +v -0.580405 -3.845080 0.410859 +v -0.813866 -3.751364 0.406824 +v -1.047327 -3.657649 0.402789 +v -1.280789 -3.563933 0.398754 +v -1.514250 -3.470217 0.394719 +v -1.747711 -3.376501 0.390684 +v -1.981173 -3.282785 0.386649 +v -2.214634 -3.189070 0.382614 +v -2.448095 -3.095354 0.378579 +v -2.681557 -3.001638 0.374544 +v -2.915018 -2.907923 0.370509 +v -3.148480 -2.814207 0.366474 +v -3.381941 -2.720491 0.362439 +v -3.615402 -2.626775 0.358404 +v 1.217447 -4.431463 0.433502 +v 0.983986 -4.337747 0.429467 +v 0.750524 -4.244032 0.425432 +v 0.517063 -4.150316 0.421397 +v 0.283602 -4.056600 0.417362 +v 0.050140 -3.962884 0.413327 +v -0.183321 -3.869168 0.409292 +v -0.416783 -3.775452 0.405257 +v -0.650244 -3.681736 0.401222 +v -0.883705 -3.588021 0.397187 +v -1.117167 -3.494305 0.393152 +v -1.350628 -3.400589 0.389117 +v -1.584089 -3.306873 0.385082 +v -1.817551 -3.213157 0.381047 +v -2.051012 -3.119442 0.377012 +v -2.284473 -3.025727 0.372977 +v -2.517935 -2.932010 0.368942 +v -2.751396 -2.838295 0.364907 +v -2.984857 -2.744579 0.360872 +v -3.218319 -2.650863 0.356837 +v -3.451780 -2.557148 0.352802 +v -3.685241 -2.463431 0.348767 +v 1.381069 -4.361835 0.427900 +v 1.147608 -4.268119 0.423865 +v 0.914147 -4.174404 0.419830 +v 0.680685 -4.080688 0.415795 +v 0.447224 -3.986972 0.411760 +v 0.213762 -3.893256 0.407725 +v -0.019699 -3.799540 0.403690 +v -0.253161 -3.705824 0.399655 +v -0.486622 -3.612109 0.395620 +v -0.720084 -3.518393 0.391585 +v -0.953545 -3.424677 0.387550 +v -1.187006 -3.330961 0.383515 +v -1.420467 -3.237246 0.379480 +v -1.653929 -3.143530 0.375445 +v -1.887390 -3.049814 0.371410 +v -2.120852 -2.956098 0.367375 +v -2.354313 -2.862382 0.363340 +v -2.587774 -2.768667 0.359305 +v -2.821235 -2.674951 0.355270 +v -3.054697 -2.581235 0.351235 +v -3.288158 -2.487519 0.347200 +v -3.521620 -2.393804 0.343165 +v -3.755081 -2.300088 0.339130 +v 1.544691 -4.292208 0.422298 +v 1.311230 -4.198491 0.418263 +v 1.077768 -4.104776 0.414228 +v 0.844307 -4.011060 0.410193 +v 0.610846 -3.917344 0.406158 +v 0.377384 -3.823628 0.402123 +v 0.143923 -3.729912 0.398088 +v -0.089539 -3.636197 0.394053 +v -0.323000 -3.542481 0.390018 +v -0.556461 -3.448765 0.385983 +v -0.789923 -3.355049 0.381948 +v -1.023384 -3.261333 0.377913 +v -1.256845 -3.167618 0.373878 +v -1.490307 -3.073902 0.369843 +v -1.723768 -2.980186 0.365808 +v -1.957229 -2.886470 0.361773 +v -2.190691 -2.792754 0.357738 +v -2.424152 -2.699039 0.353703 +v -2.657614 -2.605323 0.349668 +v -2.891075 -2.511607 0.345633 +v -3.124536 -2.417892 0.341598 +v -3.357998 -2.324176 0.337563 +v -3.591459 -2.230460 0.333528 +v -3.824920 -2.136744 0.329493 +v 1.708313 -4.222580 0.416696 +v 1.474852 -4.128863 0.412661 +v 1.241390 -4.035148 0.408626 +v 1.007929 -3.941432 0.404591 +v 0.774468 -3.847716 0.400556 +v 0.541006 -3.754000 0.396521 +v 0.307545 -3.660285 0.392486 +v 0.074084 -3.566569 0.388451 +v -0.159378 -3.472853 0.384416 +v -0.392839 -3.379137 0.380381 +v -0.626301 -3.285421 0.376346 +v -0.859762 -3.191705 0.372311 +v -1.093223 -3.097989 0.368276 +v -1.326685 -3.004274 0.364241 +v -1.560146 -2.910558 0.360206 +v -1.793607 -2.816843 0.356171 +v -2.027069 -2.723127 0.352136 +v -2.260530 -2.629411 0.348101 +v -2.493991 -2.535695 0.344066 +v -2.727453 -2.441979 0.340031 +v -2.960914 -2.348264 0.335996 +v -3.194375 -2.254548 0.331961 +v -3.427837 -2.160832 0.327926 +v -3.661298 -2.067116 0.323891 +v -3.894759 -1.973400 0.319856 +v 1.871935 -4.152952 0.411094 +v 1.638474 -4.059236 0.407059 +v 1.405012 -3.965520 0.403024 +v 1.171551 -3.871805 0.398989 +v 0.938090 -3.778089 0.394954 +v 0.704628 -3.684372 0.390919 +v 0.471167 -3.590657 0.386884 +v 0.237706 -3.496941 0.382849 +v 0.004244 -3.403225 0.378814 +v -0.229217 -3.309509 0.374779 +v -0.462679 -3.215794 0.370744 +v -0.696140 -3.122078 0.366709 +v -0.929602 -3.028362 0.362674 +v -1.163063 -2.934646 0.358639 +v -1.396524 -2.840931 0.354604 +v -1.629985 -2.747215 0.350569 +v -1.863447 -2.653499 0.346534 +v -2.096908 -2.559783 0.342499 +v -2.330369 -2.466068 0.338464 +v -2.563831 -2.372352 0.334429 +v -2.797292 -2.278636 0.330394 +v -3.030753 -2.184920 0.326359 +v -3.264215 -2.091204 0.322324 +v -3.497676 -1.997488 0.318289 +v -3.731138 -1.903773 0.314254 +v -3.964599 -1.810057 0.310219 +v 2.035557 -4.083324 0.405492 +v 1.802096 -3.989609 0.401457 +v 1.568634 -3.895892 0.397422 +v 1.335173 -3.802177 0.393387 +v 1.101712 -3.708461 0.389352 +v 0.868250 -3.614745 0.385317 +v 0.634789 -3.521029 0.381282 +v 0.401328 -3.427313 0.377247 +v 0.167866 -3.333597 0.373212 +v -0.065595 -3.239882 0.369177 +v -0.299057 -3.146165 0.365142 +v -0.532518 -3.052450 0.361107 +v -0.765979 -2.958734 0.357072 +v -0.999441 -2.865018 0.353036 +v -1.232902 -2.771303 0.349001 +v -1.466363 -2.677587 0.344966 +v -1.699825 -2.583871 0.340932 +v -1.933286 -2.490155 0.336897 +v -2.166747 -2.396440 0.332862 +v -2.400209 -2.302724 0.328827 +v -2.633670 -2.209008 0.324792 +v -2.867131 -2.115292 0.320757 +v -3.100593 -2.021576 0.316722 +v -3.334054 -1.927860 0.312687 +v -3.567516 -1.834145 0.308652 +v -3.800977 -1.740429 0.304617 +v -4.034438 -1.646713 0.300582 +v 2.199179 -4.013697 0.399889 +v 1.965718 -3.919981 0.395854 +v 1.732256 -3.826265 0.391819 +v 1.498795 -3.732549 0.387784 +v 1.265334 -3.638833 0.383749 +v 1.031872 -3.545117 0.379714 +v 0.798411 -3.451401 0.375679 +v 0.564950 -3.357686 0.371644 +v 0.331488 -3.263969 0.367610 +v 0.098027 -3.170254 0.363575 +v -0.135435 -3.076538 0.359540 +v -0.368896 -2.982822 0.355505 +v -0.602357 -2.889106 0.351470 +v -0.835819 -2.795390 0.347435 +v -1.069280 -2.701675 0.343400 +v -1.302741 -2.607959 0.339365 +v -1.536203 -2.514243 0.335330 +v -1.769664 -2.420527 0.331295 +v -2.003125 -2.326812 0.327260 +v -2.236587 -2.233096 0.323225 +v -2.470048 -2.139380 0.319190 +v -2.703509 -2.045664 0.315155 +v -2.936971 -1.951948 0.311120 +v -3.170432 -1.858232 0.307085 +v -3.403893 -1.764517 0.303050 +v -3.637355 -1.670801 0.299015 +v -3.870816 -1.577085 0.294980 +v -4.104278 -1.483369 0.290945 +v 2.362801 -3.944069 0.394287 +v 2.129340 -3.850353 0.390253 +v 1.895878 -3.756637 0.386218 +v 1.662417 -3.662921 0.382183 +v 1.428956 -3.569205 0.378148 +v 1.195494 -3.475489 0.374113 +v 0.962033 -3.381773 0.370078 +v 0.728572 -3.288058 0.366043 +v 0.495110 -3.194342 0.362008 +v 0.261649 -3.100626 0.357973 +v 0.028187 -3.006910 0.353938 +v -0.205274 -2.913194 0.349903 +v -0.438735 -2.819478 0.345867 +v -0.672197 -2.725763 0.341832 +v -0.905658 -2.632047 0.337797 +v -1.139120 -2.538331 0.333762 +v -1.372581 -2.444616 0.329727 +v -1.606042 -2.350899 0.325692 +v -1.839504 -2.257183 0.321657 +v -2.072965 -2.163467 0.317622 +v -2.306426 -2.069752 0.313587 +v -2.539887 -1.976036 0.309552 +v -2.773349 -1.882320 0.305517 +v -3.006810 -1.788605 0.301483 +v -3.240271 -1.694889 0.297448 +v -3.473733 -1.601173 0.293413 +v -3.707194 -1.507457 0.289378 +v -3.940656 -1.413742 0.285343 +v -4.174116 -1.320026 0.281308 +v 2.526423 -3.874441 0.388685 +v 2.292962 -3.780725 0.384650 +v 2.059500 -3.687009 0.380615 +v 1.826039 -3.593294 0.376580 +v 1.592578 -3.499577 0.372545 +v 1.359116 -3.405861 0.368510 +v 1.125655 -3.312146 0.364475 +v 0.892194 -3.218430 0.360440 +v 0.658732 -3.124714 0.356405 +v 0.425271 -3.030998 0.352371 +v 0.191809 -2.937282 0.348336 +v -0.041652 -2.843566 0.344300 +v -0.275113 -2.749850 0.340265 +v -0.508575 -2.656135 0.336230 +v -0.742036 -2.562419 0.332195 +v -0.975497 -2.468703 0.328160 +v -1.208959 -2.374988 0.324125 +v -1.442420 -2.281271 0.320090 +v -1.675881 -2.187556 0.316055 +v -1.909343 -2.093840 0.312021 +v -2.142804 -2.000124 0.307986 +v -2.376266 -1.906408 0.303951 +v -2.609727 -1.812692 0.299916 +v -2.843188 -1.718977 0.295881 +v -3.076649 -1.625261 0.291846 +v -3.310111 -1.531545 0.287811 +v -3.543572 -1.437829 0.283776 +v -3.777034 -1.344114 0.279741 +v -4.010494 -1.250398 0.275706 +v -4.243956 -1.156682 0.271671 +v 2.690045 -3.804814 0.383083 +v 2.456584 -3.711097 0.379048 +v 2.223123 -3.617381 0.375013 +v 1.989661 -3.523665 0.370978 +v 1.756200 -3.429949 0.366943 +v 1.522738 -3.336234 0.362908 +v 1.289277 -3.242518 0.358873 +v 1.055816 -3.148802 0.354838 +v 0.822354 -3.055086 0.350803 +v 0.588893 -2.961370 0.346768 +v 0.355431 -2.867654 0.342733 +v 0.121970 -2.773938 0.338698 +v -0.111491 -2.680223 0.334663 +v -0.344953 -2.586506 0.330628 +v -0.578414 -2.492791 0.326593 +v -0.811875 -2.399075 0.322558 +v -1.045337 -2.305359 0.318523 +v -1.278798 -2.211644 0.314488 +v -1.512259 -2.117928 0.310453 +v -1.745721 -2.024212 0.306418 +v -1.979182 -1.930496 0.302383 +v -2.212643 -1.836780 0.298348 +v -2.446105 -1.743064 0.294313 +v -2.679566 -1.649349 0.290278 +v -2.913028 -1.555633 0.286243 +v -3.146489 -1.461917 0.282208 +v -3.379950 -1.368201 0.278173 +v -3.613411 -1.274486 0.274138 +v -3.846873 -1.180770 0.270103 +v -4.080334 -1.087054 0.266068 +v -4.313795 -0.993338 0.262033 +v 2.853667 -3.735186 0.377481 +v 2.620206 -3.641469 0.373446 +v 2.386744 -3.547754 0.369411 +v 2.153283 -3.454038 0.365376 +v 1.919822 -3.360322 0.361341 +v 1.686360 -3.266606 0.357306 +v 1.452899 -3.172890 0.353271 +v 1.219437 -3.079174 0.349236 +v 0.985976 -2.985458 0.345201 +v 0.752515 -2.891742 0.341166 +v 0.519053 -2.798027 0.337131 +v 0.285592 -2.704310 0.333096 +v 0.052131 -2.610595 0.329061 +v -0.181331 -2.516879 0.325026 +v -0.414792 -2.423163 0.320991 +v -0.648253 -2.329447 0.316956 +v -0.881715 -2.235731 0.312921 +v -1.115176 -2.142015 0.308886 +v -1.348638 -2.048300 0.304851 +v -1.582099 -1.954584 0.300816 +v -1.815560 -1.860868 0.296781 +v -2.049021 -1.767152 0.292746 +v -2.282483 -1.673437 0.288711 +v -2.515944 -1.579721 0.284676 +v -2.749406 -1.486005 0.280641 +v -2.982867 -1.392290 0.276606 +v -3.216328 -1.298574 0.272572 +v -3.449790 -1.204858 0.268537 +v -3.683251 -1.111142 0.264502 +v -3.916712 -1.017426 0.260467 +v -4.150173 -0.923711 0.256432 +v -4.383635 -0.829995 0.252397 +v 3.017289 -3.665558 0.371879 +v 2.783828 -3.571841 0.367844 +v 2.550366 -3.478126 0.363809 +v 2.316905 -3.384410 0.359774 +v 2.083444 -3.290694 0.355739 +v 1.849982 -3.196978 0.351704 +v 1.616521 -3.103262 0.347669 +v 1.383060 -3.009546 0.343634 +v 1.149598 -2.915830 0.339599 +v 0.916137 -2.822114 0.335564 +v 0.682675 -2.728399 0.331529 +v 0.449214 -2.634683 0.327494 +v 0.215753 -2.540967 0.323459 +v -0.017709 -2.447251 0.319424 +v -0.251170 -2.353535 0.315389 +v -0.484631 -2.259820 0.311354 +v -0.718093 -2.166104 0.307319 +v -0.951554 -2.072388 0.303284 +v -1.185016 -1.978672 0.299249 +v -1.418477 -1.884956 0.295214 +v -1.651938 -1.791241 0.291179 +v -1.885400 -1.697525 0.287144 +v -2.118861 -1.603809 0.283109 +v -2.352322 -1.510093 0.279074 +v -2.585784 -1.416377 0.275039 +v -2.819245 -1.322662 0.271004 +v -3.052706 -1.228946 0.266969 +v -3.286168 -1.135230 0.262934 +v -3.519629 -1.041514 0.258899 +v -3.753090 -0.947798 0.254864 +v -3.986552 -0.854083 0.250829 +v -4.220013 -0.760367 0.246794 +v -4.453474 -0.666651 0.242759 +v 3.180911 -3.595930 0.366277 +v 2.947450 -3.502214 0.362242 +v 2.713988 -3.408498 0.358207 +v 2.480527 -3.314782 0.354172 +v 2.247066 -3.221066 0.350137 +v 2.013604 -3.127350 0.346102 +v 1.780143 -3.033635 0.342067 +v 1.546681 -2.939919 0.338032 +v 1.313220 -2.846202 0.333997 +v 1.079759 -2.752487 0.329962 +v 0.846297 -2.658771 0.325927 +v 0.612836 -2.565055 0.321892 +v 0.379375 -2.471339 0.317857 +v 0.145913 -2.377623 0.313822 +v -0.087548 -2.283908 0.309787 +v -0.321009 -2.190192 0.305752 +v -0.554471 -2.096476 0.301717 +v -0.787932 -2.002760 0.297682 +v -1.021394 -1.909044 0.293647 +v -1.254855 -1.815328 0.289612 +v -1.488316 -1.721613 0.285577 +v -1.721778 -1.627897 0.281542 +v -1.955239 -1.534181 0.277507 +v -2.188700 -1.440465 0.273472 +v -2.422162 -1.346750 0.269437 +v -2.655623 -1.253034 0.265402 +v -2.889084 -1.159318 0.261367 +v -3.122546 -1.065602 0.257332 +v -3.356007 -0.971886 0.253297 +v -3.589468 -0.878170 0.249262 +v -3.822929 -0.784455 0.245227 +v -4.056391 -0.690739 0.241192 +v -4.289852 -0.597024 0.237157 +v -4.523314 -0.503308 0.233122 +v 3.344533 -3.526303 0.360675 +v 3.111072 -3.432586 0.356640 +v 2.877610 -3.338870 0.352605 +v 2.644149 -3.245154 0.348570 +v 2.410687 -3.151438 0.344535 +v 2.177226 -3.057723 0.340500 +v 1.943765 -2.964007 0.336465 +v 1.710303 -2.870291 0.332430 +v 1.476842 -2.776575 0.328395 +v 1.243381 -2.682859 0.324360 +v 1.009919 -2.589143 0.320325 +v 0.776458 -2.495427 0.316290 +v 0.542997 -2.401711 0.312255 +v 0.309535 -2.307995 0.308220 +v 0.076074 -2.214280 0.304185 +v -0.157387 -2.120564 0.300150 +v -0.390849 -2.026848 0.296115 +v -0.624310 -1.933132 0.292080 +v -0.857772 -1.839417 0.288045 +v -1.091233 -1.745700 0.284010 +v -1.324694 -1.651985 0.279975 +v -1.558156 -1.558269 0.275940 +v -1.791617 -1.464553 0.271905 +v -2.025078 -1.370837 0.267870 +v -2.258540 -1.277122 0.263835 +v -2.492001 -1.183406 0.259800 +v -2.725462 -1.089690 0.255765 +v -2.958924 -0.995974 0.251730 +v -3.192385 -0.902259 0.247695 +v -3.425846 -0.808543 0.243660 +v -3.659307 -0.714827 0.239625 +v -3.892769 -0.621111 0.235590 +v -4.126230 -0.527396 0.231555 +v -4.359692 -0.433680 0.227520 +v -4.593153 -0.339964 0.223485 +v 3.508155 -3.456674 0.355073 +v 3.274693 -3.362958 0.351038 +v 3.041232 -3.269243 0.347003 +v 2.807771 -3.175527 0.342968 +v 2.574309 -3.081810 0.338933 +v 2.340848 -2.988095 0.334898 +v 2.107387 -2.894379 0.330863 +v 1.873925 -2.800663 0.326828 +v 1.640464 -2.706947 0.322793 +v 1.407002 -2.613231 0.318758 +v 1.173541 -2.519516 0.314723 +v 0.940080 -2.425799 0.310688 +v 0.706618 -2.332083 0.306653 +v 0.473157 -2.238368 0.302618 +v 0.239696 -2.144652 0.298583 +v 0.006234 -2.050936 0.294548 +v -0.227227 -1.957220 0.290513 +v -0.460688 -1.863505 0.286478 +v -0.694150 -1.769789 0.282443 +v -0.927611 -1.676073 0.278408 +v -1.161072 -1.582357 0.274373 +v -1.394534 -1.488641 0.270338 +v -1.627995 -1.394925 0.266303 +v -1.861456 -1.301210 0.262268 +v -2.094918 -1.207494 0.258233 +v -2.328379 -1.113778 0.254198 +v -2.561840 -1.020062 0.250163 +v -2.795302 -0.926347 0.246128 +v -3.028763 -0.832631 0.242093 +v -3.262224 -0.738915 0.238058 +v -3.495686 -0.645199 0.234023 +v -3.729147 -0.551483 0.229988 +v -3.962608 -0.457768 0.225953 +v -4.196070 -0.364052 0.221918 +v -4.429531 -0.270336 0.217883 +v -4.662992 -0.176620 0.213848 +v 3.671777 -3.387047 0.349471 +v 3.438316 -3.293330 0.345436 +v 3.204854 -3.199615 0.341401 +v 2.971393 -3.105899 0.337366 +v 2.737931 -3.012183 0.333331 +v 2.504470 -2.918467 0.329296 +v 2.271009 -2.824751 0.325261 +v 2.037547 -2.731035 0.321226 +v 1.804086 -2.637319 0.317191 +v 1.570624 -2.543603 0.313156 +v 1.337163 -2.449888 0.309121 +v 1.103702 -2.356172 0.305086 +v 0.870240 -2.262455 0.301051 +v 0.636779 -2.168740 0.297016 +v 0.403318 -2.075024 0.292981 +v 0.169856 -1.981308 0.288946 +v -0.063605 -1.887592 0.284911 +v -0.297066 -1.793877 0.280876 +v -0.530528 -1.700161 0.276841 +v -0.763989 -1.606445 0.272806 +v -0.997450 -1.512729 0.268771 +v -1.230912 -1.419013 0.264736 +v -1.464373 -1.325298 0.260701 +v -1.697834 -1.231582 0.256666 +v -1.931295 -1.137866 0.252631 +v -2.164757 -1.044150 0.248596 +v -2.398218 -0.950434 0.244561 +v -2.631680 -0.856719 0.240526 +v -2.865141 -0.763003 0.236491 +v -3.098603 -0.669287 0.232456 +v -3.332064 -0.575571 0.228421 +v -3.565525 -0.481856 0.224386 +v -3.798986 -0.388140 0.220351 +v -4.032447 -0.294424 0.216316 +v -4.265909 -0.200708 0.212281 +v -4.499370 -0.106993 0.208246 +v -4.732831 -0.013277 0.204211 +v 3.835399 -3.317418 0.343869 +v 3.601938 -3.223703 0.339834 +v 3.368476 -3.129987 0.335799 +v 3.135015 -3.036271 0.331764 +v 2.901554 -2.942555 0.327729 +v 2.668092 -2.848839 0.323694 +v 2.434631 -2.755123 0.319659 +v 2.201169 -2.661407 0.315624 +v 1.967708 -2.567691 0.311589 +v 1.734246 -2.473976 0.307554 +v 1.500785 -2.380260 0.303519 +v 1.267324 -2.286544 0.299484 +v 1.033862 -2.192828 0.295449 +v 0.800401 -2.099112 0.291414 +v 0.566940 -2.005396 0.287379 +v 0.333478 -1.911680 0.283344 +v 0.100017 -1.817965 0.279309 +v -0.133444 -1.724249 0.275274 +v -0.366906 -1.630533 0.271239 +v -0.600367 -1.536817 0.267204 +v -0.833828 -1.443102 0.263169 +v -1.067290 -1.349386 0.259134 +v -1.300751 -1.255670 0.255099 +v -1.534212 -1.161954 0.251064 +v -1.767674 -1.068238 0.247029 +v -2.001135 -0.974522 0.242994 +v -2.234596 -0.880807 0.238959 +v -2.468058 -0.787091 0.234924 +v -2.701519 -0.693375 0.230889 +v -2.934980 -0.599659 0.226854 +v -3.168442 -0.505944 0.222819 +v -3.401903 -0.412228 0.218784 +v -3.635364 -0.318512 0.214749 +v -3.868825 -0.224796 0.210714 +v -4.102286 -0.131081 0.206679 +v -4.335748 -0.037365 0.202644 +v -4.569209 0.056351 0.198609 +v -4.802670 0.150067 0.194574 +v 3.999021 -3.247791 0.338267 +v 3.765560 -3.154075 0.334232 +v 3.532098 -3.060359 0.330197 +v 3.298637 -2.966643 0.326162 +v 3.065176 -2.872927 0.322127 +v 2.831714 -2.779212 0.318092 +v 2.598253 -2.685495 0.314057 +v 2.364791 -2.591780 0.310022 +v 2.131330 -2.498064 0.305987 +v 1.897868 -2.404348 0.301952 +v 1.664407 -2.310632 0.297917 +v 1.430946 -2.216916 0.293882 +v 1.197484 -2.123200 0.289847 +v 0.964023 -2.029484 0.285812 +v 0.730562 -1.935768 0.281777 +v 0.497100 -1.842052 0.277742 +v 0.263639 -1.748337 0.273707 +v 0.030178 -1.654621 0.269672 +v -0.203284 -1.560905 0.265637 +v -0.436745 -1.467189 0.261602 +v -0.670206 -1.373474 0.257567 +v -0.903668 -1.279758 0.253532 +v -1.137129 -1.186042 0.249497 +v -1.370590 -1.092326 0.245462 +v -1.604052 -0.998610 0.241427 +v -1.837513 -0.904895 0.237392 +v -2.070974 -0.811179 0.233357 +v -2.304435 -0.717463 0.229322 +v -2.537897 -0.623747 0.225287 +v -2.771358 -0.530031 0.221252 +v -3.004820 -0.436316 0.217217 +v -3.238281 -0.342600 0.213182 +v -3.471742 -0.248884 0.209147 +v -3.705204 -0.155168 0.205112 +v -3.938665 -0.061453 0.201077 +v -4.172126 0.032263 0.197042 +v -4.405587 0.125979 0.193007 +v -4.639049 0.219695 0.188972 +v -4.872510 0.313411 0.184937 +v 4.162643 -3.178163 0.332665 +v 3.929182 -3.084447 0.328630 +v 3.695721 -2.990731 0.324595 +v 3.462259 -2.897015 0.320560 +v 3.228797 -2.803299 0.316525 +v 2.995336 -2.709584 0.312490 +v 2.761875 -2.615868 0.308455 +v 2.528413 -2.522151 0.304420 +v 2.294952 -2.428436 0.300385 +v 2.061491 -2.334720 0.296350 +v 1.828029 -2.241004 0.292315 +v 1.594568 -2.147288 0.288280 +v 1.361106 -2.053572 0.284245 +v 1.127645 -1.959856 0.280210 +v 0.894184 -1.866141 0.276175 +v 0.660722 -1.772425 0.272140 +v 0.427261 -1.678709 0.268105 +v 0.193800 -1.584993 0.264070 +v -0.039662 -1.491277 0.260035 +v -0.273123 -1.397561 0.256000 +v -0.506584 -1.303846 0.251965 +v -0.740046 -1.210130 0.247930 +v -0.973507 -1.116414 0.243895 +v -1.206968 -1.022698 0.239860 +v -1.440430 -0.928983 0.235825 +v -1.673891 -0.835267 0.231790 +v -1.907352 -0.741551 0.227755 +v -2.140813 -0.647835 0.223720 +v -2.374275 -0.554119 0.219685 +v -2.607736 -0.460404 0.215650 +v -2.841197 -0.366688 0.211615 +v -3.074659 -0.272972 0.207580 +v -3.308120 -0.179256 0.203545 +v -3.541582 -0.085541 0.199510 +v -3.775043 0.008175 0.195475 +v -4.008504 0.101891 0.191440 +v -4.241965 0.195607 0.187405 +v -4.475427 0.289323 0.183370 +v -4.708888 0.383039 0.179335 +v -4.942349 0.476755 0.175300 +v 4.326265 -3.108535 0.327063 +v 4.092804 -3.014819 0.323028 +v 3.859343 -2.921103 0.318993 +v 3.625881 -2.827387 0.314958 +v 3.392420 -2.733672 0.310923 +v 3.158958 -2.639956 0.306888 +v 2.925497 -2.546240 0.302853 +v 2.692035 -2.452524 0.298818 +v 2.458574 -2.358808 0.294783 +v 2.225112 -2.265092 0.290748 +v 1.991651 -2.171377 0.286713 +v 1.758190 -2.077660 0.282678 +v 1.524728 -1.983944 0.278643 +v 1.291267 -1.890228 0.274608 +v 1.057806 -1.796513 0.270573 +v 0.824344 -1.702797 0.266538 +v 0.590883 -1.609081 0.262503 +v 0.357422 -1.515365 0.258468 +v 0.123960 -1.421649 0.254433 +v -0.109501 -1.327934 0.250398 +v -0.342962 -1.234218 0.246363 +v -0.576424 -1.140502 0.242328 +v -0.809885 -1.046786 0.238293 +v -1.043346 -0.953071 0.234258 +v -1.276808 -0.859355 0.230223 +v -1.510269 -0.765639 0.226188 +v -1.743730 -0.671923 0.222153 +v -1.977192 -0.578207 0.218118 +v -2.210653 -0.484491 0.214083 +v -2.444114 -0.390776 0.210048 +v -2.677576 -0.297060 0.206013 +v -2.911037 -0.203344 0.201978 +v -3.144498 -0.109628 0.197943 +v -3.377960 -0.015913 0.193908 +v -3.611421 0.077803 0.189873 +v -3.844882 0.171519 0.185838 +v -4.078343 0.265235 0.181803 +v -4.311805 0.358951 0.177768 +v -4.545266 0.452667 0.173733 +v -4.778728 0.546382 0.169698 +v -5.012189 0.640098 0.165663 +v 4.489887 -3.038907 0.321461 +v 4.256426 -2.945192 0.317426 +v 4.022964 -2.851475 0.313390 +v 3.789503 -2.757760 0.309355 +v 3.556042 -2.664043 0.305321 +v 3.322580 -2.570328 0.301286 +v 3.089119 -2.476612 0.297251 +v 2.855658 -2.382896 0.293216 +v 2.622196 -2.289180 0.289181 +v 2.388735 -2.195465 0.285146 +v 2.155273 -2.101748 0.281111 +v 1.921812 -2.008032 0.277076 +v 1.688350 -1.914317 0.273041 +v 1.454889 -1.820600 0.269006 +v 1.221428 -1.726885 0.264971 +v 0.987966 -1.633169 0.260936 +v 0.754505 -1.539453 0.256901 +v 0.521044 -1.445737 0.252866 +v 0.287582 -1.352022 0.248831 +v 0.054121 -1.258306 0.244796 +v -0.179340 -1.164590 0.240761 +v -0.412802 -1.070874 0.236726 +v -0.646263 -0.977158 0.232691 +v -0.879724 -0.883443 0.228656 +v -1.113186 -0.789727 0.224621 +v -1.346647 -0.696011 0.220586 +v -1.580108 -0.602295 0.216551 +v -1.813570 -0.508579 0.212516 +v -2.047031 -0.414864 0.208481 +v -2.280492 -0.321148 0.204446 +v -2.513954 -0.227432 0.200411 +v -2.747415 -0.133716 0.196376 +v -2.980876 -0.040001 0.192341 +v -3.214338 0.053715 0.188306 +v -3.447799 0.147431 0.184271 +v -3.681260 0.241147 0.180236 +v -3.914722 0.334863 0.176201 +v -4.148183 0.428579 0.172166 +v -4.381644 0.522295 0.168131 +v -4.615106 0.616011 0.164096 +v -4.848567 0.709726 0.160061 +v -5.082028 0.803442 0.156026 +v 4.653510 -2.969280 0.315859 +v 4.420048 -2.875564 0.311824 +v 4.186587 -2.781847 0.307789 +v 3.953125 -2.688132 0.303754 +v 3.719664 -2.594416 0.299719 +v 3.486202 -2.500700 0.295684 +v 3.252741 -2.406984 0.291649 +v 3.019279 -2.313268 0.287614 +v 2.785818 -2.219553 0.283579 +v 2.552357 -2.125836 0.279544 +v 2.318895 -2.032120 0.275509 +v 2.085434 -1.938404 0.271474 +v 1.851972 -1.844689 0.267439 +v 1.618511 -1.750973 0.263404 +v 1.385050 -1.657257 0.259369 +v 1.151588 -1.563541 0.255334 +v 0.918127 -1.469826 0.251299 +v 0.684666 -1.376110 0.247264 +v 0.451204 -1.282394 0.243229 +v 0.217743 -1.188678 0.239194 +v -0.015718 -1.094962 0.235159 +v -0.249180 -1.001246 0.231124 +v -0.482641 -0.907531 0.227089 +v -0.716102 -0.813815 0.223054 +v -0.949564 -0.720099 0.219019 +v -1.183025 -0.626383 0.214984 +v -1.416486 -0.532667 0.210949 +v -1.649948 -0.438952 0.206914 +v -1.883409 -0.345236 0.202879 +v -2.116870 -0.251520 0.198844 +v -2.350331 -0.157804 0.194809 +v -2.583793 -0.064088 0.190774 +v -2.817254 0.029627 0.186739 +v -3.050715 0.123343 0.182704 +v -3.284177 0.217059 0.178669 +v -3.517638 0.310775 0.174634 +v -3.751100 0.404491 0.170599 +v -3.984561 0.498207 0.166564 +v -4.218022 0.591923 0.162529 +v -4.451484 0.685638 0.158494 +v -4.684945 0.779354 0.154459 +v -4.918406 0.873070 0.150424 +v -5.151868 0.966786 0.146389 +v 4.817132 -2.899652 0.310257 +v 4.583670 -2.805936 0.306221 +v 4.350208 -2.712219 0.302186 +v 4.116747 -2.618504 0.298151 +v 3.883286 -2.524788 0.294116 +v 3.649824 -2.431072 0.290082 +v 3.416363 -2.337356 0.286047 +v 3.182901 -2.243640 0.282012 +v 2.949440 -2.149925 0.277977 +v 2.715979 -2.056208 0.273942 +v 2.482517 -1.962493 0.269907 +v 2.249056 -1.868777 0.265872 +v 2.015594 -1.775061 0.261837 +v 1.782133 -1.681345 0.257802 +v 1.548671 -1.587629 0.253767 +v 1.315210 -1.493914 0.249732 +v 1.081749 -1.400198 0.245697 +v 0.848288 -1.306482 0.241662 +v 0.614826 -1.212766 0.237627 +v 0.381365 -1.119050 0.233592 +v 0.147904 -1.025334 0.229557 +v -0.085558 -0.931619 0.225522 +v -0.319019 -0.837903 0.221487 +v -0.552480 -0.744187 0.217452 +v -0.785942 -0.650471 0.213417 +v -1.019403 -0.556755 0.209382 +v -1.252864 -0.463039 0.205347 +v -1.486326 -0.369324 0.201312 +v -1.719787 -0.275608 0.197277 +v -1.953248 -0.181892 0.193242 +v -2.186710 -0.088176 0.189207 +v -2.420171 0.005539 0.185172 +v -2.653632 0.099255 0.181137 +v -2.887094 0.192971 0.177102 +v -3.120555 0.286687 0.173067 +v -3.354016 0.380403 0.169032 +v -3.587478 0.474118 0.164997 +v -3.820939 0.567834 0.160962 +v -4.054400 0.661550 0.156927 +v -4.287862 0.755266 0.152892 +v -4.521323 0.848982 0.148857 +v -4.754785 0.942698 0.144822 +v -4.988246 1.036414 0.140787 +v -5.221706 1.130129 0.136752 +v 4.980753 -2.830024 0.304654 +v 4.747292 -2.736308 0.300619 +v 4.513830 -2.642592 0.296584 +v 4.280369 -2.548876 0.292549 +v 4.046907 -2.455160 0.288514 +v 3.813446 -2.361444 0.284479 +v 3.579985 -2.267728 0.280444 +v 3.346523 -2.174013 0.276409 +v 3.113062 -2.080297 0.272375 +v 2.879601 -1.986581 0.268340 +v 2.646139 -1.892865 0.264305 +v 2.412678 -1.799149 0.260270 +v 2.179216 -1.705433 0.256235 +v 1.945755 -1.611717 0.252200 +v 1.712294 -1.518002 0.248165 +v 1.478832 -1.424286 0.244130 +v 1.245371 -1.330570 0.240095 +v 1.011909 -1.236854 0.236060 +v 0.778448 -1.143138 0.232025 +v 0.544987 -1.049423 0.227990 +v 0.311526 -0.955707 0.223955 +v 0.078064 -0.861991 0.219920 +v -0.155397 -0.768275 0.215885 +v -0.388859 -0.674559 0.211850 +v -0.622320 -0.580843 0.207815 +v -0.855781 -0.487128 0.203780 +v -1.089242 -0.393412 0.199745 +v -1.322704 -0.299696 0.195710 +v -1.556165 -0.205980 0.191675 +v -1.789626 -0.112264 0.187640 +v -2.023088 -0.018548 0.183605 +v -2.256549 0.075167 0.179570 +v -2.490010 0.168883 0.175535 +v -2.723472 0.262599 0.171500 +v -2.956933 0.356315 0.167465 +v -3.190394 0.450030 0.163430 +v -3.423856 0.543746 0.159395 +v -3.657317 0.637462 0.155360 +v -3.890779 0.731178 0.151325 +v -4.124240 0.824894 0.147290 +v -4.357701 0.918610 0.143255 +v -4.591162 1.012325 0.139220 +v -4.824624 1.106042 0.135185 +v -5.058085 1.199757 0.131150 +v -5.291546 1.293473 0.127115 +v 5.144376 -2.760396 0.299052 +v 4.910913 -2.666680 0.295017 +v 4.677453 -2.572964 0.290982 +v 4.443991 -2.479249 0.286947 +v 4.210530 -2.385532 0.282912 +v 3.977068 -2.291817 0.278877 +v 3.743607 -2.198101 0.274843 +v 3.510145 -2.104385 0.270808 +v 3.276684 -2.010669 0.266773 +v 3.043222 -1.916953 0.262738 +v 2.809761 -1.823237 0.258703 +v 2.576299 -1.729521 0.254668 +v 2.342838 -1.635805 0.250633 +v 2.109377 -1.542089 0.246598 +v 1.875915 -1.448374 0.242563 +v 1.642454 -1.354658 0.238528 +v 1.408993 -1.260942 0.234493 +v 1.175532 -1.167226 0.230458 +v 0.942070 -1.073511 0.226423 +v 0.708609 -0.979795 0.222388 +v 0.475148 -0.886079 0.218353 +v 0.241686 -0.792363 0.214318 +v 0.008225 -0.698647 0.210283 +v -0.225236 -0.604931 0.206248 +v -0.458698 -0.511216 0.202213 +v -0.692159 -0.417500 0.198178 +v -0.925620 -0.323784 0.194143 +v -1.159082 -0.230068 0.190108 +v -1.392543 -0.136352 0.186073 +v -1.626004 -0.042636 0.182038 +v -1.859466 0.051079 0.178003 +v -2.092927 0.144795 0.173968 +v -2.326388 0.238511 0.169933 +v -2.559850 0.332227 0.165898 +v -2.793311 0.425943 0.161863 +v -3.026772 0.519658 0.157828 +v -3.260234 0.613374 0.153793 +v -3.493695 0.707090 0.149758 +v -3.727157 0.800806 0.145723 +v -3.960618 0.894522 0.141688 +v -4.194079 0.988238 0.137653 +v -4.427540 1.081954 0.133618 +v -4.661001 1.175669 0.129583 +v -4.894464 1.269385 0.125548 +v -5.127924 1.363101 0.121513 +v -5.361385 1.456817 0.117478 +v 5.307998 -2.690768 0.293450 +v 5.074536 -2.597052 0.289415 +v 4.841075 -2.503336 0.285380 +v 4.607614 -2.409621 0.281345 +v 4.374152 -2.315905 0.277310 +v 4.140691 -2.222188 0.273275 +v 3.907229 -2.128473 0.269240 +v 3.673767 -2.034757 0.265205 +v 3.440306 -1.941041 0.261170 +v 3.206845 -1.847325 0.257135 +v 2.973383 -1.753609 0.253100 +v 2.739922 -1.659893 0.249065 +v 2.506460 -1.566177 0.245030 +v 2.272999 -1.472462 0.240995 +v 2.039538 -1.378746 0.236960 +v 1.806076 -1.285030 0.232925 +v 1.572615 -1.191314 0.228890 +v 1.339153 -1.097599 0.224855 +v 1.105692 -1.003883 0.220821 +v 0.872231 -0.910167 0.216786 +v 0.638770 -0.816451 0.212751 +v 0.405308 -0.722735 0.208716 +v 0.171847 -0.629019 0.204681 +v -0.061614 -0.535303 0.200646 +v -0.295076 -0.441588 0.196611 +v -0.528537 -0.347872 0.192576 +v -0.761998 -0.254156 0.188541 +v -0.995460 -0.160440 0.184506 +v -1.228921 -0.066724 0.180471 +v -1.462382 0.026991 0.176436 +v -1.695844 0.120707 0.172401 +v -1.929305 0.214423 0.168366 +v -2.162766 0.308139 0.164331 +v -2.396228 0.401855 0.160296 +v -2.629689 0.495571 0.156261 +v -2.863150 0.589286 0.152226 +v -3.096612 0.683002 0.148191 +v -3.330073 0.776718 0.144156 +v -3.563535 0.870434 0.140121 +v -3.796996 0.964150 0.136086 +v -4.030457 1.057866 0.132051 +v -4.263918 1.151582 0.128016 +v -4.497379 1.245297 0.123981 +v -4.730841 1.339013 0.119946 +v -4.964303 1.432729 0.115911 +v -5.197763 1.526445 0.111876 +v -5.431225 1.620160 0.107841 +v 5.471620 -2.621141 0.287848 +v 5.238158 -2.527424 0.283813 +v 5.004697 -2.433708 0.279778 +v 4.771235 -2.339993 0.275743 +v 4.537774 -2.246277 0.271708 +v 4.304313 -2.152560 0.267673 +v 4.070851 -2.058845 0.263638 +v 3.837389 -1.965129 0.259603 +v 3.603928 -1.871413 0.255568 +v 3.370467 -1.777697 0.251533 +v 3.137005 -1.683981 0.247498 +v 2.903544 -1.590265 0.243463 +v 2.670082 -1.496549 0.239429 +v 2.436621 -1.402834 0.235394 +v 2.203160 -1.309118 0.231359 +v 1.969698 -1.215402 0.227324 +v 1.736237 -1.121686 0.223289 +v 1.502776 -1.027971 0.219254 +v 1.269314 -0.934255 0.215219 +v 1.035853 -0.840539 0.211184 +v 0.802391 -0.746823 0.207149 +v 0.568930 -0.653107 0.203114 +v 0.335469 -0.559391 0.199079 +v 0.102008 -0.465676 0.195044 +v -0.131454 -0.371960 0.191009 +v -0.364915 -0.278244 0.186974 +v -0.598377 -0.184528 0.182939 +v -0.831838 -0.090812 0.178904 +v -1.065299 0.002903 0.174869 +v -1.298761 0.096619 0.170834 +v -1.532222 0.190335 0.166799 +v -1.765683 0.284051 0.162764 +v -1.999144 0.377767 0.158729 +v -2.232605 0.471483 0.154694 +v -2.466067 0.565198 0.150659 +v -2.699528 0.658914 0.146624 +v -2.932990 0.752630 0.142589 +v -3.166451 0.846346 0.138554 +v -3.399912 0.940062 0.134519 +v -3.633374 1.033778 0.130484 +v -3.866836 1.127494 0.126449 +v -4.100297 1.221209 0.122414 +v -4.333757 1.314925 0.118379 +v -4.567219 1.408641 0.114344 +v -4.800680 1.502357 0.110309 +v -5.034142 1.596073 0.106274 +v -5.267603 1.689788 0.102239 +v -5.501064 1.783504 0.098204 +v 5.635241 -2.551513 0.282246 +v 5.401779 -2.457797 0.278211 +v 5.168319 -2.364081 0.274176 +v 4.934856 -2.270365 0.270141 +v 4.701396 -2.176649 0.266106 +v 4.467934 -2.082933 0.262071 +v 4.234472 -1.989217 0.258036 +v 4.001011 -1.895501 0.254001 +v 3.767550 -1.801785 0.249966 +v 3.534088 -1.708070 0.245931 +v 3.300627 -1.614354 0.241896 +v 3.067165 -1.520638 0.237861 +v 2.833704 -1.426922 0.233826 +v 2.600243 -1.333206 0.229791 +v 2.366781 -1.239491 0.225756 +v 2.133320 -1.145774 0.221721 +v 1.899859 -1.052059 0.217686 +v 1.666397 -0.958343 0.213651 +v 1.432936 -0.864627 0.209616 +v 1.199475 -0.770911 0.205581 +v 0.966013 -0.677196 0.201546 +v 0.732552 -0.583480 0.197511 +v 0.499091 -0.489764 0.193476 +v 0.265629 -0.396048 0.189441 +v 0.032168 -0.302332 0.185406 +v -0.201293 -0.208616 0.181371 +v -0.434755 -0.114901 0.177336 +v -0.668216 -0.021185 0.173302 +v -0.901677 0.072531 0.169267 +v -1.135139 0.166247 0.165232 +v -1.368600 0.259963 0.161197 +v -1.602061 0.353679 0.157162 +v -1.835523 0.447395 0.153127 +v -2.068984 0.541110 0.149092 +v -2.302445 0.634826 0.145057 +v -2.535906 0.728542 0.141022 +v -2.769368 0.822258 0.136987 +v -3.002829 0.915974 0.132952 +v -3.236290 1.009689 0.128917 +v -3.469752 1.103406 0.124882 +v -3.703213 1.197121 0.120847 +v -3.936675 1.290837 0.116812 +v -4.170135 1.384553 0.112777 +v -4.403597 1.478269 0.108742 +v -4.637058 1.571984 0.104707 +v -4.870520 1.665701 0.100672 +v -5.103981 1.759416 0.096637 +v -5.337442 1.853132 0.092602 +v -5.570904 1.946848 0.088567 +vn 0.0077 0.0622 0.9980 +usemtl None +s off +f 2//1 254//1 104//1 +f 2//1 105//1 254//1 +f 205//1 204//1 3//1 +f 206//1 255//1 205//1 +f 207//1 256//1 206//1 +f 208//1 258//1 207//1 +f 209//1 261//1 208//1 +f 210//1 265//1 209//1 +f 211//1 270//1 210//1 +f 212//1 276//1 211//1 +f 213//1 283//1 212//1 +f 214//1 291//1 213//1 +f 215//1 300//1 214//1 +f 216//1 310//1 215//1 +f 217//1 321//1 216//1 +f 218//1 333//1 217//1 +f 219//1 346//1 218//1 +f 220//1 360//1 219//1 +f 221//1 375//1 220//1 +f 222//1 391//1 221//1 +f 223//1 408//1 222//1 +f 224//1 426//1 223//1 +f 225//1 445//1 224//1 +f 226//1 465//1 225//1 +f 227//1 486//1 226//1 +f 228//1 508//1 227//1 +f 229//1 531//1 228//1 +f 230//1 555//1 229//1 +f 231//1 580//1 230//1 +f 232//1 606//1 231//1 +f 233//1 633//1 232//1 +f 234//1 661//1 233//1 +f 235//1 690//1 234//1 +f 236//1 720//1 235//1 +f 237//1 751//1 236//1 +f 238//1 783//1 237//1 +f 239//1 816//1 238//1 +f 240//1 850//1 239//1 +f 241//1 885//1 240//1 +f 242//1 921//1 241//1 +f 243//1 958//1 242//1 +f 244//1 996//1 243//1 +f 245//1 1035//1 244//1 +f 246//1 1075//1 245//1 +f 247//1 1116//1 246//1 +f 248//1 1158//1 247//1 +f 249//1 1201//1 248//1 +f 250//1 1245//1 249//1 +f 251//1 1290//1 250//1 +f 252//1 1336//1 251//1 +f 253//1 1383//1 252//1 +f 254//1 1431//1 253//1 +f 205//1 255//1 204//1 +f 255//1 203//1 204//1 +f 206//1 256//1 255//1 +f 256//1 257//1 255//1 +f 255//1 257//1 203//1 +f 257//1 202//1 203//1 +f 207//1 258//1 256//1 +f 258//1 259//1 256//1 +f 256//1 259//1 257//1 +f 259//1 260//1 257//1 +f 257//1 260//1 202//1 +f 260//1 201//1 202//1 +f 208//1 261//1 258//1 +f 261//1 262//1 258//1 +f 258//1 262//1 259//1 +f 262//1 263//1 259//1 +f 259//1 263//1 260//1 +f 263//1 264//1 260//1 +f 260//1 264//1 201//1 +f 264//1 200//1 201//1 +f 209//1 265//1 261//1 +f 265//1 266//1 261//1 +f 261//1 266//1 262//1 +f 266//1 267//1 262//1 +f 262//1 267//1 263//1 +f 267//1 268//1 263//1 +f 263//1 268//1 264//1 +f 268//1 269//1 264//1 +f 264//1 269//1 200//1 +f 269//1 199//1 200//1 +f 210//1 270//1 265//1 +f 270//1 271//1 265//1 +f 265//1 271//1 266//1 +f 271//1 272//1 266//1 +f 266//1 272//1 267//1 +f 272//1 273//1 267//1 +f 267//1 273//1 268//1 +f 273//1 274//1 268//1 +f 268//1 274//1 269//1 +f 274//1 275//1 269//1 +f 269//1 275//1 199//1 +f 275//1 198//1 199//1 +f 211//1 276//1 270//1 +f 276//1 277//1 270//1 +f 270//1 277//1 271//1 +f 277//1 278//1 271//1 +f 271//1 278//1 272//1 +f 278//1 279//1 272//1 +f 272//1 279//1 273//1 +f 279//1 280//1 273//1 +f 273//1 280//1 274//1 +f 280//1 281//1 274//1 +f 274//1 281//1 275//1 +f 281//1 282//1 275//1 +f 275//1 282//1 198//1 +f 282//1 197//1 198//1 +f 212//1 283//1 276//1 +f 283//1 284//1 276//1 +f 276//1 284//1 277//1 +f 284//1 285//1 277//1 +f 277//1 285//1 278//1 +f 285//1 286//1 278//1 +f 278//1 286//1 279//1 +f 286//1 287//1 279//1 +f 279//1 287//1 280//1 +f 287//1 288//1 280//1 +f 280//1 288//1 281//1 +f 288//1 289//1 281//1 +f 281//1 289//1 282//1 +f 289//1 290//1 282//1 +f 282//1 290//1 197//1 +f 290//1 196//1 197//1 +f 213//1 291//1 283//1 +f 291//1 292//1 283//1 +f 283//1 292//1 284//1 +f 292//1 293//1 284//1 +f 284//1 293//1 285//1 +f 293//1 294//1 285//1 +f 285//1 294//1 286//1 +f 294//1 295//1 286//1 +f 286//1 295//1 287//1 +f 295//1 296//1 287//1 +f 287//1 296//1 288//1 +f 296//1 297//1 288//1 +f 288//1 297//1 289//1 +f 297//1 298//1 289//1 +f 289//1 298//1 290//1 +f 298//1 299//1 290//1 +f 290//1 299//1 196//1 +f 299//1 195//1 196//1 +f 214//1 300//1 291//1 +f 300//1 301//1 291//1 +f 291//1 301//1 292//1 +f 301//1 302//1 292//1 +f 292//1 302//1 293//1 +f 302//1 303//1 293//1 +f 293//1 303//1 294//1 +f 303//1 304//1 294//1 +f 294//1 304//1 295//1 +f 304//1 305//1 295//1 +f 295//1 305//1 296//1 +f 305//1 306//1 296//1 +f 296//1 306//1 297//1 +f 306//1 307//1 297//1 +f 297//1 307//1 298//1 +f 307//1 308//1 298//1 +f 298//1 308//1 299//1 +f 308//1 309//1 299//1 +f 299//1 309//1 195//1 +f 309//1 194//1 195//1 +f 215//1 310//1 300//1 +f 310//1 311//1 300//1 +f 300//1 311//1 301//1 +f 311//1 312//1 301//1 +f 301//1 312//1 302//1 +f 312//1 313//1 302//1 +f 302//1 313//1 303//1 +f 313//1 314//1 303//1 +f 303//1 314//1 304//1 +f 314//1 315//1 304//1 +f 304//1 315//1 305//1 +f 315//1 316//1 305//1 +f 305//1 316//1 306//1 +f 316//1 317//1 306//1 +f 306//1 317//1 307//1 +f 317//1 318//1 307//1 +f 307//1 318//1 308//1 +f 318//1 319//1 308//1 +f 308//1 319//1 309//1 +f 319//1 320//1 309//1 +f 309//1 320//1 194//1 +f 320//1 193//1 194//1 +f 216//1 321//1 310//1 +f 321//1 322//1 310//1 +f 310//1 322//1 311//1 +f 322//1 323//1 311//1 +f 311//1 323//1 312//1 +f 323//1 324//1 312//1 +f 312//1 324//1 313//1 +f 324//1 325//1 313//1 +f 313//1 325//1 314//1 +f 325//1 326//1 314//1 +f 314//1 326//1 315//1 +f 326//1 327//1 315//1 +f 315//1 327//1 316//1 +f 327//1 328//1 316//1 +f 316//1 328//1 317//1 +f 328//1 329//1 317//1 +f 317//1 329//1 318//1 +f 329//1 330//1 318//1 +f 318//1 330//1 319//1 +f 330//1 331//1 319//1 +f 319//1 331//1 320//1 +f 331//1 332//1 320//1 +f 320//1 332//1 193//1 +f 332//1 192//1 193//1 +f 217//1 333//1 321//1 +f 333//1 334//1 321//1 +f 321//1 334//1 322//1 +f 334//1 335//1 322//1 +f 322//1 335//1 323//1 +f 335//1 336//1 323//1 +f 323//1 336//1 324//1 +f 336//1 337//1 324//1 +f 324//1 337//1 325//1 +f 337//1 338//1 325//1 +f 325//1 338//1 326//1 +f 338//1 339//1 326//1 +f 326//1 339//1 327//1 +f 339//1 340//1 327//1 +f 327//1 340//1 328//1 +f 340//1 341//1 328//1 +f 328//1 341//1 329//1 +f 341//1 342//1 329//1 +f 329//1 342//1 330//1 +f 342//1 343//1 330//1 +f 330//1 343//1 331//1 +f 343//1 344//1 331//1 +f 331//1 344//1 332//1 +f 344//1 345//1 332//1 +f 332//1 345//1 192//1 +f 345//1 191//1 192//1 +f 218//1 346//1 333//1 +f 346//1 347//1 333//1 +f 333//1 347//1 334//1 +f 347//1 348//1 334//1 +f 334//1 348//1 335//1 +f 348//1 349//1 335//1 +f 335//1 349//1 336//1 +f 349//1 350//1 336//1 +f 336//1 350//1 337//1 +f 350//1 351//1 337//1 +f 337//1 351//1 338//1 +f 351//1 352//1 338//1 +f 338//1 352//1 339//1 +f 352//1 353//1 339//1 +f 339//1 353//1 340//1 +f 353//1 354//1 340//1 +f 340//1 354//1 341//1 +f 354//1 355//1 341//1 +f 341//1 355//1 342//1 +f 355//1 356//1 342//1 +f 342//1 356//1 343//1 +f 356//1 357//1 343//1 +f 343//1 357//1 344//1 +f 357//1 358//1 344//1 +f 344//1 358//1 345//1 +f 358//1 359//1 345//1 +f 345//1 359//1 191//1 +f 359//1 190//1 191//1 +f 219//1 360//1 346//1 +f 360//1 361//1 346//1 +f 346//1 361//1 347//1 +f 361//1 362//1 347//1 +f 347//1 362//1 348//1 +f 362//1 363//1 348//1 +f 348//1 363//1 349//1 +f 363//1 364//1 349//1 +f 349//1 364//1 350//1 +f 364//1 365//1 350//1 +f 350//1 365//1 351//1 +f 365//1 366//1 351//1 +f 351//1 366//1 352//1 +f 366//1 367//1 352//1 +f 352//1 367//1 353//1 +f 367//1 368//1 353//1 +f 353//1 368//1 354//1 +f 368//1 369//1 354//1 +f 354//1 369//1 355//1 +f 369//1 370//1 355//1 +f 355//1 370//1 356//1 +f 370//1 371//1 356//1 +f 356//1 371//1 357//1 +f 371//1 372//1 357//1 +f 357//1 372//1 358//1 +f 372//1 373//1 358//1 +f 358//1 373//1 359//1 +f 373//1 374//1 359//1 +f 359//1 374//1 190//1 +f 374//1 189//1 190//1 +f 220//1 375//1 360//1 +f 375//1 376//1 360//1 +f 360//1 376//1 361//1 +f 376//1 377//1 361//1 +f 361//1 377//1 362//1 +f 377//1 378//1 362//1 +f 362//1 378//1 363//1 +f 378//1 379//1 363//1 +f 363//1 379//1 364//1 +f 379//1 380//1 364//1 +f 364//1 380//1 365//1 +f 380//1 381//1 365//1 +f 365//1 381//1 366//1 +f 381//1 382//1 366//1 +f 366//1 382//1 367//1 +f 382//1 383//1 367//1 +f 367//1 383//1 368//1 +f 383//1 384//1 368//1 +f 368//1 384//1 369//1 +f 384//1 385//1 369//1 +f 369//1 385//1 370//1 +f 385//1 386//1 370//1 +f 370//1 386//1 371//1 +f 386//1 387//1 371//1 +f 371//1 387//1 372//1 +f 387//1 388//1 372//1 +f 372//1 388//1 373//1 +f 388//1 389//1 373//1 +f 373//1 389//1 374//1 +f 389//1 390//1 374//1 +f 374//1 390//1 189//1 +f 390//1 188//1 189//1 +f 221//1 391//1 375//1 +f 391//1 392//1 375//1 +f 375//1 392//1 376//1 +f 392//1 393//1 376//1 +f 376//1 393//1 377//1 +f 393//1 394//1 377//1 +f 377//1 394//1 378//1 +f 394//1 395//1 378//1 +f 378//1 395//1 379//1 +f 395//1 396//1 379//1 +f 379//1 396//1 380//1 +f 396//1 397//1 380//1 +f 380//1 397//1 381//1 +f 397//1 398//1 381//1 +f 381//1 398//1 382//1 +f 398//1 399//1 382//1 +f 382//1 399//1 383//1 +f 399//1 400//1 383//1 +f 383//1 400//1 384//1 +f 400//1 401//1 384//1 +f 384//1 401//1 385//1 +f 401//1 402//1 385//1 +f 385//1 402//1 386//1 +f 402//1 403//1 386//1 +f 386//1 403//1 387//1 +f 403//1 404//1 387//1 +f 387//1 404//1 388//1 +f 404//1 405//1 388//1 +f 388//1 405//1 389//1 +f 405//1 406//1 389//1 +f 389//1 406//1 390//1 +f 406//1 407//1 390//1 +f 390//1 407//1 188//1 +f 407//1 187//1 188//1 +f 222//1 408//1 391//1 +f 408//1 409//1 391//1 +f 391//1 409//1 392//1 +f 409//1 410//1 392//1 +f 392//1 410//1 393//1 +f 410//1 411//1 393//1 +f 393//1 411//1 394//1 +f 411//1 412//1 394//1 +f 394//1 412//1 395//1 +f 412//1 413//1 395//1 +f 395//1 413//1 396//1 +f 413//1 414//1 396//1 +f 396//1 414//1 397//1 +f 414//1 415//1 397//1 +f 397//1 415//1 398//1 +f 415//1 416//1 398//1 +f 398//1 416//1 399//1 +f 416//1 417//1 399//1 +f 399//1 417//1 400//1 +f 417//1 418//1 400//1 +f 400//1 418//1 401//1 +f 418//1 419//1 401//1 +f 401//1 419//1 402//1 +f 419//1 420//1 402//1 +f 402//1 420//1 403//1 +f 420//1 421//1 403//1 +f 403//1 421//1 404//1 +f 421//1 422//1 404//1 +f 404//1 422//1 405//1 +f 422//1 423//1 405//1 +f 405//1 423//1 406//1 +f 423//1 424//1 406//1 +f 406//1 424//1 407//1 +f 424//1 425//1 407//1 +f 407//1 425//1 187//1 +f 425//1 186//1 187//1 +f 223//1 426//1 408//1 +f 426//1 427//1 408//1 +f 408//1 427//1 409//1 +f 427//1 428//1 409//1 +f 409//1 428//1 410//1 +f 428//1 429//1 410//1 +f 410//1 429//1 411//1 +f 429//1 430//1 411//1 +f 411//1 430//1 412//1 +f 430//1 431//1 412//1 +f 412//1 431//1 413//1 +f 431//1 432//1 413//1 +f 413//1 432//1 414//1 +f 432//1 433//1 414//1 +f 414//1 433//1 415//1 +f 433//1 434//1 415//1 +f 415//1 434//1 416//1 +f 434//1 435//1 416//1 +f 416//1 435//1 417//1 +f 435//1 436//1 417//1 +f 417//1 436//1 418//1 +f 436//1 437//1 418//1 +f 418//1 437//1 419//1 +f 437//1 438//1 419//1 +f 419//1 438//1 420//1 +f 438//1 439//1 420//1 +f 420//1 439//1 421//1 +f 439//1 440//1 421//1 +f 421//1 440//1 422//1 +f 440//1 441//1 422//1 +f 422//1 441//1 423//1 +f 441//1 442//1 423//1 +f 423//1 442//1 424//1 +f 442//1 443//1 424//1 +f 424//1 443//1 425//1 +f 443//1 444//1 425//1 +f 425//1 444//1 186//1 +f 444//1 185//1 186//1 +f 224//1 445//1 426//1 +f 445//1 446//1 426//1 +f 426//1 446//1 427//1 +f 446//1 447//1 427//1 +f 427//1 447//1 428//1 +f 447//1 448//1 428//1 +f 428//1 448//1 429//1 +f 448//1 449//1 429//1 +f 429//1 449//1 430//1 +f 449//1 450//1 430//1 +f 430//1 450//1 431//1 +f 450//1 451//1 431//1 +f 431//1 451//1 432//1 +f 451//1 452//1 432//1 +f 432//1 452//1 433//1 +f 452//1 453//1 433//1 +f 433//1 453//1 434//1 +f 453//1 454//1 434//1 +f 434//1 454//1 435//1 +f 454//1 455//1 435//1 +f 435//1 455//1 436//1 +f 455//1 456//1 436//1 +f 436//1 456//1 437//1 +f 456//1 457//1 437//1 +f 437//1 457//1 438//1 +f 457//1 458//1 438//1 +f 438//1 458//1 439//1 +f 458//1 459//1 439//1 +f 439//1 459//1 440//1 +f 459//1 460//1 440//1 +f 440//1 460//1 441//1 +f 460//1 461//1 441//1 +f 441//1 461//1 442//1 +f 461//1 462//1 442//1 +f 442//1 462//1 443//1 +f 462//1 463//1 443//1 +f 443//1 463//1 444//1 +f 463//1 464//1 444//1 +f 444//1 464//1 185//1 +f 464//1 184//1 185//1 +f 225//1 465//1 445//1 +f 465//1 466//1 445//1 +f 445//1 466//1 446//1 +f 466//1 467//1 446//1 +f 446//1 467//1 447//1 +f 467//1 468//1 447//1 +f 447//1 468//1 448//1 +f 468//1 469//1 448//1 +f 448//1 469//1 449//1 +f 469//1 470//1 449//1 +f 449//1 470//1 450//1 +f 470//1 471//1 450//1 +f 450//1 471//1 451//1 +f 471//1 472//1 451//1 +f 451//1 472//1 452//1 +f 472//1 473//1 452//1 +f 452//1 473//1 453//1 +f 473//1 474//1 453//1 +f 453//1 474//1 454//1 +f 474//1 475//1 454//1 +f 454//1 475//1 455//1 +f 475//1 476//1 455//1 +f 455//1 476//1 456//1 +f 476//1 477//1 456//1 +f 456//1 477//1 457//1 +f 477//1 478//1 457//1 +f 457//1 478//1 458//1 +f 478//1 479//1 458//1 +f 458//1 479//1 459//1 +f 479//1 480//1 459//1 +f 459//1 480//1 460//1 +f 480//1 481//1 460//1 +f 460//1 481//1 461//1 +f 481//1 482//1 461//1 +f 461//1 482//1 462//1 +f 482//1 483//1 462//1 +f 462//1 483//1 463//1 +f 483//1 484//1 463//1 +f 463//1 484//1 464//1 +f 484//1 485//1 464//1 +f 464//1 485//1 184//1 +f 485//1 183//1 184//1 +f 226//1 486//1 465//1 +f 486//1 487//1 465//1 +f 465//1 487//1 466//1 +f 487//1 488//1 466//1 +f 466//1 488//1 467//1 +f 488//1 489//1 467//1 +f 467//1 489//1 468//1 +f 489//1 490//1 468//1 +f 468//1 490//1 469//1 +f 490//1 491//1 469//1 +f 469//1 491//1 470//1 +f 491//1 492//1 470//1 +f 470//1 492//1 471//1 +f 492//1 493//1 471//1 +f 471//1 493//1 472//1 +f 493//1 494//1 472//1 +f 472//1 494//1 473//1 +f 494//1 495//1 473//1 +f 473//1 495//1 474//1 +f 495//1 496//1 474//1 +f 474//1 496//1 475//1 +f 496//1 497//1 475//1 +f 475//1 497//1 476//1 +f 497//1 498//1 476//1 +f 476//1 498//1 477//1 +f 498//1 499//1 477//1 +f 477//1 499//1 478//1 +f 499//1 500//1 478//1 +f 478//1 500//1 479//1 +f 500//1 501//1 479//1 +f 479//1 501//1 480//1 +f 501//1 502//1 480//1 +f 480//1 502//1 481//1 +f 502//1 503//1 481//1 +f 481//1 503//1 482//1 +f 503//1 504//1 482//1 +f 482//1 504//1 483//1 +f 504//1 505//1 483//1 +f 483//1 505//1 484//1 +f 505//1 506//1 484//1 +f 484//1 506//1 485//1 +f 506//1 507//1 485//1 +f 485//1 507//1 183//1 +f 507//1 182//1 183//1 +f 227//1 508//1 486//1 +f 508//1 509//1 486//1 +f 486//1 509//1 487//1 +f 509//1 510//1 487//1 +f 487//1 510//1 488//1 +f 510//1 511//1 488//1 +f 488//1 511//1 489//1 +f 511//1 512//1 489//1 +f 489//1 512//1 490//1 +f 512//1 513//1 490//1 +f 490//1 513//1 491//1 +f 513//1 514//1 491//1 +f 491//1 514//1 492//1 +f 514//1 515//1 492//1 +f 492//1 515//1 493//1 +f 515//1 516//1 493//1 +f 493//1 516//1 494//1 +f 516//1 517//1 494//1 +f 494//1 517//1 495//1 +f 517//1 518//1 495//1 +f 495//1 518//1 496//1 +f 518//1 519//1 496//1 +f 496//1 519//1 497//1 +f 519//1 520//1 497//1 +f 497//1 520//1 498//1 +f 520//1 521//1 498//1 +f 498//1 521//1 499//1 +f 521//1 522//1 499//1 +f 499//1 522//1 500//1 +f 522//1 523//1 500//1 +f 500//1 523//1 501//1 +f 523//1 524//1 501//1 +f 501//1 524//1 502//1 +f 524//1 525//1 502//1 +f 502//1 525//1 503//1 +f 525//1 526//1 503//1 +f 503//1 526//1 504//1 +f 526//1 527//1 504//1 +f 504//1 527//1 505//1 +f 527//1 528//1 505//1 +f 505//1 528//1 506//1 +f 528//1 529//1 506//1 +f 506//1 529//1 507//1 +f 529//1 530//1 507//1 +f 507//1 530//1 182//1 +f 530//1 181//1 182//1 +f 228//1 531//1 508//1 +f 531//1 532//1 508//1 +f 508//1 532//1 509//1 +f 532//1 533//1 509//1 +f 509//1 533//1 510//1 +f 533//1 534//1 510//1 +f 510//1 534//1 511//1 +f 534//1 535//1 511//1 +f 511//1 535//1 512//1 +f 535//1 536//1 512//1 +f 512//1 536//1 513//1 +f 536//1 537//1 513//1 +f 513//1 537//1 514//1 +f 537//1 538//1 514//1 +f 514//1 538//1 515//1 +f 538//1 539//1 515//1 +f 515//1 539//1 516//1 +f 539//1 540//1 516//1 +f 516//1 540//1 517//1 +f 540//1 541//1 517//1 +f 517//1 541//1 518//1 +f 541//1 542//1 518//1 +f 518//1 542//1 519//1 +f 542//1 543//1 519//1 +f 519//1 543//1 520//1 +f 543//1 544//1 520//1 +f 520//1 544//1 521//1 +f 544//1 545//1 521//1 +f 521//1 545//1 522//1 +f 545//1 546//1 522//1 +f 522//1 546//1 523//1 +f 546//1 547//1 523//1 +f 523//1 547//1 524//1 +f 547//1 548//1 524//1 +f 524//1 548//1 525//1 +f 548//1 549//1 525//1 +f 525//1 549//1 526//1 +f 549//1 550//1 526//1 +f 526//1 550//1 527//1 +f 550//1 551//1 527//1 +f 527//1 551//1 528//1 +f 551//1 552//1 528//1 +f 528//1 552//1 529//1 +f 552//1 553//1 529//1 +f 529//1 553//1 530//1 +f 553//1 554//1 530//1 +f 530//1 554//1 181//1 +f 554//1 180//1 181//1 +f 229//1 555//1 531//1 +f 555//1 556//1 531//1 +f 531//1 556//1 532//1 +f 556//1 557//1 532//1 +f 532//1 557//1 533//1 +f 557//1 558//1 533//1 +f 533//1 558//1 534//1 +f 558//1 559//1 534//1 +f 534//1 559//1 535//1 +f 559//1 560//1 535//1 +f 535//1 560//1 536//1 +f 560//1 561//1 536//1 +f 536//1 561//1 537//1 +f 561//1 562//1 537//1 +f 537//1 562//1 538//1 +f 562//1 563//1 538//1 +f 538//1 563//1 539//1 +f 563//1 564//1 539//1 +f 539//1 564//1 540//1 +f 564//1 565//1 540//1 +f 540//1 565//1 541//1 +f 565//1 566//1 541//1 +f 541//1 566//1 542//1 +f 566//1 567//1 542//1 +f 542//1 567//1 543//1 +f 567//1 568//1 543//1 +f 543//1 568//1 544//1 +f 568//1 569//1 544//1 +f 544//1 569//1 545//1 +f 569//1 570//1 545//1 +f 545//1 570//1 546//1 +f 570//1 571//1 546//1 +f 546//1 571//1 547//1 +f 571//1 572//1 547//1 +f 547//1 572//1 548//1 +f 572//1 573//1 548//1 +f 548//1 573//1 549//1 +f 573//1 574//1 549//1 +f 549//1 574//1 550//1 +f 574//1 575//1 550//1 +f 550//1 575//1 551//1 +f 575//1 576//1 551//1 +f 551//1 576//1 552//1 +f 576//1 577//1 552//1 +f 552//1 577//1 553//1 +f 577//1 578//1 553//1 +f 553//1 578//1 554//1 +f 578//1 579//1 554//1 +f 554//1 579//1 180//1 +f 579//1 179//1 180//1 +f 230//1 580//1 555//1 +f 580//1 581//1 555//1 +f 555//1 581//1 556//1 +f 581//1 582//1 556//1 +f 556//1 582//1 557//1 +f 582//1 583//1 557//1 +f 557//1 583//1 558//1 +f 583//1 584//1 558//1 +f 558//1 584//1 559//1 +f 584//1 585//1 559//1 +f 559//1 585//1 560//1 +f 585//1 586//1 560//1 +f 560//1 586//1 561//1 +f 586//1 587//1 561//1 +f 561//1 587//1 562//1 +f 587//1 588//1 562//1 +f 562//1 588//1 563//1 +f 588//1 589//1 563//1 +f 563//1 589//1 564//1 +f 589//1 590//1 564//1 +f 564//1 590//1 565//1 +f 590//1 591//1 565//1 +f 565//1 591//1 566//1 +f 591//1 592//1 566//1 +f 566//1 592//1 567//1 +f 592//1 593//1 567//1 +f 567//1 593//1 568//1 +f 593//1 594//1 568//1 +f 568//1 594//1 569//1 +f 594//1 595//1 569//1 +f 569//1 595//1 570//1 +f 595//1 596//1 570//1 +f 570//1 596//1 571//1 +f 596//1 597//1 571//1 +f 571//1 597//1 572//1 +f 597//1 598//1 572//1 +f 572//1 598//1 573//1 +f 598//1 599//1 573//1 +f 573//1 599//1 574//1 +f 599//1 600//1 574//1 +f 574//1 600//1 575//1 +f 600//1 601//1 575//1 +f 575//1 601//1 576//1 +f 601//1 602//1 576//1 +f 576//1 602//1 577//1 +f 602//1 603//1 577//1 +f 577//1 603//1 578//1 +f 603//1 604//1 578//1 +f 578//1 604//1 579//1 +f 604//1 605//1 579//1 +f 579//1 605//1 179//1 +f 605//1 178//1 179//1 +f 231//1 606//1 580//1 +f 606//1 607//1 580//1 +f 580//1 607//1 581//1 +f 607//1 608//1 581//1 +f 581//1 608//1 582//1 +f 608//1 609//1 582//1 +f 582//1 609//1 583//1 +f 609//1 610//1 583//1 +f 583//1 610//1 584//1 +f 610//1 611//1 584//1 +f 584//1 611//1 585//1 +f 611//1 612//1 585//1 +f 585//1 612//1 586//1 +f 612//1 613//1 586//1 +f 586//1 613//1 587//1 +f 613//1 614//1 587//1 +f 587//1 614//1 588//1 +f 614//1 615//1 588//1 +f 588//1 615//1 589//1 +f 615//1 616//1 589//1 +f 589//1 616//1 590//1 +f 616//1 617//1 590//1 +f 590//1 617//1 591//1 +f 617//1 618//1 591//1 +f 591//1 618//1 592//1 +f 618//1 619//1 592//1 +f 592//1 619//1 593//1 +f 619//1 620//1 593//1 +f 593//1 620//1 594//1 +f 620//1 621//1 594//1 +f 594//1 621//1 595//1 +f 621//1 622//1 595//1 +f 595//1 622//1 596//1 +f 622//1 623//1 596//1 +f 596//1 623//1 597//1 +f 623//1 624//1 597//1 +f 597//1 624//1 598//1 +f 624//1 625//1 598//1 +f 598//1 625//1 599//1 +f 625//1 626//1 599//1 +f 599//1 626//1 600//1 +f 626//1 627//1 600//1 +f 600//1 627//1 601//1 +f 627//1 628//1 601//1 +f 601//1 628//1 602//1 +f 628//1 629//1 602//1 +f 602//1 629//1 603//1 +f 629//1 630//1 603//1 +f 603//1 630//1 604//1 +f 630//1 631//1 604//1 +f 604//1 631//1 605//1 +f 631//1 632//1 605//1 +f 605//1 632//1 178//1 +f 632//1 177//1 178//1 +f 232//1 633//1 606//1 +f 633//1 634//1 606//1 +f 606//1 634//1 607//1 +f 634//1 635//1 607//1 +f 607//1 635//1 608//1 +f 635//1 636//1 608//1 +f 608//1 636//1 609//1 +f 636//1 637//1 609//1 +f 609//1 637//1 610//1 +f 637//1 638//1 610//1 +f 610//1 638//1 611//1 +f 638//1 639//1 611//1 +f 611//1 639//1 612//1 +f 639//1 640//1 612//1 +f 612//1 640//1 613//1 +f 640//1 641//1 613//1 +f 613//1 641//1 614//1 +f 641//1 642//1 614//1 +f 614//1 642//1 615//1 +f 642//1 643//1 615//1 +f 615//1 643//1 616//1 +f 643//1 644//1 616//1 +f 616//1 644//1 617//1 +f 644//1 645//1 617//1 +f 617//1 645//1 618//1 +f 645//1 646//1 618//1 +f 618//1 646//1 619//1 +f 646//1 647//1 619//1 +f 619//1 647//1 620//1 +f 647//1 648//1 620//1 +f 620//1 648//1 621//1 +f 648//1 649//1 621//1 +f 621//1 649//1 622//1 +f 649//1 650//1 622//1 +f 622//1 650//1 623//1 +f 650//1 651//1 623//1 +f 623//1 651//1 624//1 +f 651//1 652//1 624//1 +f 624//1 652//1 625//1 +f 652//1 653//1 625//1 +f 625//1 653//1 626//1 +f 653//1 654//1 626//1 +f 626//1 654//1 627//1 +f 654//1 655//1 627//1 +f 627//1 655//1 628//1 +f 655//1 656//1 628//1 +f 628//1 656//1 629//1 +f 656//1 657//1 629//1 +f 629//1 657//1 630//1 +f 657//1 658//1 630//1 +f 630//1 658//1 631//1 +f 658//1 659//1 631//1 +f 631//1 659//1 632//1 +f 659//1 660//1 632//1 +f 632//1 660//1 177//1 +f 660//1 176//1 177//1 +f 233//1 661//1 633//1 +f 661//1 662//1 633//1 +f 633//1 662//1 634//1 +f 662//1 663//1 634//1 +f 634//1 663//1 635//1 +f 663//1 664//1 635//1 +f 635//1 664//1 636//1 +f 664//1 665//1 636//1 +f 636//1 665//1 637//1 +f 665//1 666//1 637//1 +f 637//1 666//1 638//1 +f 666//1 667//1 638//1 +f 638//1 667//1 639//1 +f 667//1 668//1 639//1 +f 639//1 668//1 640//1 +f 668//1 669//1 640//1 +f 640//1 669//1 641//1 +f 669//1 670//1 641//1 +f 641//1 670//1 642//1 +f 670//1 671//1 642//1 +f 642//1 671//1 643//1 +f 671//1 672//1 643//1 +f 643//1 672//1 644//1 +f 672//1 673//1 644//1 +f 644//1 673//1 645//1 +f 673//1 674//1 645//1 +f 645//1 674//1 646//1 +f 674//1 675//1 646//1 +f 646//1 675//1 647//1 +f 675//1 676//1 647//1 +f 647//1 676//1 648//1 +f 676//1 677//1 648//1 +f 648//1 677//1 649//1 +f 677//1 678//1 649//1 +f 649//1 678//1 650//1 +f 678//1 679//1 650//1 +f 650//1 679//1 651//1 +f 679//1 680//1 651//1 +f 651//1 680//1 652//1 +f 680//1 681//1 652//1 +f 652//1 681//1 653//1 +f 681//1 682//1 653//1 +f 653//1 682//1 654//1 +f 682//1 683//1 654//1 +f 654//1 683//1 655//1 +f 683//1 684//1 655//1 +f 655//1 684//1 656//1 +f 684//1 685//1 656//1 +f 656//1 685//1 657//1 +f 685//1 686//1 657//1 +f 657//1 686//1 658//1 +f 686//1 687//1 658//1 +f 658//1 687//1 659//1 +f 687//1 688//1 659//1 +f 659//1 688//1 660//1 +f 688//1 689//1 660//1 +f 660//1 689//1 176//1 +f 689//1 175//1 176//1 +f 234//1 690//1 661//1 +f 690//1 691//1 661//1 +f 661//1 691//1 662//1 +f 691//1 692//1 662//1 +f 662//1 692//1 663//1 +f 692//1 693//1 663//1 +f 663//1 693//1 664//1 +f 693//1 694//1 664//1 +f 664//1 694//1 665//1 +f 694//1 695//1 665//1 +f 665//1 695//1 666//1 +f 695//1 696//1 666//1 +f 666//1 696//1 667//1 +f 696//1 697//1 667//1 +f 667//1 697//1 668//1 +f 697//1 698//1 668//1 +f 668//1 698//1 669//1 +f 698//1 699//1 669//1 +f 669//1 699//1 670//1 +f 699//1 700//1 670//1 +f 670//1 700//1 671//1 +f 700//1 701//1 671//1 +f 671//1 701//1 672//1 +f 701//1 702//1 672//1 +f 672//1 702//1 673//1 +f 702//1 703//1 673//1 +f 673//1 703//1 674//1 +f 703//1 704//1 674//1 +f 674//1 704//1 675//1 +f 704//1 705//1 675//1 +f 675//1 705//1 676//1 +f 705//1 706//1 676//1 +f 676//1 706//1 677//1 +f 706//1 707//1 677//1 +f 677//1 707//1 678//1 +f 707//1 708//1 678//1 +f 678//1 708//1 679//1 +f 708//1 709//1 679//1 +f 679//1 709//1 680//1 +f 709//1 710//1 680//1 +f 680//1 710//1 681//1 +f 710//1 711//1 681//1 +f 681//1 711//1 682//1 +f 711//1 712//1 682//1 +f 682//1 712//1 683//1 +f 712//1 713//1 683//1 +f 683//1 713//1 684//1 +f 713//1 714//1 684//1 +f 684//1 714//1 685//1 +f 714//1 715//1 685//1 +f 685//1 715//1 686//1 +f 715//1 716//1 686//1 +f 686//1 716//1 687//1 +f 716//1 717//1 687//1 +f 687//1 717//1 688//1 +f 717//1 718//1 688//1 +f 688//1 718//1 689//1 +f 718//1 719//1 689//1 +f 689//1 719//1 175//1 +f 719//1 174//1 175//1 +f 235//1 720//1 690//1 +f 720//1 721//1 690//1 +f 690//1 721//1 691//1 +f 721//1 722//1 691//1 +f 691//1 722//1 692//1 +f 722//1 723//1 692//1 +f 692//1 723//1 693//1 +f 723//1 724//1 693//1 +f 693//1 724//1 694//1 +f 724//1 725//1 694//1 +f 694//1 725//1 695//1 +f 725//1 726//1 695//1 +f 695//1 726//1 696//1 +f 726//1 727//1 696//1 +f 696//1 727//1 697//1 +f 727//1 728//1 697//1 +f 697//1 728//1 698//1 +f 728//1 729//1 698//1 +f 698//1 729//1 699//1 +f 729//1 730//1 699//1 +f 699//1 730//1 700//1 +f 730//1 731//1 700//1 +f 700//1 731//1 701//1 +f 731//1 732//1 701//1 +f 701//1 732//1 702//1 +f 732//1 733//1 702//1 +f 702//1 733//1 703//1 +f 733//1 734//1 703//1 +f 703//1 734//1 704//1 +f 734//1 735//1 704//1 +f 704//1 735//1 705//1 +f 735//1 736//1 705//1 +f 705//1 736//1 706//1 +f 736//1 737//1 706//1 +f 706//1 737//1 707//1 +f 737//1 738//1 707//1 +f 707//1 738//1 708//1 +f 738//1 739//1 708//1 +f 708//1 739//1 709//1 +f 739//1 740//1 709//1 +f 709//1 740//1 710//1 +f 740//1 741//1 710//1 +f 710//1 741//1 711//1 +f 741//1 742//1 711//1 +f 711//1 742//1 712//1 +f 742//1 743//1 712//1 +f 712//1 743//1 713//1 +f 743//1 744//1 713//1 +f 713//1 744//1 714//1 +f 744//1 745//1 714//1 +f 714//1 745//1 715//1 +f 745//1 746//1 715//1 +f 715//1 746//1 716//1 +f 746//1 747//1 716//1 +f 716//1 747//1 717//1 +f 747//1 748//1 717//1 +f 717//1 748//1 718//1 +f 748//1 749//1 718//1 +f 718//1 749//1 719//1 +f 749//1 750//1 719//1 +f 719//1 750//1 174//1 +f 750//1 173//1 174//1 +f 236//1 751//1 720//1 +f 751//1 752//1 720//1 +f 720//1 752//1 721//1 +f 752//1 753//1 721//1 +f 721//1 753//1 722//1 +f 753//1 754//1 722//1 +f 722//1 754//1 723//1 +f 754//1 755//1 723//1 +f 723//1 755//1 724//1 +f 755//1 756//1 724//1 +f 724//1 756//1 725//1 +f 756//1 757//1 725//1 +f 725//1 757//1 726//1 +f 757//1 758//1 726//1 +f 726//1 758//1 727//1 +f 758//1 759//1 727//1 +f 727//1 759//1 728//1 +f 759//1 760//1 728//1 +f 728//1 760//1 729//1 +f 760//1 761//1 729//1 +f 729//1 761//1 730//1 +f 761//1 762//1 730//1 +f 730//1 762//1 731//1 +f 762//1 763//1 731//1 +f 731//1 763//1 732//1 +f 763//1 764//1 732//1 +f 732//1 764//1 733//1 +f 764//1 765//1 733//1 +f 733//1 765//1 734//1 +f 765//1 766//1 734//1 +f 734//1 766//1 735//1 +f 766//1 767//1 735//1 +f 735//1 767//1 736//1 +f 767//1 768//1 736//1 +f 736//1 768//1 737//1 +f 768//1 769//1 737//1 +f 737//1 769//1 738//1 +f 769//1 770//1 738//1 +f 738//1 770//1 739//1 +f 770//1 771//1 739//1 +f 739//1 771//1 740//1 +f 771//1 772//1 740//1 +f 740//1 772//1 741//1 +f 772//1 773//1 741//1 +f 741//1 773//1 742//1 +f 773//1 774//1 742//1 +f 742//1 774//1 743//1 +f 774//1 775//1 743//1 +f 743//1 775//1 744//1 +f 775//1 776//1 744//1 +f 744//1 776//1 745//1 +f 776//1 777//1 745//1 +f 745//1 777//1 746//1 +f 777//1 778//1 746//1 +f 746//1 778//1 747//1 +f 778//1 779//1 747//1 +f 747//1 779//1 748//1 +f 779//1 780//1 748//1 +f 748//1 780//1 749//1 +f 780//1 781//1 749//1 +f 749//1 781//1 750//1 +f 781//1 782//1 750//1 +f 750//1 782//1 173//1 +f 782//1 172//1 173//1 +f 237//1 783//1 751//1 +f 783//1 784//1 751//1 +f 751//1 784//1 752//1 +f 784//1 785//1 752//1 +f 752//1 785//1 753//1 +f 785//1 786//1 753//1 +f 753//1 786//1 754//1 +f 786//1 787//1 754//1 +f 754//1 787//1 755//1 +f 787//1 788//1 755//1 +f 755//1 788//1 756//1 +f 788//1 789//1 756//1 +f 756//1 789//1 757//1 +f 789//1 790//1 757//1 +f 757//1 790//1 758//1 +f 790//1 791//1 758//1 +f 758//1 791//1 759//1 +f 791//1 792//1 759//1 +f 759//1 792//1 760//1 +f 792//1 793//1 760//1 +f 760//1 793//1 761//1 +f 793//1 794//1 761//1 +f 761//1 794//1 762//1 +f 794//1 795//1 762//1 +f 762//1 795//1 763//1 +f 795//1 796//1 763//1 +f 763//1 796//1 764//1 +f 796//1 797//1 764//1 +f 764//1 797//1 765//1 +f 797//1 798//1 765//1 +f 765//1 798//1 766//1 +f 798//1 799//1 766//1 +f 766//1 799//1 767//1 +f 799//1 800//1 767//1 +f 767//1 800//1 768//1 +f 800//1 801//1 768//1 +f 768//1 801//1 769//1 +f 801//1 802//1 769//1 +f 769//1 802//1 770//1 +f 802//1 803//1 770//1 +f 770//1 803//1 771//1 +f 803//1 804//1 771//1 +f 771//1 804//1 772//1 +f 804//1 805//1 772//1 +f 772//1 805//1 773//1 +f 805//1 806//1 773//1 +f 773//1 806//1 774//1 +f 806//1 807//1 774//1 +f 774//1 807//1 775//1 +f 807//1 808//1 775//1 +f 775//1 808//1 776//1 +f 808//1 809//1 776//1 +f 776//1 809//1 777//1 +f 809//1 810//1 777//1 +f 777//1 810//1 778//1 +f 810//1 811//1 778//1 +f 778//1 811//1 779//1 +f 811//1 812//1 779//1 +f 779//1 812//1 780//1 +f 812//1 813//1 780//1 +f 780//1 813//1 781//1 +f 813//1 814//1 781//1 +f 781//1 814//1 782//1 +f 814//1 815//1 782//1 +f 782//1 815//1 172//1 +f 815//1 171//1 172//1 +f 238//1 816//1 783//1 +f 816//1 817//1 783//1 +f 783//1 817//1 784//1 +f 817//1 818//1 784//1 +f 784//1 818//1 785//1 +f 818//1 819//1 785//1 +f 785//1 819//1 786//1 +f 819//1 820//1 786//1 +f 786//1 820//1 787//1 +f 820//1 821//1 787//1 +f 787//1 821//1 788//1 +f 821//1 822//1 788//1 +f 788//1 822//1 789//1 +f 822//1 823//1 789//1 +f 789//1 823//1 790//1 +f 823//1 824//1 790//1 +f 790//1 824//1 791//1 +f 824//1 825//1 791//1 +f 791//1 825//1 792//1 +f 825//1 826//1 792//1 +f 792//1 826//1 793//1 +f 826//1 827//1 793//1 +f 793//1 827//1 794//1 +f 827//1 828//1 794//1 +f 794//1 828//1 795//1 +f 828//1 829//1 795//1 +f 795//1 829//1 796//1 +f 829//1 830//1 796//1 +f 796//1 830//1 797//1 +f 830//1 831//1 797//1 +f 797//1 831//1 798//1 +f 831//1 832//1 798//1 +f 798//1 832//1 799//1 +f 832//1 833//1 799//1 +f 799//1 833//1 800//1 +f 833//1 834//1 800//1 +f 800//1 834//1 801//1 +f 834//1 835//1 801//1 +f 801//1 835//1 802//1 +f 835//1 836//1 802//1 +f 802//1 836//1 803//1 +f 836//1 837//1 803//1 +f 803//1 837//1 804//1 +f 837//1 838//1 804//1 +f 804//1 838//1 805//1 +f 838//1 839//1 805//1 +f 805//1 839//1 806//1 +f 839//1 840//1 806//1 +f 806//1 840//1 807//1 +f 840//1 841//1 807//1 +f 807//1 841//1 808//1 +f 841//1 842//1 808//1 +f 808//1 842//1 809//1 +f 842//1 843//1 809//1 +f 809//1 843//1 810//1 +f 843//1 844//1 810//1 +f 810//1 844//1 811//1 +f 844//1 845//1 811//1 +f 811//1 845//1 812//1 +f 845//1 846//1 812//1 +f 812//1 846//1 813//1 +f 846//1 847//1 813//1 +f 813//1 847//1 814//1 +f 847//1 848//1 814//1 +f 814//1 848//1 815//1 +f 848//1 849//1 815//1 +f 815//1 849//1 171//1 +f 849//1 170//1 171//1 +f 239//1 850//1 816//1 +f 850//1 851//1 816//1 +f 816//1 851//1 817//1 +f 851//1 852//1 817//1 +f 817//1 852//1 818//1 +f 852//1 853//1 818//1 +f 818//1 853//1 819//1 +f 853//1 854//1 819//1 +f 819//1 854//1 820//1 +f 854//1 855//1 820//1 +f 820//1 855//1 821//1 +f 855//1 856//1 821//1 +f 821//1 856//1 822//1 +f 856//1 857//1 822//1 +f 822//1 857//1 823//1 +f 857//1 858//1 823//1 +f 823//1 858//1 824//1 +f 858//1 859//1 824//1 +f 824//1 859//1 825//1 +f 859//1 860//1 825//1 +f 825//1 860//1 826//1 +f 860//1 861//1 826//1 +f 826//1 861//1 827//1 +f 861//1 862//1 827//1 +f 827//1 862//1 828//1 +f 862//1 863//1 828//1 +f 828//1 863//1 829//1 +f 863//1 864//1 829//1 +f 829//1 864//1 830//1 +f 864//1 865//1 830//1 +f 830//1 865//1 831//1 +f 865//1 866//1 831//1 +f 831//1 866//1 832//1 +f 866//1 867//1 832//1 +f 832//1 867//1 833//1 +f 867//1 868//1 833//1 +f 833//1 868//1 834//1 +f 868//1 869//1 834//1 +f 834//1 869//1 835//1 +f 869//1 870//1 835//1 +f 835//1 870//1 836//1 +f 870//1 871//1 836//1 +f 836//1 871//1 837//1 +f 871//1 872//1 837//1 +f 837//1 872//1 838//1 +f 872//1 873//1 838//1 +f 838//1 873//1 839//1 +f 873//1 874//1 839//1 +f 839//1 874//1 840//1 +f 874//1 875//1 840//1 +f 840//1 875//1 841//1 +f 875//1 876//1 841//1 +f 841//1 876//1 842//1 +f 876//1 877//1 842//1 +f 842//1 877//1 843//1 +f 877//1 878//1 843//1 +f 843//1 878//1 844//1 +f 878//1 879//1 844//1 +f 844//1 879//1 845//1 +f 879//1 880//1 845//1 +f 845//1 880//1 846//1 +f 880//1 881//1 846//1 +f 846//1 881//1 847//1 +f 881//1 882//1 847//1 +f 847//1 882//1 848//1 +f 882//1 883//1 848//1 +f 848//1 883//1 849//1 +f 883//1 884//1 849//1 +f 849//1 884//1 170//1 +f 884//1 169//1 170//1 +f 240//1 885//1 850//1 +f 885//1 886//1 850//1 +f 850//1 886//1 851//1 +f 886//1 887//1 851//1 +f 851//1 887//1 852//1 +f 887//1 888//1 852//1 +f 852//1 888//1 853//1 +f 888//1 889//1 853//1 +f 853//1 889//1 854//1 +f 889//1 890//1 854//1 +f 854//1 890//1 855//1 +f 890//1 891//1 855//1 +f 855//1 891//1 856//1 +f 891//1 892//1 856//1 +f 856//1 892//1 857//1 +f 892//1 893//1 857//1 +f 857//1 893//1 858//1 +f 893//1 894//1 858//1 +f 858//1 894//1 859//1 +f 894//1 895//1 859//1 +f 859//1 895//1 860//1 +f 895//1 896//1 860//1 +f 860//1 896//1 861//1 +f 896//1 897//1 861//1 +f 861//1 897//1 862//1 +f 897//1 898//1 862//1 +f 862//1 898//1 863//1 +f 898//1 899//1 863//1 +f 863//1 899//1 864//1 +f 899//1 900//1 864//1 +f 864//1 900//1 865//1 +f 900//1 901//1 865//1 +f 865//1 901//1 866//1 +f 901//1 902//1 866//1 +f 866//1 902//1 867//1 +f 902//1 903//1 867//1 +f 867//1 903//1 868//1 +f 903//1 904//1 868//1 +f 868//1 904//1 869//1 +f 904//1 905//1 869//1 +f 869//1 905//1 870//1 +f 905//1 906//1 870//1 +f 870//1 906//1 871//1 +f 906//1 907//1 871//1 +f 871//1 907//1 872//1 +f 907//1 908//1 872//1 +f 872//1 908//1 873//1 +f 908//1 909//1 873//1 +f 873//1 909//1 874//1 +f 909//1 910//1 874//1 +f 874//1 910//1 875//1 +f 910//1 911//1 875//1 +f 875//1 911//1 876//1 +f 911//1 912//1 876//1 +f 876//1 912//1 877//1 +f 912//1 913//1 877//1 +f 877//1 913//1 878//1 +f 913//1 914//1 878//1 +f 878//1 914//1 879//1 +f 914//1 915//1 879//1 +f 879//1 915//1 880//1 +f 915//1 916//1 880//1 +f 880//1 916//1 881//1 +f 916//1 917//1 881//1 +f 881//1 917//1 882//1 +f 917//1 918//1 882//1 +f 882//1 918//1 883//1 +f 918//1 919//1 883//1 +f 883//1 919//1 884//1 +f 919//1 920//1 884//1 +f 884//1 920//1 169//1 +f 920//1 168//1 169//1 +f 241//1 921//1 885//1 +f 921//1 922//1 885//1 +f 885//1 922//1 886//1 +f 922//1 923//1 886//1 +f 886//1 923//1 887//1 +f 923//1 924//1 887//1 +f 887//1 924//1 888//1 +f 924//1 925//1 888//1 +f 888//1 925//1 889//1 +f 925//1 926//1 889//1 +f 889//1 926//1 890//1 +f 926//1 927//1 890//1 +f 890//1 927//1 891//1 +f 927//1 928//1 891//1 +f 891//1 928//1 892//1 +f 928//1 929//1 892//1 +f 892//1 929//1 893//1 +f 929//1 930//1 893//1 +f 893//1 930//1 894//1 +f 930//1 931//1 894//1 +f 894//1 931//1 895//1 +f 931//1 932//1 895//1 +f 895//1 932//1 896//1 +f 932//1 933//1 896//1 +f 896//1 933//1 897//1 +f 933//1 934//1 897//1 +f 897//1 934//1 898//1 +f 934//1 935//1 898//1 +f 898//1 935//1 899//1 +f 935//1 936//1 899//1 +f 899//1 936//1 900//1 +f 936//1 937//1 900//1 +f 900//1 937//1 901//1 +f 937//1 938//1 901//1 +f 901//1 938//1 902//1 +f 938//1 939//1 902//1 +f 902//1 939//1 903//1 +f 939//1 940//1 903//1 +f 903//1 940//1 904//1 +f 940//1 941//1 904//1 +f 904//1 941//1 905//1 +f 941//1 942//1 905//1 +f 905//1 942//1 906//1 +f 942//1 943//1 906//1 +f 906//1 943//1 907//1 +f 943//1 944//1 907//1 +f 907//1 944//1 908//1 +f 944//1 945//1 908//1 +f 908//1 945//1 909//1 +f 945//1 946//1 909//1 +f 909//1 946//1 910//1 +f 946//1 947//1 910//1 +f 910//1 947//1 911//1 +f 947//1 948//1 911//1 +f 911//1 948//1 912//1 +f 948//1 949//1 912//1 +f 912//1 949//1 913//1 +f 949//1 950//1 913//1 +f 913//1 950//1 914//1 +f 950//1 951//1 914//1 +f 914//1 951//1 915//1 +f 951//1 952//1 915//1 +f 915//1 952//1 916//1 +f 952//1 953//1 916//1 +f 916//1 953//1 917//1 +f 953//1 954//1 917//1 +f 917//1 954//1 918//1 +f 954//1 955//1 918//1 +f 918//1 955//1 919//1 +f 955//1 956//1 919//1 +f 919//1 956//1 920//1 +f 956//1 957//1 920//1 +f 920//1 957//1 168//1 +f 957//1 167//1 168//1 +f 242//1 958//1 921//1 +f 958//1 959//1 921//1 +f 921//1 959//1 922//1 +f 959//1 960//1 922//1 +f 922//1 960//1 923//1 +f 960//1 961//1 923//1 +f 923//1 961//1 924//1 +f 961//1 962//1 924//1 +f 924//1 962//1 925//1 +f 962//1 963//1 925//1 +f 925//1 963//1 926//1 +f 963//1 964//1 926//1 +f 926//1 964//1 927//1 +f 964//1 965//1 927//1 +f 927//1 965//1 928//1 +f 965//1 966//1 928//1 +f 928//1 966//1 929//1 +f 966//1 967//1 929//1 +f 929//1 967//1 930//1 +f 967//1 968//1 930//1 +f 930//1 968//1 931//1 +f 968//1 969//1 931//1 +f 931//1 969//1 932//1 +f 969//1 970//1 932//1 +f 932//1 970//1 933//1 +f 970//1 971//1 933//1 +f 933//1 971//1 934//1 +f 971//1 972//1 934//1 +f 934//1 972//1 935//1 +f 972//1 973//1 935//1 +f 935//1 973//1 936//1 +f 973//1 974//1 936//1 +f 936//1 974//1 937//1 +f 974//1 975//1 937//1 +f 937//1 975//1 938//1 +f 975//1 976//1 938//1 +f 938//1 976//1 939//1 +f 976//1 977//1 939//1 +f 939//1 977//1 940//1 +f 977//1 978//1 940//1 +f 940//1 978//1 941//1 +f 978//1 979//1 941//1 +f 941//1 979//1 942//1 +f 979//1 980//1 942//1 +f 942//1 980//1 943//1 +f 980//1 981//1 943//1 +f 943//1 981//1 944//1 +f 981//1 982//1 944//1 +f 944//1 982//1 945//1 +f 982//1 983//1 945//1 +f 945//1 983//1 946//1 +f 983//1 984//1 946//1 +f 946//1 984//1 947//1 +f 984//1 985//1 947//1 +f 947//1 985//1 948//1 +f 985//1 986//1 948//1 +f 948//1 986//1 949//1 +f 986//1 987//1 949//1 +f 949//1 987//1 950//1 +f 987//1 988//1 950//1 +f 950//1 988//1 951//1 +f 988//1 989//1 951//1 +f 951//1 989//1 952//1 +f 989//1 990//1 952//1 +f 952//1 990//1 953//1 +f 990//1 991//1 953//1 +f 953//1 991//1 954//1 +f 991//1 992//1 954//1 +f 954//1 992//1 955//1 +f 992//1 993//1 955//1 +f 955//1 993//1 956//1 +f 993//1 994//1 956//1 +f 956//1 994//1 957//1 +f 994//1 995//1 957//1 +f 957//1 995//1 167//1 +f 995//1 166//1 167//1 +f 243//1 996//1 958//1 +f 996//1 997//1 958//1 +f 958//1 997//1 959//1 +f 997//1 998//1 959//1 +f 959//1 998//1 960//1 +f 998//1 999//1 960//1 +f 960//1 999//1 961//1 +f 999//1 1000//1 961//1 +f 961//1 1000//1 962//1 +f 1000//1 1001//1 962//1 +f 962//1 1001//1 963//1 +f 1001//1 1002//1 963//1 +f 963//1 1002//1 964//1 +f 1002//1 1003//1 964//1 +f 964//1 1003//1 965//1 +f 1003//1 1004//1 965//1 +f 965//1 1004//1 966//1 +f 1004//1 1005//1 966//1 +f 966//1 1005//1 967//1 +f 1005//1 1006//1 967//1 +f 967//1 1006//1 968//1 +f 1006//1 1007//1 968//1 +f 968//1 1007//1 969//1 +f 1007//1 1008//1 969//1 +f 969//1 1008//1 970//1 +f 1008//1 1009//1 970//1 +f 970//1 1009//1 971//1 +f 1009//1 1010//1 971//1 +f 971//1 1010//1 972//1 +f 1010//1 1011//1 972//1 +f 972//1 1011//1 973//1 +f 1011//1 1012//1 973//1 +f 973//1 1012//1 974//1 +f 1012//1 1013//1 974//1 +f 974//1 1013//1 975//1 +f 1013//1 1014//1 975//1 +f 975//1 1014//1 976//1 +f 1014//1 1015//1 976//1 +f 976//1 1015//1 977//1 +f 1015//1 1016//1 977//1 +f 977//1 1016//1 978//1 +f 1016//1 1017//1 978//1 +f 978//1 1017//1 979//1 +f 1017//1 1018//1 979//1 +f 979//1 1018//1 980//1 +f 1018//1 1019//1 980//1 +f 980//1 1019//1 981//1 +f 1019//1 1020//1 981//1 +f 981//1 1020//1 982//1 +f 1020//1 1021//1 982//1 +f 982//1 1021//1 983//1 +f 1021//1 1022//1 983//1 +f 983//1 1022//1 984//1 +f 1022//1 1023//1 984//1 +f 984//1 1023//1 985//1 +f 1023//1 1024//1 985//1 +f 985//1 1024//1 986//1 +f 1024//1 1025//1 986//1 +f 986//1 1025//1 987//1 +f 1025//1 1026//1 987//1 +f 987//1 1026//1 988//1 +f 1026//1 1027//1 988//1 +f 988//1 1027//1 989//1 +f 1027//1 1028//1 989//1 +f 989//1 1028//1 990//1 +f 1028//1 1029//1 990//1 +f 990//1 1029//1 991//1 +f 1029//1 1030//1 991//1 +f 991//1 1030//1 992//1 +f 1030//1 1031//1 992//1 +f 992//1 1031//1 993//1 +f 1031//1 1032//1 993//1 +f 993//1 1032//1 994//1 +f 1032//1 1033//1 994//1 +f 994//1 1033//1 995//1 +f 1033//1 1034//1 995//1 +f 995//1 1034//1 166//1 +f 1034//1 165//1 166//1 +f 244//1 1035//1 996//1 +f 1035//1 1036//1 996//1 +f 996//1 1036//1 997//1 +f 1036//1 1037//1 997//1 +f 997//1 1037//1 998//1 +f 1037//1 1038//1 998//1 +f 998//1 1038//1 999//1 +f 1038//1 1039//1 999//1 +f 999//1 1039//1 1000//1 +f 1039//1 1040//1 1000//1 +f 1000//1 1040//1 1001//1 +f 1040//1 1041//1 1001//1 +f 1001//1 1041//1 1002//1 +f 1041//1 1042//1 1002//1 +f 1002//1 1042//1 1003//1 +f 1042//1 1043//1 1003//1 +f 1003//1 1043//1 1004//1 +f 1043//1 1044//1 1004//1 +f 1004//1 1044//1 1005//1 +f 1044//1 1045//1 1005//1 +f 1005//1 1045//1 1006//1 +f 1045//1 1046//1 1006//1 +f 1006//1 1046//1 1007//1 +f 1046//1 1047//1 1007//1 +f 1007//1 1047//1 1008//1 +f 1047//1 1048//1 1008//1 +f 1008//1 1048//1 1009//1 +f 1048//1 1049//1 1009//1 +f 1009//1 1049//1 1010//1 +f 1049//1 1050//1 1010//1 +f 1010//1 1050//1 1011//1 +f 1050//1 1051//1 1011//1 +f 1011//1 1051//1 1012//1 +f 1051//1 1052//1 1012//1 +f 1012//1 1052//1 1013//1 +f 1052//1 1053//1 1013//1 +f 1013//1 1053//1 1014//1 +f 1053//1 1054//1 1014//1 +f 1014//1 1054//1 1015//1 +f 1054//1 1055//1 1015//1 +f 1015//1 1055//1 1016//1 +f 1055//1 1056//1 1016//1 +f 1016//1 1056//1 1017//1 +f 1056//1 1057//1 1017//1 +f 1017//1 1057//1 1018//1 +f 1057//1 1058//1 1018//1 +f 1018//1 1058//1 1019//1 +f 1058//1 1059//1 1019//1 +f 1019//1 1059//1 1020//1 +f 1059//1 1060//1 1020//1 +f 1020//1 1060//1 1021//1 +f 1060//1 1061//1 1021//1 +f 1021//1 1061//1 1022//1 +f 1061//1 1062//1 1022//1 +f 1022//1 1062//1 1023//1 +f 1062//1 1063//1 1023//1 +f 1023//1 1063//1 1024//1 +f 1063//1 1064//1 1024//1 +f 1024//1 1064//1 1025//1 +f 1064//1 1065//1 1025//1 +f 1025//1 1065//1 1026//1 +f 1065//1 1066//1 1026//1 +f 1026//1 1066//1 1027//1 +f 1066//1 1067//1 1027//1 +f 1027//1 1067//1 1028//1 +f 1067//1 1068//1 1028//1 +f 1028//1 1068//1 1029//1 +f 1068//1 1069//1 1029//1 +f 1029//1 1069//1 1030//1 +f 1069//1 1070//1 1030//1 +f 1030//1 1070//1 1031//1 +f 1070//1 1071//1 1031//1 +f 1031//1 1071//1 1032//1 +f 1071//1 1072//1 1032//1 +f 1032//1 1072//1 1033//1 +f 1072//1 1073//1 1033//1 +f 1033//1 1073//1 1034//1 +f 1073//1 1074//1 1034//1 +f 1034//1 1074//1 165//1 +f 1074//1 164//1 165//1 +f 245//1 1075//1 1035//1 +f 1075//1 1076//1 1035//1 +f 1035//1 1076//1 1036//1 +f 1076//1 1077//1 1036//1 +f 1036//1 1077//1 1037//1 +f 1077//1 1078//1 1037//1 +f 1037//1 1078//1 1038//1 +f 1078//1 1079//1 1038//1 +f 1038//1 1079//1 1039//1 +f 1079//1 1080//1 1039//1 +f 1039//1 1080//1 1040//1 +f 1080//1 1081//1 1040//1 +f 1040//1 1081//1 1041//1 +f 1081//1 1082//1 1041//1 +f 1041//1 1082//1 1042//1 +f 1082//1 1083//1 1042//1 +f 1042//1 1083//1 1043//1 +f 1083//1 1084//1 1043//1 +f 1043//1 1084//1 1044//1 +f 1084//1 1085//1 1044//1 +f 1044//1 1085//1 1045//1 +f 1085//1 1086//1 1045//1 +f 1045//1 1086//1 1046//1 +f 1086//1 1087//1 1046//1 +f 1046//1 1087//1 1047//1 +f 1087//1 1088//1 1047//1 +f 1047//1 1088//1 1048//1 +f 1088//1 1089//1 1048//1 +f 1048//1 1089//1 1049//1 +f 1089//1 1090//1 1049//1 +f 1049//1 1090//1 1050//1 +f 1090//1 1091//1 1050//1 +f 1050//1 1091//1 1051//1 +f 1091//1 1092//1 1051//1 +f 1051//1 1092//1 1052//1 +f 1092//1 1093//1 1052//1 +f 1052//1 1093//1 1053//1 +f 1093//1 1094//1 1053//1 +f 1053//1 1094//1 1054//1 +f 1094//1 1095//1 1054//1 +f 1054//1 1095//1 1055//1 +f 1095//1 1096//1 1055//1 +f 1055//1 1096//1 1056//1 +f 1096//1 1097//1 1056//1 +f 1056//1 1097//1 1057//1 +f 1097//1 1098//1 1057//1 +f 1057//1 1098//1 1058//1 +f 1098//1 1099//1 1058//1 +f 1058//1 1099//1 1059//1 +f 1099//1 1100//1 1059//1 +f 1059//1 1100//1 1060//1 +f 1100//1 1101//1 1060//1 +f 1060//1 1101//1 1061//1 +f 1101//1 1102//1 1061//1 +f 1061//1 1102//1 1062//1 +f 1102//1 1103//1 1062//1 +f 1062//1 1103//1 1063//1 +f 1103//1 1104//1 1063//1 +f 1063//1 1104//1 1064//1 +f 1104//1 1105//1 1064//1 +f 1064//1 1105//1 1065//1 +f 1105//1 1106//1 1065//1 +f 1065//1 1106//1 1066//1 +f 1106//1 1107//1 1066//1 +f 1066//1 1107//1 1067//1 +f 1107//1 1108//1 1067//1 +f 1067//1 1108//1 1068//1 +f 1108//1 1109//1 1068//1 +f 1068//1 1109//1 1069//1 +f 1109//1 1110//1 1069//1 +f 1069//1 1110//1 1070//1 +f 1110//1 1111//1 1070//1 +f 1070//1 1111//1 1071//1 +f 1111//1 1112//1 1071//1 +f 1071//1 1112//1 1072//1 +f 1112//1 1113//1 1072//1 +f 1072//1 1113//1 1073//1 +f 1113//1 1114//1 1073//1 +f 1073//1 1114//1 1074//1 +f 1114//1 1115//1 1074//1 +f 1074//1 1115//1 164//1 +f 1115//1 163//1 164//1 +f 246//1 1116//1 1075//1 +f 1116//1 1117//1 1075//1 +f 1075//1 1117//1 1076//1 +f 1117//1 1118//1 1076//1 +f 1076//1 1118//1 1077//1 +f 1118//1 1119//1 1077//1 +f 1077//1 1119//1 1078//1 +f 1119//1 1120//1 1078//1 +f 1078//1 1120//1 1079//1 +f 1120//1 1121//1 1079//1 +f 1079//1 1121//1 1080//1 +f 1121//1 1122//1 1080//1 +f 1080//1 1122//1 1081//1 +f 1122//1 1123//1 1081//1 +f 1081//1 1123//1 1082//1 +f 1123//1 1124//1 1082//1 +f 1082//1 1124//1 1083//1 +f 1124//1 1125//1 1083//1 +f 1083//1 1125//1 1084//1 +f 1125//1 1126//1 1084//1 +f 1084//1 1126//1 1085//1 +f 1126//1 1127//1 1085//1 +f 1085//1 1127//1 1086//1 +f 1127//1 1128//1 1086//1 +f 1086//1 1128//1 1087//1 +f 1128//1 1129//1 1087//1 +f 1087//1 1129//1 1088//1 +f 1129//1 1130//1 1088//1 +f 1088//1 1130//1 1089//1 +f 1130//1 1131//1 1089//1 +f 1089//1 1131//1 1090//1 +f 1131//1 1132//1 1090//1 +f 1090//1 1132//1 1091//1 +f 1132//1 1133//1 1091//1 +f 1091//1 1133//1 1092//1 +f 1133//1 1134//1 1092//1 +f 1092//1 1134//1 1093//1 +f 1134//1 1135//1 1093//1 +f 1093//1 1135//1 1094//1 +f 1135//1 1136//1 1094//1 +f 1094//1 1136//1 1095//1 +f 1136//1 1137//1 1095//1 +f 1095//1 1137//1 1096//1 +f 1137//1 1138//1 1096//1 +f 1096//1 1138//1 1097//1 +f 1138//1 1139//1 1097//1 +f 1097//1 1139//1 1098//1 +f 1139//1 1140//1 1098//1 +f 1098//1 1140//1 1099//1 +f 1140//1 1141//1 1099//1 +f 1099//1 1141//1 1100//1 +f 1141//1 1142//1 1100//1 +f 1100//1 1142//1 1101//1 +f 1142//1 1143//1 1101//1 +f 1101//1 1143//1 1102//1 +f 1143//1 1144//1 1102//1 +f 1102//1 1144//1 1103//1 +f 1144//1 1145//1 1103//1 +f 1103//1 1145//1 1104//1 +f 1145//1 1146//1 1104//1 +f 1104//1 1146//1 1105//1 +f 1146//1 1147//1 1105//1 +f 1105//1 1147//1 1106//1 +f 1147//1 1148//1 1106//1 +f 1106//1 1148//1 1107//1 +f 1148//1 1149//1 1107//1 +f 1107//1 1149//1 1108//1 +f 1149//1 1150//1 1108//1 +f 1108//1 1150//1 1109//1 +f 1150//1 1151//1 1109//1 +f 1109//1 1151//1 1110//1 +f 1151//1 1152//1 1110//1 +f 1110//1 1152//1 1111//1 +f 1152//1 1153//1 1111//1 +f 1111//1 1153//1 1112//1 +f 1153//1 1154//1 1112//1 +f 1112//1 1154//1 1113//1 +f 1154//1 1155//1 1113//1 +f 1113//1 1155//1 1114//1 +f 1155//1 1156//1 1114//1 +f 1114//1 1156//1 1115//1 +f 1156//1 1157//1 1115//1 +f 1115//1 1157//1 163//1 +f 1157//1 162//1 163//1 +f 247//1 1158//1 1116//1 +f 1158//1 1159//1 1116//1 +f 1116//1 1159//1 1117//1 +f 1159//1 1160//1 1117//1 +f 1117//1 1160//1 1118//1 +f 1160//1 1161//1 1118//1 +f 1118//1 1161//1 1119//1 +f 1161//1 1162//1 1119//1 +f 1119//1 1162//1 1120//1 +f 1162//1 1163//1 1120//1 +f 1120//1 1163//1 1121//1 +f 1163//1 1164//1 1121//1 +f 1121//1 1164//1 1122//1 +f 1164//1 1165//1 1122//1 +f 1122//1 1165//1 1123//1 +f 1165//1 1166//1 1123//1 +f 1123//1 1166//1 1124//1 +f 1166//1 1167//1 1124//1 +f 1124//1 1167//1 1125//1 +f 1167//1 1168//1 1125//1 +f 1125//1 1168//1 1126//1 +f 1168//1 1169//1 1126//1 +f 1126//1 1169//1 1127//1 +f 1169//1 1170//1 1127//1 +f 1127//1 1170//1 1128//1 +f 1170//1 1171//1 1128//1 +f 1128//1 1171//1 1129//1 +f 1171//1 1172//1 1129//1 +f 1129//1 1172//1 1130//1 +f 1172//1 1173//1 1130//1 +f 1130//1 1173//1 1131//1 +f 1173//1 1174//1 1131//1 +f 1131//1 1174//1 1132//1 +f 1174//1 1175//1 1132//1 +f 1132//1 1175//1 1133//1 +f 1175//1 1176//1 1133//1 +f 1133//1 1176//1 1134//1 +f 1176//1 1177//1 1134//1 +f 1134//1 1177//1 1135//1 +f 1177//1 1178//1 1135//1 +f 1135//1 1178//1 1136//1 +f 1178//1 1179//1 1136//1 +f 1136//1 1179//1 1137//1 +f 1179//1 1180//1 1137//1 +f 1137//1 1180//1 1138//1 +f 1180//1 1181//1 1138//1 +f 1138//1 1181//1 1139//1 +f 1181//1 1182//1 1139//1 +f 1139//1 1182//1 1140//1 +f 1182//1 1183//1 1140//1 +f 1140//1 1183//1 1141//1 +f 1183//1 1184//1 1141//1 +f 1141//1 1184//1 1142//1 +f 1184//1 1185//1 1142//1 +f 1142//1 1185//1 1143//1 +f 1185//1 1186//1 1143//1 +f 1143//1 1186//1 1144//1 +f 1186//1 1187//1 1144//1 +f 1144//1 1187//1 1145//1 +f 1187//1 1188//1 1145//1 +f 1145//1 1188//1 1146//1 +f 1188//1 1189//1 1146//1 +f 1146//1 1189//1 1147//1 +f 1189//1 1190//1 1147//1 +f 1147//1 1190//1 1148//1 +f 1190//1 1191//1 1148//1 +f 1148//1 1191//1 1149//1 +f 1191//1 1192//1 1149//1 +f 1149//1 1192//1 1150//1 +f 1192//1 1193//1 1150//1 +f 1150//1 1193//1 1151//1 +f 1193//1 1194//1 1151//1 +f 1151//1 1194//1 1152//1 +f 1194//1 1195//1 1152//1 +f 1152//1 1195//1 1153//1 +f 1195//1 1196//1 1153//1 +f 1153//1 1196//1 1154//1 +f 1196//1 1197//1 1154//1 +f 1154//1 1197//1 1155//1 +f 1197//1 1198//1 1155//1 +f 1155//1 1198//1 1156//1 +f 1198//1 1199//1 1156//1 +f 1156//1 1199//1 1157//1 +f 1199//1 1200//1 1157//1 +f 1157//1 1200//1 162//1 +f 1200//1 161//1 162//1 +f 248//1 1201//1 1158//1 +f 1201//1 1202//1 1158//1 +f 1158//1 1202//1 1159//1 +f 1202//1 1203//1 1159//1 +f 1159//1 1203//1 1160//1 +f 1203//1 1204//1 1160//1 +f 1160//1 1204//1 1161//1 +f 1204//1 1205//1 1161//1 +f 1161//1 1205//1 1162//1 +f 1205//1 1206//1 1162//1 +f 1162//1 1206//1 1163//1 +f 1206//1 1207//1 1163//1 +f 1163//1 1207//1 1164//1 +f 1207//1 1208//1 1164//1 +f 1164//1 1208//1 1165//1 +f 1208//1 1209//1 1165//1 +f 1165//1 1209//1 1166//1 +f 1209//1 1210//1 1166//1 +f 1166//1 1210//1 1167//1 +f 1210//1 1211//1 1167//1 +f 1167//1 1211//1 1168//1 +f 1211//1 1212//1 1168//1 +f 1168//1 1212//1 1169//1 +f 1212//1 1213//1 1169//1 +f 1169//1 1213//1 1170//1 +f 1213//1 1214//1 1170//1 +f 1170//1 1214//1 1171//1 +f 1214//1 1215//1 1171//1 +f 1171//1 1215//1 1172//1 +f 1215//1 1216//1 1172//1 +f 1172//1 1216//1 1173//1 +f 1216//1 1217//1 1173//1 +f 1173//1 1217//1 1174//1 +f 1217//1 1218//1 1174//1 +f 1174//1 1218//1 1175//1 +f 1218//1 1219//1 1175//1 +f 1175//1 1219//1 1176//1 +f 1219//1 1220//1 1176//1 +f 1176//1 1220//1 1177//1 +f 1220//1 1221//1 1177//1 +f 1177//1 1221//1 1178//1 +f 1221//1 1222//1 1178//1 +f 1178//1 1222//1 1179//1 +f 1222//1 1223//1 1179//1 +f 1179//1 1223//1 1180//1 +f 1223//1 1224//1 1180//1 +f 1180//1 1224//1 1181//1 +f 1224//1 1225//1 1181//1 +f 1181//1 1225//1 1182//1 +f 1225//1 1226//1 1182//1 +f 1182//1 1226//1 1183//1 +f 1226//1 1227//1 1183//1 +f 1183//1 1227//1 1184//1 +f 1227//1 1228//1 1184//1 +f 1184//1 1228//1 1185//1 +f 1228//1 1229//1 1185//1 +f 1185//1 1229//1 1186//1 +f 1229//1 1230//1 1186//1 +f 1186//1 1230//1 1187//1 +f 1230//1 1231//1 1187//1 +f 1187//1 1231//1 1188//1 +f 1231//1 1232//1 1188//1 +f 1188//1 1232//1 1189//1 +f 1232//1 1233//1 1189//1 +f 1189//1 1233//1 1190//1 +f 1233//1 1234//1 1190//1 +f 1190//1 1234//1 1191//1 +f 1234//1 1235//1 1191//1 +f 1191//1 1235//1 1192//1 +f 1235//1 1236//1 1192//1 +f 1192//1 1236//1 1193//1 +f 1236//1 1237//1 1193//1 +f 1193//1 1237//1 1194//1 +f 1237//1 1238//1 1194//1 +f 1194//1 1238//1 1195//1 +f 1238//1 1239//1 1195//1 +f 1195//1 1239//1 1196//1 +f 1239//1 1240//1 1196//1 +f 1196//1 1240//1 1197//1 +f 1240//1 1241//1 1197//1 +f 1197//1 1241//1 1198//1 +f 1241//1 1242//1 1198//1 +f 1198//1 1242//1 1199//1 +f 1242//1 1243//1 1199//1 +f 1199//1 1243//1 1200//1 +f 1243//1 1244//1 1200//1 +f 1200//1 1244//1 161//1 +f 1244//1 160//1 161//1 +f 249//1 1245//1 1201//1 +f 1245//1 1246//1 1201//1 +f 1201//1 1246//1 1202//1 +f 1246//1 1247//1 1202//1 +f 1202//1 1247//1 1203//1 +f 1247//1 1248//1 1203//1 +f 1203//1 1248//1 1204//1 +f 1248//1 1249//1 1204//1 +f 1204//1 1249//1 1205//1 +f 1249//1 1250//1 1205//1 +f 1205//1 1250//1 1206//1 +f 1250//1 1251//1 1206//1 +f 1206//1 1251//1 1207//1 +f 1251//1 1252//1 1207//1 +f 1207//1 1252//1 1208//1 +f 1252//1 1253//1 1208//1 +f 1208//1 1253//1 1209//1 +f 1253//1 1254//1 1209//1 +f 1209//1 1254//1 1210//1 +f 1254//1 1255//1 1210//1 +f 1210//1 1255//1 1211//1 +f 1255//1 1256//1 1211//1 +f 1211//1 1256//1 1212//1 +f 1256//1 1257//1 1212//1 +f 1212//1 1257//1 1213//1 +f 1257//1 1258//1 1213//1 +f 1213//1 1258//1 1214//1 +f 1258//1 1259//1 1214//1 +f 1214//1 1259//1 1215//1 +f 1259//1 1260//1 1215//1 +f 1215//1 1260//1 1216//1 +f 1260//1 1261//1 1216//1 +f 1216//1 1261//1 1217//1 +f 1261//1 1262//1 1217//1 +f 1217//1 1262//1 1218//1 +f 1262//1 1263//1 1218//1 +f 1218//1 1263//1 1219//1 +f 1263//1 1264//1 1219//1 +f 1219//1 1264//1 1220//1 +f 1264//1 1265//1 1220//1 +f 1220//1 1265//1 1221//1 +f 1265//1 1266//1 1221//1 +f 1221//1 1266//1 1222//1 +f 1266//1 1267//1 1222//1 +f 1222//1 1267//1 1223//1 +f 1267//1 1268//1 1223//1 +f 1223//1 1268//1 1224//1 +f 1268//1 1269//1 1224//1 +f 1224//1 1269//1 1225//1 +f 1269//1 1270//1 1225//1 +f 1225//1 1270//1 1226//1 +f 1270//1 1271//1 1226//1 +f 1226//1 1271//1 1227//1 +f 1271//1 1272//1 1227//1 +f 1227//1 1272//1 1228//1 +f 1272//1 1273//1 1228//1 +f 1228//1 1273//1 1229//1 +f 1273//1 1274//1 1229//1 +f 1229//1 1274//1 1230//1 +f 1274//1 1275//1 1230//1 +f 1230//1 1275//1 1231//1 +f 1275//1 1276//1 1231//1 +f 1231//1 1276//1 1232//1 +f 1276//1 1277//1 1232//1 +f 1232//1 1277//1 1233//1 +f 1277//1 1278//1 1233//1 +f 1233//1 1278//1 1234//1 +f 1278//1 1279//1 1234//1 +f 1234//1 1279//1 1235//1 +f 1279//1 1280//1 1235//1 +f 1235//1 1280//1 1236//1 +f 1280//1 1281//1 1236//1 +f 1236//1 1281//1 1237//1 +f 1281//1 1282//1 1237//1 +f 1237//1 1282//1 1238//1 +f 1282//1 1283//1 1238//1 +f 1238//1 1283//1 1239//1 +f 1283//1 1284//1 1239//1 +f 1239//1 1284//1 1240//1 +f 1284//1 1285//1 1240//1 +f 1240//1 1285//1 1241//1 +f 1285//1 1286//1 1241//1 +f 1241//1 1286//1 1242//1 +f 1286//1 1287//1 1242//1 +f 1242//1 1287//1 1243//1 +f 1287//1 1288//1 1243//1 +f 1243//1 1288//1 1244//1 +f 1288//1 1289//1 1244//1 +f 1244//1 1289//1 160//1 +f 1289//1 159//1 160//1 +f 250//1 1290//1 1245//1 +f 1290//1 1291//1 1245//1 +f 1245//1 1291//1 1246//1 +f 1291//1 1292//1 1246//1 +f 1246//1 1292//1 1247//1 +f 1292//1 1293//1 1247//1 +f 1247//1 1293//1 1248//1 +f 1293//1 1294//1 1248//1 +f 1248//1 1294//1 1249//1 +f 1294//1 1295//1 1249//1 +f 1249//1 1295//1 1250//1 +f 1295//1 1296//1 1250//1 +f 1250//1 1296//1 1251//1 +f 1296//1 1297//1 1251//1 +f 1251//1 1297//1 1252//1 +f 1297//1 1298//1 1252//1 +f 1252//1 1298//1 1253//1 +f 1298//1 1299//1 1253//1 +f 1253//1 1299//1 1254//1 +f 1299//1 1300//1 1254//1 +f 1254//1 1300//1 1255//1 +f 1300//1 1301//1 1255//1 +f 1255//1 1301//1 1256//1 +f 1301//1 1302//1 1256//1 +f 1256//1 1302//1 1257//1 +f 1302//1 1303//1 1257//1 +f 1257//1 1303//1 1258//1 +f 1303//1 1304//1 1258//1 +f 1258//1 1304//1 1259//1 +f 1304//1 1305//1 1259//1 +f 1259//1 1305//1 1260//1 +f 1305//1 1306//1 1260//1 +f 1260//1 1306//1 1261//1 +f 1306//1 1307//1 1261//1 +f 1261//1 1307//1 1262//1 +f 1307//1 1308//1 1262//1 +f 1262//1 1308//1 1263//1 +f 1308//1 1309//1 1263//1 +f 1263//1 1309//1 1264//1 +f 1309//1 1310//1 1264//1 +f 1264//1 1310//1 1265//1 +f 1310//1 1311//1 1265//1 +f 1265//1 1311//1 1266//1 +f 1311//1 1312//1 1266//1 +f 1266//1 1312//1 1267//1 +f 1312//1 1313//1 1267//1 +f 1267//1 1313//1 1268//1 +f 1313//1 1314//1 1268//1 +f 1268//1 1314//1 1269//1 +f 1314//1 1315//1 1269//1 +f 1269//1 1315//1 1270//1 +f 1315//1 1316//1 1270//1 +f 1270//1 1316//1 1271//1 +f 1316//1 1317//1 1271//1 +f 1271//1 1317//1 1272//1 +f 1317//1 1318//1 1272//1 +f 1272//1 1318//1 1273//1 +f 1318//1 1319//1 1273//1 +f 1273//1 1319//1 1274//1 +f 1319//1 1320//1 1274//1 +f 1274//1 1320//1 1275//1 +f 1320//1 1321//1 1275//1 +f 1275//1 1321//1 1276//1 +f 1321//1 1322//1 1276//1 +f 1276//1 1322//1 1277//1 +f 1322//1 1323//1 1277//1 +f 1277//1 1323//1 1278//1 +f 1323//1 1324//1 1278//1 +f 1278//1 1324//1 1279//1 +f 1324//1 1325//1 1279//1 +f 1279//1 1325//1 1280//1 +f 1325//1 1326//1 1280//1 +f 1280//1 1326//1 1281//1 +f 1326//1 1327//1 1281//1 +f 1281//1 1327//1 1282//1 +f 1327//1 1328//1 1282//1 +f 1282//1 1328//1 1283//1 +f 1328//1 1329//1 1283//1 +f 1283//1 1329//1 1284//1 +f 1329//1 1330//1 1284//1 +f 1284//1 1330//1 1285//1 +f 1330//1 1331//1 1285//1 +f 1285//1 1331//1 1286//1 +f 1331//1 1332//1 1286//1 +f 1286//1 1332//1 1287//1 +f 1332//1 1333//1 1287//1 +f 1287//1 1333//1 1288//1 +f 1333//1 1334//1 1288//1 +f 1288//1 1334//1 1289//1 +f 1334//1 1335//1 1289//1 +f 1289//1 1335//1 159//1 +f 1335//1 158//1 159//1 +f 251//1 1336//1 1290//1 +f 1336//1 1337//1 1290//1 +f 1290//1 1337//1 1291//1 +f 1337//1 1338//1 1291//1 +f 1291//1 1338//1 1292//1 +f 1338//1 1339//1 1292//1 +f 1292//1 1339//1 1293//1 +f 1339//1 1340//1 1293//1 +f 1293//1 1340//1 1294//1 +f 1340//1 1341//1 1294//1 +f 1294//1 1341//1 1295//1 +f 1341//1 1342//1 1295//1 +f 1295//1 1342//1 1296//1 +f 1342//1 1343//1 1296//1 +f 1296//1 1343//1 1297//1 +f 1343//1 1344//1 1297//1 +f 1297//1 1344//1 1298//1 +f 1344//1 1345//1 1298//1 +f 1298//1 1345//1 1299//1 +f 1345//1 1346//1 1299//1 +f 1299//1 1346//1 1300//1 +f 1346//1 1347//1 1300//1 +f 1300//1 1347//1 1301//1 +f 1347//1 1348//1 1301//1 +f 1301//1 1348//1 1302//1 +f 1348//1 1349//1 1302//1 +f 1302//1 1349//1 1303//1 +f 1349//1 1350//1 1303//1 +f 1303//1 1350//1 1304//1 +f 1350//1 1351//1 1304//1 +f 1304//1 1351//1 1305//1 +f 1351//1 1352//1 1305//1 +f 1305//1 1352//1 1306//1 +f 1352//1 1353//1 1306//1 +f 1306//1 1353//1 1307//1 +f 1353//1 1354//1 1307//1 +f 1307//1 1354//1 1308//1 +f 1354//1 1355//1 1308//1 +f 1308//1 1355//1 1309//1 +f 1355//1 1356//1 1309//1 +f 1309//1 1356//1 1310//1 +f 1356//1 1357//1 1310//1 +f 1310//1 1357//1 1311//1 +f 1357//1 1358//1 1311//1 +f 1311//1 1358//1 1312//1 +f 1358//1 1359//1 1312//1 +f 1312//1 1359//1 1313//1 +f 1359//1 1360//1 1313//1 +f 1313//1 1360//1 1314//1 +f 1360//1 1361//1 1314//1 +f 1314//1 1361//1 1315//1 +f 1361//1 1362//1 1315//1 +f 1315//1 1362//1 1316//1 +f 1362//1 1363//1 1316//1 +f 1316//1 1363//1 1317//1 +f 1363//1 1364//1 1317//1 +f 1317//1 1364//1 1318//1 +f 1364//1 1365//1 1318//1 +f 1318//1 1365//1 1319//1 +f 1365//1 1366//1 1319//1 +f 1319//1 1366//1 1320//1 +f 1366//1 1367//1 1320//1 +f 1320//1 1367//1 1321//1 +f 1367//1 1368//1 1321//1 +f 1321//1 1368//1 1322//1 +f 1368//1 1369//1 1322//1 +f 1322//1 1369//1 1323//1 +f 1369//1 1370//1 1323//1 +f 1323//1 1370//1 1324//1 +f 1370//1 1371//1 1324//1 +f 1324//1 1371//1 1325//1 +f 1371//1 1372//1 1325//1 +f 1325//1 1372//1 1326//1 +f 1372//1 1373//1 1326//1 +f 1326//1 1373//1 1327//1 +f 1373//1 1374//1 1327//1 +f 1327//1 1374//1 1328//1 +f 1374//1 1375//1 1328//1 +f 1328//1 1375//1 1329//1 +f 1375//1 1376//1 1329//1 +f 1329//1 1376//1 1330//1 +f 1376//1 1377//1 1330//1 +f 1330//1 1377//1 1331//1 +f 1377//1 1378//1 1331//1 +f 1331//1 1378//1 1332//1 +f 1378//1 1379//1 1332//1 +f 1332//1 1379//1 1333//1 +f 1379//1 1380//1 1333//1 +f 1333//1 1380//1 1334//1 +f 1380//1 1381//1 1334//1 +f 1334//1 1381//1 1335//1 +f 1381//1 1382//1 1335//1 +f 1335//1 1382//1 158//1 +f 1382//1 157//1 158//1 +f 252//1 1383//1 1336//1 +f 1383//1 1384//1 1336//1 +f 1336//1 1384//1 1337//1 +f 1384//1 1385//1 1337//1 +f 1337//1 1385//1 1338//1 +f 1385//1 1386//1 1338//1 +f 1338//1 1386//1 1339//1 +f 1386//1 1387//1 1339//1 +f 1339//1 1387//1 1340//1 +f 1387//1 1388//1 1340//1 +f 1340//1 1388//1 1341//1 +f 1388//1 1389//1 1341//1 +f 1341//1 1389//1 1342//1 +f 1389//1 1390//1 1342//1 +f 1342//1 1390//1 1343//1 +f 1390//1 1391//1 1343//1 +f 1343//1 1391//1 1344//1 +f 1391//1 1392//1 1344//1 +f 1344//1 1392//1 1345//1 +f 1392//1 1393//1 1345//1 +f 1345//1 1393//1 1346//1 +f 1393//1 1394//1 1346//1 +f 1346//1 1394//1 1347//1 +f 1394//1 1395//1 1347//1 +f 1347//1 1395//1 1348//1 +f 1395//1 1396//1 1348//1 +f 1348//1 1396//1 1349//1 +f 1396//1 1397//1 1349//1 +f 1349//1 1397//1 1350//1 +f 1397//1 1398//1 1350//1 +f 1350//1 1398//1 1351//1 +f 1398//1 1399//1 1351//1 +f 1351//1 1399//1 1352//1 +f 1399//1 1400//1 1352//1 +f 1352//1 1400//1 1353//1 +f 1400//1 1401//1 1353//1 +f 1353//1 1401//1 1354//1 +f 1401//1 1402//1 1354//1 +f 1354//1 1402//1 1355//1 +f 1402//1 1403//1 1355//1 +f 1355//1 1403//1 1356//1 +f 1403//1 1404//1 1356//1 +f 1356//1 1404//1 1357//1 +f 1404//1 1405//1 1357//1 +f 1357//1 1405//1 1358//1 +f 1405//1 1406//1 1358//1 +f 1358//1 1406//1 1359//1 +f 1406//1 1407//1 1359//1 +f 1359//1 1407//1 1360//1 +f 1407//1 1408//1 1360//1 +f 1360//1 1408//1 1361//1 +f 1408//1 1409//1 1361//1 +f 1361//1 1409//1 1362//1 +f 1409//1 1410//1 1362//1 +f 1362//1 1410//1 1363//1 +f 1410//1 1411//1 1363//1 +f 1363//1 1411//1 1364//1 +f 1411//1 1412//1 1364//1 +f 1364//1 1412//1 1365//1 +f 1412//1 1413//1 1365//1 +f 1365//1 1413//1 1366//1 +f 1413//1 1414//1 1366//1 +f 1366//1 1414//1 1367//1 +f 1414//1 1415//1 1367//1 +f 1367//1 1415//1 1368//1 +f 1415//1 1416//1 1368//1 +f 1368//1 1416//1 1369//1 +f 1416//1 1417//1 1369//1 +f 1369//1 1417//1 1370//1 +f 1417//1 1418//1 1370//1 +f 1370//1 1418//1 1371//1 +f 1418//1 1419//1 1371//1 +f 1371//1 1419//1 1372//1 +f 1419//1 1420//1 1372//1 +f 1372//1 1420//1 1373//1 +f 1420//1 1421//1 1373//1 +f 1373//1 1421//1 1374//1 +f 1421//1 1422//1 1374//1 +f 1374//1 1422//1 1375//1 +f 1422//1 1423//1 1375//1 +f 1375//1 1423//1 1376//1 +f 1423//1 1424//1 1376//1 +f 1376//1 1424//1 1377//1 +f 1424//1 1425//1 1377//1 +f 1377//1 1425//1 1378//1 +f 1425//1 1426//1 1378//1 +f 1378//1 1426//1 1379//1 +f 1426//1 1427//1 1379//1 +f 1379//1 1427//1 1380//1 +f 1427//1 1428//1 1380//1 +f 1380//1 1428//1 1381//1 +f 1428//1 1429//1 1381//1 +f 1381//1 1429//1 1382//1 +f 1429//1 1430//1 1382//1 +f 1382//1 1430//1 157//1 +f 1430//1 156//1 157//1 +f 253//1 1431//1 1383//1 +f 1431//1 1432//1 1383//1 +f 1383//1 1432//1 1384//1 +f 1432//1 1433//1 1384//1 +f 1384//1 1433//1 1385//1 +f 1433//1 1434//1 1385//1 +f 1385//1 1434//1 1386//1 +f 1434//1 1435//1 1386//1 +f 1386//1 1435//1 1387//1 +f 1435//1 1436//1 1387//1 +f 1387//1 1436//1 1388//1 +f 1436//1 1437//1 1388//1 +f 1388//1 1437//1 1389//1 +f 1437//1 1438//1 1389//1 +f 1389//1 1438//1 1390//1 +f 1438//1 1439//1 1390//1 +f 1390//1 1439//1 1391//1 +f 1439//1 1440//1 1391//1 +f 1391//1 1440//1 1392//1 +f 1440//1 1441//1 1392//1 +f 1392//1 1441//1 1393//1 +f 1441//1 1442//1 1393//1 +f 1393//1 1442//1 1394//1 +f 1442//1 1443//1 1394//1 +f 1394//1 1443//1 1395//1 +f 1443//1 1444//1 1395//1 +f 1395//1 1444//1 1396//1 +f 1444//1 1445//1 1396//1 +f 1396//1 1445//1 1397//1 +f 1445//1 1446//1 1397//1 +f 1397//1 1446//1 1398//1 +f 1446//1 1447//1 1398//1 +f 1398//1 1447//1 1399//1 +f 1447//1 1448//1 1399//1 +f 1399//1 1448//1 1400//1 +f 1448//1 1449//1 1400//1 +f 1400//1 1449//1 1401//1 +f 1449//1 1450//1 1401//1 +f 1401//1 1450//1 1402//1 +f 1450//1 1451//1 1402//1 +f 1402//1 1451//1 1403//1 +f 1451//1 1452//1 1403//1 +f 1403//1 1452//1 1404//1 +f 1452//1 1453//1 1404//1 +f 1404//1 1453//1 1405//1 +f 1453//1 1454//1 1405//1 +f 1405//1 1454//1 1406//1 +f 1454//1 1455//1 1406//1 +f 1406//1 1455//1 1407//1 +f 1455//1 1456//1 1407//1 +f 1407//1 1456//1 1408//1 +f 1456//1 1457//1 1408//1 +f 1408//1 1457//1 1409//1 +f 1457//1 1458//1 1409//1 +f 1409//1 1458//1 1410//1 +f 1458//1 1459//1 1410//1 +f 1410//1 1459//1 1411//1 +f 1459//1 1460//1 1411//1 +f 1411//1 1460//1 1412//1 +f 1460//1 1461//1 1412//1 +f 1412//1 1461//1 1413//1 +f 1461//1 1462//1 1413//1 +f 1413//1 1462//1 1414//1 +f 1462//1 1463//1 1414//1 +f 1414//1 1463//1 1415//1 +f 1463//1 1464//1 1415//1 +f 1415//1 1464//1 1416//1 +f 1464//1 1465//1 1416//1 +f 1416//1 1465//1 1417//1 +f 1465//1 1466//1 1417//1 +f 1417//1 1466//1 1418//1 +f 1466//1 1467//1 1418//1 +f 1418//1 1467//1 1419//1 +f 1467//1 1468//1 1419//1 +f 1419//1 1468//1 1420//1 +f 1468//1 1469//1 1420//1 +f 1420//1 1469//1 1421//1 +f 1469//1 1470//1 1421//1 +f 1421//1 1470//1 1422//1 +f 1470//1 1471//1 1422//1 +f 1422//1 1471//1 1423//1 +f 1471//1 1472//1 1423//1 +f 1423//1 1472//1 1424//1 +f 1472//1 1473//1 1424//1 +f 1424//1 1473//1 1425//1 +f 1473//1 1474//1 1425//1 +f 1425//1 1474//1 1426//1 +f 1474//1 1475//1 1426//1 +f 1426//1 1475//1 1427//1 +f 1475//1 1476//1 1427//1 +f 1427//1 1476//1 1428//1 +f 1476//1 1477//1 1428//1 +f 1428//1 1477//1 1429//1 +f 1477//1 1478//1 1429//1 +f 1429//1 1478//1 1430//1 +f 1478//1 1479//1 1430//1 +f 1430//1 1479//1 156//1 +f 1479//1 155//1 156//1 +f 254//1 105//1 1431//1 +f 105//1 106//1 1431//1 +f 1431//1 106//1 1432//1 +f 106//1 107//1 1432//1 +f 1432//1 107//1 1433//1 +f 107//1 108//1 1433//1 +f 1433//1 108//1 1434//1 +f 108//1 109//1 1434//1 +f 1434//1 109//1 1435//1 +f 109//1 110//1 1435//1 +f 1435//1 110//1 1436//1 +f 110//1 111//1 1436//1 +f 1436//1 111//1 1437//1 +f 111//1 112//1 1437//1 +f 1437//1 112//1 1438//1 +f 112//1 113//1 1438//1 +f 1438//1 113//1 1439//1 +f 113//1 114//1 1439//1 +f 1439//1 114//1 1440//1 +f 114//1 115//1 1440//1 +f 1440//1 115//1 1441//1 +f 115//1 116//1 1441//1 +f 1441//1 116//1 1442//1 +f 116//1 117//1 1442//1 +f 1442//1 117//1 1443//1 +f 117//1 118//1 1443//1 +f 1443//1 118//1 1444//1 +f 118//1 119//1 1444//1 +f 1444//1 119//1 1445//1 +f 119//1 120//1 1445//1 +f 1445//1 120//1 1446//1 +f 120//1 121//1 1446//1 +f 1446//1 121//1 1447//1 +f 121//1 122//1 1447//1 +f 1447//1 122//1 1448//1 +f 122//1 123//1 1448//1 +f 1448//1 123//1 1449//1 +f 123//1 124//1 1449//1 +f 1449//1 124//1 1450//1 +f 124//1 125//1 1450//1 +f 1450//1 125//1 1451//1 +f 125//1 126//1 1451//1 +f 1451//1 126//1 1452//1 +f 126//1 127//1 1452//1 +f 1452//1 127//1 1453//1 +f 127//1 128//1 1453//1 +f 1453//1 128//1 1454//1 +f 128//1 129//1 1454//1 +f 1454//1 129//1 1455//1 +f 129//1 130//1 1455//1 +f 1455//1 130//1 1456//1 +f 130//1 131//1 1456//1 +f 1456//1 131//1 1457//1 +f 131//1 132//1 1457//1 +f 1457//1 132//1 1458//1 +f 132//1 133//1 1458//1 +f 1458//1 133//1 1459//1 +f 133//1 134//1 1459//1 +f 1459//1 134//1 1460//1 +f 134//1 135//1 1460//1 +f 1460//1 135//1 1461//1 +f 135//1 136//1 1461//1 +f 1461//1 136//1 1462//1 +f 136//1 137//1 1462//1 +f 1462//1 137//1 1463//1 +f 137//1 138//1 1463//1 +f 1463//1 138//1 1464//1 +f 138//1 139//1 1464//1 +f 1464//1 139//1 1465//1 +f 139//1 140//1 1465//1 +f 1465//1 140//1 1466//1 +f 140//1 141//1 1466//1 +f 1466//1 141//1 1467//1 +f 141//1 142//1 1467//1 +f 1467//1 142//1 1468//1 +f 142//1 143//1 1468//1 +f 1468//1 143//1 1469//1 +f 143//1 144//1 1469//1 +f 1469//1 144//1 1470//1 +f 144//1 145//1 1470//1 +f 1470//1 145//1 1471//1 +f 145//1 146//1 1471//1 +f 1471//1 146//1 1472//1 +f 146//1 147//1 1472//1 +f 1472//1 147//1 1473//1 +f 147//1 148//1 1473//1 +f 1473//1 148//1 1474//1 +f 148//1 149//1 1474//1 +f 1474//1 149//1 1475//1 +f 149//1 150//1 1475//1 +f 1475//1 150//1 1476//1 +f 150//1 151//1 1476//1 +f 1476//1 151//1 1477//1 +f 151//1 152//1 1477//1 +f 1477//1 152//1 1478//1 +f 152//1 153//1 1478//1 +f 1478//1 153//1 1479//1 +f 153//1 154//1 1479//1 +f 1479//1 154//1 155//1 +f 154//1 4//1 155//1 +f 55//1 54//1 1//1 +f 56//1 1480//1 55//1 +f 57//1 1481//1 56//1 +f 58//1 1483//1 57//1 +f 59//1 1486//1 58//1 +f 60//1 1490//1 59//1 +f 61//1 1495//1 60//1 +f 62//1 1501//1 61//1 +f 63//1 1508//1 62//1 +f 64//1 1516//1 63//1 +f 65//1 1525//1 64//1 +f 66//1 1535//1 65//1 +f 67//1 1546//1 66//1 +f 68//1 1558//1 67//1 +f 69//1 1571//1 68//1 +f 70//1 1585//1 69//1 +f 71//1 1600//1 70//1 +f 72//1 1616//1 71//1 +f 73//1 1633//1 72//1 +f 74//1 1651//1 73//1 +f 75//1 1670//1 74//1 +f 76//1 1690//1 75//1 +f 77//1 1711//1 76//1 +f 78//1 1733//1 77//1 +f 79//1 1756//1 78//1 +f 80//1 1780//1 79//1 +f 81//1 1805//1 80//1 +f 82//1 1831//1 81//1 +f 83//1 1858//1 82//1 +f 84//1 1886//1 83//1 +f 85//1 1915//1 84//1 +f 86//1 1945//1 85//1 +f 87//1 1976//1 86//1 +f 88//1 2008//1 87//1 +f 89//1 2041//1 88//1 +f 90//1 2075//1 89//1 +f 91//1 2110//1 90//1 +f 92//1 2146//1 91//1 +f 93//1 2183//1 92//1 +f 94//1 2221//1 93//1 +f 95//1 2260//1 94//1 +f 96//1 2300//1 95//1 +f 97//1 2341//1 96//1 +f 98//1 2383//1 97//1 +f 99//1 2426//1 98//1 +f 100//1 2470//1 99//1 +f 101//1 2515//1 100//1 +f 102//1 2561//1 101//1 +f 103//1 2608//1 102//1 +f 104//1 2656//1 103//1 +f 55//1 1480//1 54//1 +f 1480//1 53//1 54//1 +f 56//1 1481//1 1480//1 +f 1481//1 1482//1 1480//1 +f 1480//1 1482//1 53//1 +f 1482//1 52//1 53//1 +f 57//1 1483//1 1481//1 +f 1483//1 1484//1 1481//1 +f 1481//1 1484//1 1482//1 +f 1484//1 1485//1 1482//1 +f 1482//1 1485//1 52//1 +f 1485//1 51//1 52//1 +f 58//1 1486//1 1483//1 +f 1486//1 1487//1 1483//1 +f 1483//1 1487//1 1484//1 +f 1487//1 1488//1 1484//1 +f 1484//1 1488//1 1485//1 +f 1488//1 1489//1 1485//1 +f 1485//1 1489//1 51//1 +f 1489//1 50//1 51//1 +f 59//1 1490//1 1486//1 +f 1490//1 1491//1 1486//1 +f 1486//1 1491//1 1487//1 +f 1491//1 1492//1 1487//1 +f 1487//1 1492//1 1488//1 +f 1492//1 1493//1 1488//1 +f 1488//1 1493//1 1489//1 +f 1493//1 1494//1 1489//1 +f 1489//1 1494//1 50//1 +f 1494//1 49//1 50//1 +f 60//1 1495//1 1490//1 +f 1495//1 1496//1 1490//1 +f 1490//1 1496//1 1491//1 +f 1496//1 1497//1 1491//1 +f 1491//1 1497//1 1492//1 +f 1497//1 1498//1 1492//1 +f 1492//1 1498//1 1493//1 +f 1498//1 1499//1 1493//1 +f 1493//1 1499//1 1494//1 +f 1499//1 1500//1 1494//1 +f 1494//1 1500//1 49//1 +f 1500//1 48//1 49//1 +f 61//1 1501//1 1495//1 +f 1501//1 1502//1 1495//1 +f 1495//1 1502//1 1496//1 +f 1502//1 1503//1 1496//1 +f 1496//1 1503//1 1497//1 +f 1503//1 1504//1 1497//1 +f 1497//1 1504//1 1498//1 +f 1504//1 1505//1 1498//1 +f 1498//1 1505//1 1499//1 +f 1505//1 1506//1 1499//1 +f 1499//1 1506//1 1500//1 +f 1506//1 1507//1 1500//1 +f 1500//1 1507//1 48//1 +f 1507//1 47//1 48//1 +f 62//1 1508//1 1501//1 +f 1508//1 1509//1 1501//1 +f 1501//1 1509//1 1502//1 +f 1509//1 1510//1 1502//1 +f 1502//1 1510//1 1503//1 +f 1510//1 1511//1 1503//1 +f 1503//1 1511//1 1504//1 +f 1511//1 1512//1 1504//1 +f 1504//1 1512//1 1505//1 +f 1512//1 1513//1 1505//1 +f 1505//1 1513//1 1506//1 +f 1513//1 1514//1 1506//1 +f 1506//1 1514//1 1507//1 +f 1514//1 1515//1 1507//1 +f 1507//1 1515//1 47//1 +f 1515//1 46//1 47//1 +f 63//1 1516//1 1508//1 +f 1516//1 1517//1 1508//1 +f 1508//1 1517//1 1509//1 +f 1517//1 1518//1 1509//1 +f 1509//1 1518//1 1510//1 +f 1518//1 1519//1 1510//1 +f 1510//1 1519//1 1511//1 +f 1519//1 1520//1 1511//1 +f 1511//1 1520//1 1512//1 +f 1520//1 1521//1 1512//1 +f 1512//1 1521//1 1513//1 +f 1521//1 1522//1 1513//1 +f 1513//1 1522//1 1514//1 +f 1522//1 1523//1 1514//1 +f 1514//1 1523//1 1515//1 +f 1523//1 1524//1 1515//1 +f 1515//1 1524//1 46//1 +f 1524//1 45//1 46//1 +f 64//1 1525//1 1516//1 +f 1525//1 1526//1 1516//1 +f 1516//1 1526//1 1517//1 +f 1526//1 1527//1 1517//1 +f 1517//1 1527//1 1518//1 +f 1527//1 1528//1 1518//1 +f 1518//1 1528//1 1519//1 +f 1528//1 1529//1 1519//1 +f 1519//1 1529//1 1520//1 +f 1529//1 1530//1 1520//1 +f 1520//1 1530//1 1521//1 +f 1530//1 1531//1 1521//1 +f 1521//1 1531//1 1522//1 +f 1531//1 1532//1 1522//1 +f 1522//1 1532//1 1523//1 +f 1532//1 1533//1 1523//1 +f 1523//1 1533//1 1524//1 +f 1533//1 1534//1 1524//1 +f 1524//1 1534//1 45//1 +f 1534//1 44//1 45//1 +f 65//1 1535//1 1525//1 +f 1535//1 1536//1 1525//1 +f 1525//1 1536//1 1526//1 +f 1536//1 1537//1 1526//1 +f 1526//1 1537//1 1527//1 +f 1537//1 1538//1 1527//1 +f 1527//1 1538//1 1528//1 +f 1538//1 1539//1 1528//1 +f 1528//1 1539//1 1529//1 +f 1539//1 1540//1 1529//1 +f 1529//1 1540//1 1530//1 +f 1540//1 1541//1 1530//1 +f 1530//1 1541//1 1531//1 +f 1541//1 1542//1 1531//1 +f 1531//1 1542//1 1532//1 +f 1542//1 1543//1 1532//1 +f 1532//1 1543//1 1533//1 +f 1543//1 1544//1 1533//1 +f 1533//1 1544//1 1534//1 +f 1544//1 1545//1 1534//1 +f 1534//1 1545//1 44//1 +f 1545//1 43//1 44//1 +f 66//1 1546//1 1535//1 +f 1546//1 1547//1 1535//1 +f 1535//1 1547//1 1536//1 +f 1547//1 1548//1 1536//1 +f 1536//1 1548//1 1537//1 +f 1548//1 1549//1 1537//1 +f 1537//1 1549//1 1538//1 +f 1549//1 1550//1 1538//1 +f 1538//1 1550//1 1539//1 +f 1550//1 1551//1 1539//1 +f 1539//1 1551//1 1540//1 +f 1551//1 1552//1 1540//1 +f 1540//1 1552//1 1541//1 +f 1552//1 1553//1 1541//1 +f 1541//1 1553//1 1542//1 +f 1553//1 1554//1 1542//1 +f 1542//1 1554//1 1543//1 +f 1554//1 1555//1 1543//1 +f 1543//1 1555//1 1544//1 +f 1555//1 1556//1 1544//1 +f 1544//1 1556//1 1545//1 +f 1556//1 1557//1 1545//1 +f 1545//1 1557//1 43//1 +f 1557//1 42//1 43//1 +f 67//1 1558//1 1546//1 +f 1558//1 1559//1 1546//1 +f 1546//1 1559//1 1547//1 +f 1559//1 1560//1 1547//1 +f 1547//1 1560//1 1548//1 +f 1560//1 1561//1 1548//1 +f 1548//1 1561//1 1549//1 +f 1561//1 1562//1 1549//1 +f 1549//1 1562//1 1550//1 +f 1562//1 1563//1 1550//1 +f 1550//1 1563//1 1551//1 +f 1563//1 1564//1 1551//1 +f 1551//1 1564//1 1552//1 +f 1564//1 1565//1 1552//1 +f 1552//1 1565//1 1553//1 +f 1565//1 1566//1 1553//1 +f 1553//1 1566//1 1554//1 +f 1566//1 1567//1 1554//1 +f 1554//1 1567//1 1555//1 +f 1567//1 1568//1 1555//1 +f 1555//1 1568//1 1556//1 +f 1568//1 1569//1 1556//1 +f 1556//1 1569//1 1557//1 +f 1569//1 1570//1 1557//1 +f 1557//1 1570//1 42//1 +f 1570//1 41//1 42//1 +f 68//1 1571//1 1558//1 +f 1571//1 1572//1 1558//1 +f 1558//1 1572//1 1559//1 +f 1572//1 1573//1 1559//1 +f 1559//1 1573//1 1560//1 +f 1573//1 1574//1 1560//1 +f 1560//1 1574//1 1561//1 +f 1574//1 1575//1 1561//1 +f 1561//1 1575//1 1562//1 +f 1575//1 1576//1 1562//1 +f 1562//1 1576//1 1563//1 +f 1576//1 1577//1 1563//1 +f 1563//1 1577//1 1564//1 +f 1577//1 1578//1 1564//1 +f 1564//1 1578//1 1565//1 +f 1578//1 1579//1 1565//1 +f 1565//1 1579//1 1566//1 +f 1579//1 1580//1 1566//1 +f 1566//1 1580//1 1567//1 +f 1580//1 1581//1 1567//1 +f 1567//1 1581//1 1568//1 +f 1581//1 1582//1 1568//1 +f 1568//1 1582//1 1569//1 +f 1582//1 1583//1 1569//1 +f 1569//1 1583//1 1570//1 +f 1583//1 1584//1 1570//1 +f 1570//1 1584//1 41//1 +f 1584//1 40//1 41//1 +f 69//1 1585//1 1571//1 +f 1585//1 1586//1 1571//1 +f 1571//1 1586//1 1572//1 +f 1586//1 1587//1 1572//1 +f 1572//1 1587//1 1573//1 +f 1587//1 1588//1 1573//1 +f 1573//1 1588//1 1574//1 +f 1588//1 1589//1 1574//1 +f 1574//1 1589//1 1575//1 +f 1589//1 1590//1 1575//1 +f 1575//1 1590//1 1576//1 +f 1590//1 1591//1 1576//1 +f 1576//1 1591//1 1577//1 +f 1591//1 1592//1 1577//1 +f 1577//1 1592//1 1578//1 +f 1592//1 1593//1 1578//1 +f 1578//1 1593//1 1579//1 +f 1593//1 1594//1 1579//1 +f 1579//1 1594//1 1580//1 +f 1594//1 1595//1 1580//1 +f 1580//1 1595//1 1581//1 +f 1595//1 1596//1 1581//1 +f 1581//1 1596//1 1582//1 +f 1596//1 1597//1 1582//1 +f 1582//1 1597//1 1583//1 +f 1597//1 1598//1 1583//1 +f 1583//1 1598//1 1584//1 +f 1598//1 1599//1 1584//1 +f 1584//1 1599//1 40//1 +f 1599//1 39//1 40//1 +f 70//1 1600//1 1585//1 +f 1600//1 1601//1 1585//1 +f 1585//1 1601//1 1586//1 +f 1601//1 1602//1 1586//1 +f 1586//1 1602//1 1587//1 +f 1602//1 1603//1 1587//1 +f 1587//1 1603//1 1588//1 +f 1603//1 1604//1 1588//1 +f 1588//1 1604//1 1589//1 +f 1604//1 1605//1 1589//1 +f 1589//1 1605//1 1590//1 +f 1605//1 1606//1 1590//1 +f 1590//1 1606//1 1591//1 +f 1606//1 1607//1 1591//1 +f 1591//1 1607//1 1592//1 +f 1607//1 1608//1 1592//1 +f 1592//1 1608//1 1593//1 +f 1608//1 1609//1 1593//1 +f 1593//1 1609//1 1594//1 +f 1609//1 1610//1 1594//1 +f 1594//1 1610//1 1595//1 +f 1610//1 1611//1 1595//1 +f 1595//1 1611//1 1596//1 +f 1611//1 1612//1 1596//1 +f 1596//1 1612//1 1597//1 +f 1612//1 1613//1 1597//1 +f 1597//1 1613//1 1598//1 +f 1613//1 1614//1 1598//1 +f 1598//1 1614//1 1599//1 +f 1614//1 1615//1 1599//1 +f 1599//1 1615//1 39//1 +f 1615//1 38//1 39//1 +f 71//1 1616//1 1600//1 +f 1616//1 1617//1 1600//1 +f 1600//1 1617//1 1601//1 +f 1617//1 1618//1 1601//1 +f 1601//1 1618//1 1602//1 +f 1618//1 1619//1 1602//1 +f 1602//1 1619//1 1603//1 +f 1619//1 1620//1 1603//1 +f 1603//1 1620//1 1604//1 +f 1620//1 1621//1 1604//1 +f 1604//1 1621//1 1605//1 +f 1621//1 1622//1 1605//1 +f 1605//1 1622//1 1606//1 +f 1622//1 1623//1 1606//1 +f 1606//1 1623//1 1607//1 +f 1623//1 1624//1 1607//1 +f 1607//1 1624//1 1608//1 +f 1624//1 1625//1 1608//1 +f 1608//1 1625//1 1609//1 +f 1625//1 1626//1 1609//1 +f 1609//1 1626//1 1610//1 +f 1626//1 1627//1 1610//1 +f 1610//1 1627//1 1611//1 +f 1627//1 1628//1 1611//1 +f 1611//1 1628//1 1612//1 +f 1628//1 1629//1 1612//1 +f 1612//1 1629//1 1613//1 +f 1629//1 1630//1 1613//1 +f 1613//1 1630//1 1614//1 +f 1630//1 1631//1 1614//1 +f 1614//1 1631//1 1615//1 +f 1631//1 1632//1 1615//1 +f 1615//1 1632//1 38//1 +f 1632//1 37//1 38//1 +f 72//1 1633//1 1616//1 +f 1633//1 1634//1 1616//1 +f 1616//1 1634//1 1617//1 +f 1634//1 1635//1 1617//1 +f 1617//1 1635//1 1618//1 +f 1635//1 1636//1 1618//1 +f 1618//1 1636//1 1619//1 +f 1636//1 1637//1 1619//1 +f 1619//1 1637//1 1620//1 +f 1637//1 1638//1 1620//1 +f 1620//1 1638//1 1621//1 +f 1638//1 1639//1 1621//1 +f 1621//1 1639//1 1622//1 +f 1639//1 1640//1 1622//1 +f 1622//1 1640//1 1623//1 +f 1640//1 1641//1 1623//1 +f 1623//1 1641//1 1624//1 +f 1641//1 1642//1 1624//1 +f 1624//1 1642//1 1625//1 +f 1642//1 1643//1 1625//1 +f 1625//1 1643//1 1626//1 +f 1643//1 1644//1 1626//1 +f 1626//1 1644//1 1627//1 +f 1644//1 1645//1 1627//1 +f 1627//1 1645//1 1628//1 +f 1645//1 1646//1 1628//1 +f 1628//1 1646//1 1629//1 +f 1646//1 1647//1 1629//1 +f 1629//1 1647//1 1630//1 +f 1647//1 1648//1 1630//1 +f 1630//1 1648//1 1631//1 +f 1648//1 1649//1 1631//1 +f 1631//1 1649//1 1632//1 +f 1649//1 1650//1 1632//1 +f 1632//1 1650//1 37//1 +f 1650//1 36//1 37//1 +f 73//1 1651//1 1633//1 +f 1651//1 1652//1 1633//1 +f 1633//1 1652//1 1634//1 +f 1652//1 1653//1 1634//1 +f 1634//1 1653//1 1635//1 +f 1653//1 1654//1 1635//1 +f 1635//1 1654//1 1636//1 +f 1654//1 1655//1 1636//1 +f 1636//1 1655//1 1637//1 +f 1655//1 1656//1 1637//1 +f 1637//1 1656//1 1638//1 +f 1656//1 1657//1 1638//1 +f 1638//1 1657//1 1639//1 +f 1657//1 1658//1 1639//1 +f 1639//1 1658//1 1640//1 +f 1658//1 1659//1 1640//1 +f 1640//1 1659//1 1641//1 +f 1659//1 1660//1 1641//1 +f 1641//1 1660//1 1642//1 +f 1660//1 1661//1 1642//1 +f 1642//1 1661//1 1643//1 +f 1661//1 1662//1 1643//1 +f 1643//1 1662//1 1644//1 +f 1662//1 1663//1 1644//1 +f 1644//1 1663//1 1645//1 +f 1663//1 1664//1 1645//1 +f 1645//1 1664//1 1646//1 +f 1664//1 1665//1 1646//1 +f 1646//1 1665//1 1647//1 +f 1665//1 1666//1 1647//1 +f 1647//1 1666//1 1648//1 +f 1666//1 1667//1 1648//1 +f 1648//1 1667//1 1649//1 +f 1667//1 1668//1 1649//1 +f 1649//1 1668//1 1650//1 +f 1668//1 1669//1 1650//1 +f 1650//1 1669//1 36//1 +f 1669//1 35//1 36//1 +f 74//1 1670//1 1651//1 +f 1670//1 1671//1 1651//1 +f 1651//1 1671//1 1652//1 +f 1671//1 1672//1 1652//1 +f 1652//1 1672//1 1653//1 +f 1672//1 1673//1 1653//1 +f 1653//1 1673//1 1654//1 +f 1673//1 1674//1 1654//1 +f 1654//1 1674//1 1655//1 +f 1674//1 1675//1 1655//1 +f 1655//1 1675//1 1656//1 +f 1675//1 1676//1 1656//1 +f 1656//1 1676//1 1657//1 +f 1676//1 1677//1 1657//1 +f 1657//1 1677//1 1658//1 +f 1677//1 1678//1 1658//1 +f 1658//1 1678//1 1659//1 +f 1678//1 1679//1 1659//1 +f 1659//1 1679//1 1660//1 +f 1679//1 1680//1 1660//1 +f 1660//1 1680//1 1661//1 +f 1680//1 1681//1 1661//1 +f 1661//1 1681//1 1662//1 +f 1681//1 1682//1 1662//1 +f 1662//1 1682//1 1663//1 +f 1682//1 1683//1 1663//1 +f 1663//1 1683//1 1664//1 +f 1683//1 1684//1 1664//1 +f 1664//1 1684//1 1665//1 +f 1684//1 1685//1 1665//1 +f 1665//1 1685//1 1666//1 +f 1685//1 1686//1 1666//1 +f 1666//1 1686//1 1667//1 +f 1686//1 1687//1 1667//1 +f 1667//1 1687//1 1668//1 +f 1687//1 1688//1 1668//1 +f 1668//1 1688//1 1669//1 +f 1688//1 1689//1 1669//1 +f 1669//1 1689//1 35//1 +f 1689//1 34//1 35//1 +f 75//1 1690//1 1670//1 +f 1690//1 1691//1 1670//1 +f 1670//1 1691//1 1671//1 +f 1691//1 1692//1 1671//1 +f 1671//1 1692//1 1672//1 +f 1692//1 1693//1 1672//1 +f 1672//1 1693//1 1673//1 +f 1693//1 1694//1 1673//1 +f 1673//1 1694//1 1674//1 +f 1694//1 1695//1 1674//1 +f 1674//1 1695//1 1675//1 +f 1695//1 1696//1 1675//1 +f 1675//1 1696//1 1676//1 +f 1696//1 1697//1 1676//1 +f 1676//1 1697//1 1677//1 +f 1697//1 1698//1 1677//1 +f 1677//1 1698//1 1678//1 +f 1698//1 1699//1 1678//1 +f 1678//1 1699//1 1679//1 +f 1699//1 1700//1 1679//1 +f 1679//1 1700//1 1680//1 +f 1700//1 1701//1 1680//1 +f 1680//1 1701//1 1681//1 +f 1701//1 1702//1 1681//1 +f 1681//1 1702//1 1682//1 +f 1702//1 1703//1 1682//1 +f 1682//1 1703//1 1683//1 +f 1703//1 1704//1 1683//1 +f 1683//1 1704//1 1684//1 +f 1704//1 1705//1 1684//1 +f 1684//1 1705//1 1685//1 +f 1705//1 1706//1 1685//1 +f 1685//1 1706//1 1686//1 +f 1706//1 1707//1 1686//1 +f 1686//1 1707//1 1687//1 +f 1707//1 1708//1 1687//1 +f 1687//1 1708//1 1688//1 +f 1708//1 1709//1 1688//1 +f 1688//1 1709//1 1689//1 +f 1709//1 1710//1 1689//1 +f 1689//1 1710//1 34//1 +f 1710//1 33//1 34//1 +f 76//1 1711//1 1690//1 +f 1711//1 1712//1 1690//1 +f 1690//1 1712//1 1691//1 +f 1712//1 1713//1 1691//1 +f 1691//1 1713//1 1692//1 +f 1713//1 1714//1 1692//1 +f 1692//1 1714//1 1693//1 +f 1714//1 1715//1 1693//1 +f 1693//1 1715//1 1694//1 +f 1715//1 1716//1 1694//1 +f 1694//1 1716//1 1695//1 +f 1716//1 1717//1 1695//1 +f 1695//1 1717//1 1696//1 +f 1717//1 1718//1 1696//1 +f 1696//1 1718//1 1697//1 +f 1718//1 1719//1 1697//1 +f 1697//1 1719//1 1698//1 +f 1719//1 1720//1 1698//1 +f 1698//1 1720//1 1699//1 +f 1720//1 1721//1 1699//1 +f 1699//1 1721//1 1700//1 +f 1721//1 1722//1 1700//1 +f 1700//1 1722//1 1701//1 +f 1722//1 1723//1 1701//1 +f 1701//1 1723//1 1702//1 +f 1723//1 1724//1 1702//1 +f 1702//1 1724//1 1703//1 +f 1724//1 1725//1 1703//1 +f 1703//1 1725//1 1704//1 +f 1725//1 1726//1 1704//1 +f 1704//1 1726//1 1705//1 +f 1726//1 1727//1 1705//1 +f 1705//1 1727//1 1706//1 +f 1727//1 1728//1 1706//1 +f 1706//1 1728//1 1707//1 +f 1728//1 1729//1 1707//1 +f 1707//1 1729//1 1708//1 +f 1729//1 1730//1 1708//1 +f 1708//1 1730//1 1709//1 +f 1730//1 1731//1 1709//1 +f 1709//1 1731//1 1710//1 +f 1731//1 1732//1 1710//1 +f 1710//1 1732//1 33//1 +f 1732//1 32//1 33//1 +f 77//1 1733//1 1711//1 +f 1733//1 1734//1 1711//1 +f 1711//1 1734//1 1712//1 +f 1734//1 1735//1 1712//1 +f 1712//1 1735//1 1713//1 +f 1735//1 1736//1 1713//1 +f 1713//1 1736//1 1714//1 +f 1736//1 1737//1 1714//1 +f 1714//1 1737//1 1715//1 +f 1737//1 1738//1 1715//1 +f 1715//1 1738//1 1716//1 +f 1738//1 1739//1 1716//1 +f 1716//1 1739//1 1717//1 +f 1739//1 1740//1 1717//1 +f 1717//1 1740//1 1718//1 +f 1740//1 1741//1 1718//1 +f 1718//1 1741//1 1719//1 +f 1741//1 1742//1 1719//1 +f 1719//1 1742//1 1720//1 +f 1742//1 1743//1 1720//1 +f 1720//1 1743//1 1721//1 +f 1743//1 1744//1 1721//1 +f 1721//1 1744//1 1722//1 +f 1744//1 1745//1 1722//1 +f 1722//1 1745//1 1723//1 +f 1745//1 1746//1 1723//1 +f 1723//1 1746//1 1724//1 +f 1746//1 1747//1 1724//1 +f 1724//1 1747//1 1725//1 +f 1747//1 1748//1 1725//1 +f 1725//1 1748//1 1726//1 +f 1748//1 1749//1 1726//1 +f 1726//1 1749//1 1727//1 +f 1749//1 1750//1 1727//1 +f 1727//1 1750//1 1728//1 +f 1750//1 1751//1 1728//1 +f 1728//1 1751//1 1729//1 +f 1751//1 1752//1 1729//1 +f 1729//1 1752//1 1730//1 +f 1752//1 1753//1 1730//1 +f 1730//1 1753//1 1731//1 +f 1753//1 1754//1 1731//1 +f 1731//1 1754//1 1732//1 +f 1754//1 1755//1 1732//1 +f 1732//1 1755//1 32//1 +f 1755//1 31//1 32//1 +f 78//1 1756//1 1733//1 +f 1756//1 1757//1 1733//1 +f 1733//1 1757//1 1734//1 +f 1757//1 1758//1 1734//1 +f 1734//1 1758//1 1735//1 +f 1758//1 1759//1 1735//1 +f 1735//1 1759//1 1736//1 +f 1759//1 1760//1 1736//1 +f 1736//1 1760//1 1737//1 +f 1760//1 1761//1 1737//1 +f 1737//1 1761//1 1738//1 +f 1761//1 1762//1 1738//1 +f 1738//1 1762//1 1739//1 +f 1762//1 1763//1 1739//1 +f 1739//1 1763//1 1740//1 +f 1763//1 1764//1 1740//1 +f 1740//1 1764//1 1741//1 +f 1764//1 1765//1 1741//1 +f 1741//1 1765//1 1742//1 +f 1765//1 1766//1 1742//1 +f 1742//1 1766//1 1743//1 +f 1766//1 1767//1 1743//1 +f 1743//1 1767//1 1744//1 +f 1767//1 1768//1 1744//1 +f 1744//1 1768//1 1745//1 +f 1768//1 1769//1 1745//1 +f 1745//1 1769//1 1746//1 +f 1769//1 1770//1 1746//1 +f 1746//1 1770//1 1747//1 +f 1770//1 1771//1 1747//1 +f 1747//1 1771//1 1748//1 +f 1771//1 1772//1 1748//1 +f 1748//1 1772//1 1749//1 +f 1772//1 1773//1 1749//1 +f 1749//1 1773//1 1750//1 +f 1773//1 1774//1 1750//1 +f 1750//1 1774//1 1751//1 +f 1774//1 1775//1 1751//1 +f 1751//1 1775//1 1752//1 +f 1775//1 1776//1 1752//1 +f 1752//1 1776//1 1753//1 +f 1776//1 1777//1 1753//1 +f 1753//1 1777//1 1754//1 +f 1777//1 1778//1 1754//1 +f 1754//1 1778//1 1755//1 +f 1778//1 1779//1 1755//1 +f 1755//1 1779//1 31//1 +f 1779//1 30//1 31//1 +f 79//1 1780//1 1756//1 +f 1780//1 1781//1 1756//1 +f 1756//1 1781//1 1757//1 +f 1781//1 1782//1 1757//1 +f 1757//1 1782//1 1758//1 +f 1782//1 1783//1 1758//1 +f 1758//1 1783//1 1759//1 +f 1783//1 1784//1 1759//1 +f 1759//1 1784//1 1760//1 +f 1784//1 1785//1 1760//1 +f 1760//1 1785//1 1761//1 +f 1785//1 1786//1 1761//1 +f 1761//1 1786//1 1762//1 +f 1786//1 1787//1 1762//1 +f 1762//1 1787//1 1763//1 +f 1787//1 1788//1 1763//1 +f 1763//1 1788//1 1764//1 +f 1788//1 1789//1 1764//1 +f 1764//1 1789//1 1765//1 +f 1789//1 1790//1 1765//1 +f 1765//1 1790//1 1766//1 +f 1790//1 1791//1 1766//1 +f 1766//1 1791//1 1767//1 +f 1791//1 1792//1 1767//1 +f 1767//1 1792//1 1768//1 +f 1792//1 1793//1 1768//1 +f 1768//1 1793//1 1769//1 +f 1793//1 1794//1 1769//1 +f 1769//1 1794//1 1770//1 +f 1794//1 1795//1 1770//1 +f 1770//1 1795//1 1771//1 +f 1795//1 1796//1 1771//1 +f 1771//1 1796//1 1772//1 +f 1796//1 1797//1 1772//1 +f 1772//1 1797//1 1773//1 +f 1797//1 1798//1 1773//1 +f 1773//1 1798//1 1774//1 +f 1798//1 1799//1 1774//1 +f 1774//1 1799//1 1775//1 +f 1799//1 1800//1 1775//1 +f 1775//1 1800//1 1776//1 +f 1800//1 1801//1 1776//1 +f 1776//1 1801//1 1777//1 +f 1801//1 1802//1 1777//1 +f 1777//1 1802//1 1778//1 +f 1802//1 1803//1 1778//1 +f 1778//1 1803//1 1779//1 +f 1803//1 1804//1 1779//1 +f 1779//1 1804//1 30//1 +f 1804//1 29//1 30//1 +f 80//1 1805//1 1780//1 +f 1805//1 1806//1 1780//1 +f 1780//1 1806//1 1781//1 +f 1806//1 1807//1 1781//1 +f 1781//1 1807//1 1782//1 +f 1807//1 1808//1 1782//1 +f 1782//1 1808//1 1783//1 +f 1808//1 1809//1 1783//1 +f 1783//1 1809//1 1784//1 +f 1809//1 1810//1 1784//1 +f 1784//1 1810//1 1785//1 +f 1810//1 1811//1 1785//1 +f 1785//1 1811//1 1786//1 +f 1811//1 1812//1 1786//1 +f 1786//1 1812//1 1787//1 +f 1812//1 1813//1 1787//1 +f 1787//1 1813//1 1788//1 +f 1813//1 1814//1 1788//1 +f 1788//1 1814//1 1789//1 +f 1814//1 1815//1 1789//1 +f 1789//1 1815//1 1790//1 +f 1815//1 1816//1 1790//1 +f 1790//1 1816//1 1791//1 +f 1816//1 1817//1 1791//1 +f 1791//1 1817//1 1792//1 +f 1817//1 1818//1 1792//1 +f 1792//1 1818//1 1793//1 +f 1818//1 1819//1 1793//1 +f 1793//1 1819//1 1794//1 +f 1819//1 1820//1 1794//1 +f 1794//1 1820//1 1795//1 +f 1820//1 1821//1 1795//1 +f 1795//1 1821//1 1796//1 +f 1821//1 1822//1 1796//1 +f 1796//1 1822//1 1797//1 +f 1822//1 1823//1 1797//1 +f 1797//1 1823//1 1798//1 +f 1823//1 1824//1 1798//1 +f 1798//1 1824//1 1799//1 +f 1824//1 1825//1 1799//1 +f 1799//1 1825//1 1800//1 +f 1825//1 1826//1 1800//1 +f 1800//1 1826//1 1801//1 +f 1826//1 1827//1 1801//1 +f 1801//1 1827//1 1802//1 +f 1827//1 1828//1 1802//1 +f 1802//1 1828//1 1803//1 +f 1828//1 1829//1 1803//1 +f 1803//1 1829//1 1804//1 +f 1829//1 1830//1 1804//1 +f 1804//1 1830//1 29//1 +f 1830//1 28//1 29//1 +f 81//1 1831//1 1805//1 +f 1831//1 1832//1 1805//1 +f 1805//1 1832//1 1806//1 +f 1832//1 1833//1 1806//1 +f 1806//1 1833//1 1807//1 +f 1833//1 1834//1 1807//1 +f 1807//1 1834//1 1808//1 +f 1834//1 1835//1 1808//1 +f 1808//1 1835//1 1809//1 +f 1835//1 1836//1 1809//1 +f 1809//1 1836//1 1810//1 +f 1836//1 1837//1 1810//1 +f 1810//1 1837//1 1811//1 +f 1837//1 1838//1 1811//1 +f 1811//1 1838//1 1812//1 +f 1838//1 1839//1 1812//1 +f 1812//1 1839//1 1813//1 +f 1839//1 1840//1 1813//1 +f 1813//1 1840//1 1814//1 +f 1840//1 1841//1 1814//1 +f 1814//1 1841//1 1815//1 +f 1841//1 1842//1 1815//1 +f 1815//1 1842//1 1816//1 +f 1842//1 1843//1 1816//1 +f 1816//1 1843//1 1817//1 +f 1843//1 1844//1 1817//1 +f 1817//1 1844//1 1818//1 +f 1844//1 1845//1 1818//1 +f 1818//1 1845//1 1819//1 +f 1845//1 1846//1 1819//1 +f 1819//1 1846//1 1820//1 +f 1846//1 1847//1 1820//1 +f 1820//1 1847//1 1821//1 +f 1847//1 1848//1 1821//1 +f 1821//1 1848//1 1822//1 +f 1848//1 1849//1 1822//1 +f 1822//1 1849//1 1823//1 +f 1849//1 1850//1 1823//1 +f 1823//1 1850//1 1824//1 +f 1850//1 1851//1 1824//1 +f 1824//1 1851//1 1825//1 +f 1851//1 1852//1 1825//1 +f 1825//1 1852//1 1826//1 +f 1852//1 1853//1 1826//1 +f 1826//1 1853//1 1827//1 +f 1853//1 1854//1 1827//1 +f 1827//1 1854//1 1828//1 +f 1854//1 1855//1 1828//1 +f 1828//1 1855//1 1829//1 +f 1855//1 1856//1 1829//1 +f 1829//1 1856//1 1830//1 +f 1856//1 1857//1 1830//1 +f 1830//1 1857//1 28//1 +f 1857//1 27//1 28//1 +f 82//1 1858//1 1831//1 +f 1858//1 1859//1 1831//1 +f 1831//1 1859//1 1832//1 +f 1859//1 1860//1 1832//1 +f 1832//1 1860//1 1833//1 +f 1860//1 1861//1 1833//1 +f 1833//1 1861//1 1834//1 +f 1861//1 1862//1 1834//1 +f 1834//1 1862//1 1835//1 +f 1862//1 1863//1 1835//1 +f 1835//1 1863//1 1836//1 +f 1863//1 1864//1 1836//1 +f 1836//1 1864//1 1837//1 +f 1864//1 1865//1 1837//1 +f 1837//1 1865//1 1838//1 +f 1865//1 1866//1 1838//1 +f 1838//1 1866//1 1839//1 +f 1866//1 1867//1 1839//1 +f 1839//1 1867//1 1840//1 +f 1867//1 1868//1 1840//1 +f 1840//1 1868//1 1841//1 +f 1868//1 1869//1 1841//1 +f 1841//1 1869//1 1842//1 +f 1869//1 1870//1 1842//1 +f 1842//1 1870//1 1843//1 +f 1870//1 1871//1 1843//1 +f 1843//1 1871//1 1844//1 +f 1871//1 1872//1 1844//1 +f 1844//1 1872//1 1845//1 +f 1872//1 1873//1 1845//1 +f 1845//1 1873//1 1846//1 +f 1873//1 1874//1 1846//1 +f 1846//1 1874//1 1847//1 +f 1874//1 1875//1 1847//1 +f 1847//1 1875//1 1848//1 +f 1875//1 1876//1 1848//1 +f 1848//1 1876//1 1849//1 +f 1876//1 1877//1 1849//1 +f 1849//1 1877//1 1850//1 +f 1877//1 1878//1 1850//1 +f 1850//1 1878//1 1851//1 +f 1878//1 1879//1 1851//1 +f 1851//1 1879//1 1852//1 +f 1879//1 1880//1 1852//1 +f 1852//1 1880//1 1853//1 +f 1880//1 1881//1 1853//1 +f 1853//1 1881//1 1854//1 +f 1881//1 1882//1 1854//1 +f 1854//1 1882//1 1855//1 +f 1882//1 1883//1 1855//1 +f 1855//1 1883//1 1856//1 +f 1883//1 1884//1 1856//1 +f 1856//1 1884//1 1857//1 +f 1884//1 1885//1 1857//1 +f 1857//1 1885//1 27//1 +f 1885//1 26//1 27//1 +f 83//1 1886//1 1858//1 +f 1886//1 1887//1 1858//1 +f 1858//1 1887//1 1859//1 +f 1887//1 1888//1 1859//1 +f 1859//1 1888//1 1860//1 +f 1888//1 1889//1 1860//1 +f 1860//1 1889//1 1861//1 +f 1889//1 1890//1 1861//1 +f 1861//1 1890//1 1862//1 +f 1890//1 1891//1 1862//1 +f 1862//1 1891//1 1863//1 +f 1891//1 1892//1 1863//1 +f 1863//1 1892//1 1864//1 +f 1892//1 1893//1 1864//1 +f 1864//1 1893//1 1865//1 +f 1893//1 1894//1 1865//1 +f 1865//1 1894//1 1866//1 +f 1894//1 1895//1 1866//1 +f 1866//1 1895//1 1867//1 +f 1895//1 1896//1 1867//1 +f 1867//1 1896//1 1868//1 +f 1896//1 1897//1 1868//1 +f 1868//1 1897//1 1869//1 +f 1897//1 1898//1 1869//1 +f 1869//1 1898//1 1870//1 +f 1898//1 1899//1 1870//1 +f 1870//1 1899//1 1871//1 +f 1899//1 1900//1 1871//1 +f 1871//1 1900//1 1872//1 +f 1900//1 1901//1 1872//1 +f 1872//1 1901//1 1873//1 +f 1901//1 1902//1 1873//1 +f 1873//1 1902//1 1874//1 +f 1902//1 1903//1 1874//1 +f 1874//1 1903//1 1875//1 +f 1903//1 1904//1 1875//1 +f 1875//1 1904//1 1876//1 +f 1904//1 1905//1 1876//1 +f 1876//1 1905//1 1877//1 +f 1905//1 1906//1 1877//1 +f 1877//1 1906//1 1878//1 +f 1906//1 1907//1 1878//1 +f 1878//1 1907//1 1879//1 +f 1907//1 1908//1 1879//1 +f 1879//1 1908//1 1880//1 +f 1908//1 1909//1 1880//1 +f 1880//1 1909//1 1881//1 +f 1909//1 1910//1 1881//1 +f 1881//1 1910//1 1882//1 +f 1910//1 1911//1 1882//1 +f 1882//1 1911//1 1883//1 +f 1911//1 1912//1 1883//1 +f 1883//1 1912//1 1884//1 +f 1912//1 1913//1 1884//1 +f 1884//1 1913//1 1885//1 +f 1913//1 1914//1 1885//1 +f 1885//1 1914//1 26//1 +f 1914//1 25//1 26//1 +f 84//1 1915//1 1886//1 +f 1915//1 1916//1 1886//1 +f 1886//1 1916//1 1887//1 +f 1916//1 1917//1 1887//1 +f 1887//1 1917//1 1888//1 +f 1917//1 1918//1 1888//1 +f 1888//1 1918//1 1889//1 +f 1918//1 1919//1 1889//1 +f 1889//1 1919//1 1890//1 +f 1919//1 1920//1 1890//1 +f 1890//1 1920//1 1891//1 +f 1920//1 1921//1 1891//1 +f 1891//1 1921//1 1892//1 +f 1921//1 1922//1 1892//1 +f 1892//1 1922//1 1893//1 +f 1922//1 1923//1 1893//1 +f 1893//1 1923//1 1894//1 +f 1923//1 1924//1 1894//1 +f 1894//1 1924//1 1895//1 +f 1924//1 1925//1 1895//1 +f 1895//1 1925//1 1896//1 +f 1925//1 1926//1 1896//1 +f 1896//1 1926//1 1897//1 +f 1926//1 1927//1 1897//1 +f 1897//1 1927//1 1898//1 +f 1927//1 1928//1 1898//1 +f 1898//1 1928//1 1899//1 +f 1928//1 1929//1 1899//1 +f 1899//1 1929//1 1900//1 +f 1929//1 1930//1 1900//1 +f 1900//1 1930//1 1901//1 +f 1930//1 1931//1 1901//1 +f 1901//1 1931//1 1902//1 +f 1931//1 1932//1 1902//1 +f 1902//1 1932//1 1903//1 +f 1932//1 1933//1 1903//1 +f 1903//1 1933//1 1904//1 +f 1933//1 1934//1 1904//1 +f 1904//1 1934//1 1905//1 +f 1934//1 1935//1 1905//1 +f 1905//1 1935//1 1906//1 +f 1935//1 1936//1 1906//1 +f 1906//1 1936//1 1907//1 +f 1936//1 1937//1 1907//1 +f 1907//1 1937//1 1908//1 +f 1937//1 1938//1 1908//1 +f 1908//1 1938//1 1909//1 +f 1938//1 1939//1 1909//1 +f 1909//1 1939//1 1910//1 +f 1939//1 1940//1 1910//1 +f 1910//1 1940//1 1911//1 +f 1940//1 1941//1 1911//1 +f 1911//1 1941//1 1912//1 +f 1941//1 1942//1 1912//1 +f 1912//1 1942//1 1913//1 +f 1942//1 1943//1 1913//1 +f 1913//1 1943//1 1914//1 +f 1943//1 1944//1 1914//1 +f 1914//1 1944//1 25//1 +f 1944//1 24//1 25//1 +f 85//1 1945//1 1915//1 +f 1945//1 1946//1 1915//1 +f 1915//1 1946//1 1916//1 +f 1946//1 1947//1 1916//1 +f 1916//1 1947//1 1917//1 +f 1947//1 1948//1 1917//1 +f 1917//1 1948//1 1918//1 +f 1948//1 1949//1 1918//1 +f 1918//1 1949//1 1919//1 +f 1949//1 1950//1 1919//1 +f 1919//1 1950//1 1920//1 +f 1950//1 1951//1 1920//1 +f 1920//1 1951//1 1921//1 +f 1951//1 1952//1 1921//1 +f 1921//1 1952//1 1922//1 +f 1952//1 1953//1 1922//1 +f 1922//1 1953//1 1923//1 +f 1953//1 1954//1 1923//1 +f 1923//1 1954//1 1924//1 +f 1954//1 1955//1 1924//1 +f 1924//1 1955//1 1925//1 +f 1955//1 1956//1 1925//1 +f 1925//1 1956//1 1926//1 +f 1956//1 1957//1 1926//1 +f 1926//1 1957//1 1927//1 +f 1957//1 1958//1 1927//1 +f 1927//1 1958//1 1928//1 +f 1958//1 1959//1 1928//1 +f 1928//1 1959//1 1929//1 +f 1959//1 1960//1 1929//1 +f 1929//1 1960//1 1930//1 +f 1960//1 1961//1 1930//1 +f 1930//1 1961//1 1931//1 +f 1961//1 1962//1 1931//1 +f 1931//1 1962//1 1932//1 +f 1962//1 1963//1 1932//1 +f 1932//1 1963//1 1933//1 +f 1963//1 1964//1 1933//1 +f 1933//1 1964//1 1934//1 +f 1964//1 1965//1 1934//1 +f 1934//1 1965//1 1935//1 +f 1965//1 1966//1 1935//1 +f 1935//1 1966//1 1936//1 +f 1966//1 1967//1 1936//1 +f 1936//1 1967//1 1937//1 +f 1967//1 1968//1 1937//1 +f 1937//1 1968//1 1938//1 +f 1968//1 1969//1 1938//1 +f 1938//1 1969//1 1939//1 +f 1969//1 1970//1 1939//1 +f 1939//1 1970//1 1940//1 +f 1970//1 1971//1 1940//1 +f 1940//1 1971//1 1941//1 +f 1971//1 1972//1 1941//1 +f 1941//1 1972//1 1942//1 +f 1972//1 1973//1 1942//1 +f 1942//1 1973//1 1943//1 +f 1973//1 1974//1 1943//1 +f 1943//1 1974//1 1944//1 +f 1974//1 1975//1 1944//1 +f 1944//1 1975//1 24//1 +f 1975//1 23//1 24//1 +f 86//1 1976//1 1945//1 +f 1976//1 1977//1 1945//1 +f 1945//1 1977//1 1946//1 +f 1977//1 1978//1 1946//1 +f 1946//1 1978//1 1947//1 +f 1978//1 1979//1 1947//1 +f 1947//1 1979//1 1948//1 +f 1979//1 1980//1 1948//1 +f 1948//1 1980//1 1949//1 +f 1980//1 1981//1 1949//1 +f 1949//1 1981//1 1950//1 +f 1981//1 1982//1 1950//1 +f 1950//1 1982//1 1951//1 +f 1982//1 1983//1 1951//1 +f 1951//1 1983//1 1952//1 +f 1983//1 1984//1 1952//1 +f 1952//1 1984//1 1953//1 +f 1984//1 1985//1 1953//1 +f 1953//1 1985//1 1954//1 +f 1985//1 1986//1 1954//1 +f 1954//1 1986//1 1955//1 +f 1986//1 1987//1 1955//1 +f 1955//1 1987//1 1956//1 +f 1987//1 1988//1 1956//1 +f 1956//1 1988//1 1957//1 +f 1988//1 1989//1 1957//1 +f 1957//1 1989//1 1958//1 +f 1989//1 1990//1 1958//1 +f 1958//1 1990//1 1959//1 +f 1990//1 1991//1 1959//1 +f 1959//1 1991//1 1960//1 +f 1991//1 1992//1 1960//1 +f 1960//1 1992//1 1961//1 +f 1992//1 1993//1 1961//1 +f 1961//1 1993//1 1962//1 +f 1993//1 1994//1 1962//1 +f 1962//1 1994//1 1963//1 +f 1994//1 1995//1 1963//1 +f 1963//1 1995//1 1964//1 +f 1995//1 1996//1 1964//1 +f 1964//1 1996//1 1965//1 +f 1996//1 1997//1 1965//1 +f 1965//1 1997//1 1966//1 +f 1997//1 1998//1 1966//1 +f 1966//1 1998//1 1967//1 +f 1998//1 1999//1 1967//1 +f 1967//1 1999//1 1968//1 +f 1999//1 2000//1 1968//1 +f 1968//1 2000//1 1969//1 +f 2000//1 2001//1 1969//1 +f 1969//1 2001//1 1970//1 +f 2001//1 2002//1 1970//1 +f 1970//1 2002//1 1971//1 +f 2002//1 2003//1 1971//1 +f 1971//1 2003//1 1972//1 +f 2003//1 2004//1 1972//1 +f 1972//1 2004//1 1973//1 +f 2004//1 2005//1 1973//1 +f 1973//1 2005//1 1974//1 +f 2005//1 2006//1 1974//1 +f 1974//1 2006//1 1975//1 +f 2006//1 2007//1 1975//1 +f 1975//1 2007//1 23//1 +f 2007//1 22//1 23//1 +f 87//1 2008//1 1976//1 +f 2008//1 2009//1 1976//1 +f 1976//1 2009//1 1977//1 +f 2009//1 2010//1 1977//1 +f 1977//1 2010//1 1978//1 +f 2010//1 2011//1 1978//1 +f 1978//1 2011//1 1979//1 +f 2011//1 2012//1 1979//1 +f 1979//1 2012//1 1980//1 +f 2012//1 2013//1 1980//1 +f 1980//1 2013//1 1981//1 +f 2013//1 2014//1 1981//1 +f 1981//1 2014//1 1982//1 +f 2014//1 2015//1 1982//1 +f 1982//1 2015//1 1983//1 +f 2015//1 2016//1 1983//1 +f 1983//1 2016//1 1984//1 +f 2016//1 2017//1 1984//1 +f 1984//1 2017//1 1985//1 +f 2017//1 2018//1 1985//1 +f 1985//1 2018//1 1986//1 +f 2018//1 2019//1 1986//1 +f 1986//1 2019//1 1987//1 +f 2019//1 2020//1 1987//1 +f 1987//1 2020//1 1988//1 +f 2020//1 2021//1 1988//1 +f 1988//1 2021//1 1989//1 +f 2021//1 2022//1 1989//1 +f 1989//1 2022//1 1990//1 +f 2022//1 2023//1 1990//1 +f 1990//1 2023//1 1991//1 +f 2023//1 2024//1 1991//1 +f 1991//1 2024//1 1992//1 +f 2024//1 2025//1 1992//1 +f 1992//1 2025//1 1993//1 +f 2025//1 2026//1 1993//1 +f 1993//1 2026//1 1994//1 +f 2026//1 2027//1 1994//1 +f 1994//1 2027//1 1995//1 +f 2027//1 2028//1 1995//1 +f 1995//1 2028//1 1996//1 +f 2028//1 2029//1 1996//1 +f 1996//1 2029//1 1997//1 +f 2029//1 2030//1 1997//1 +f 1997//1 2030//1 1998//1 +f 2030//1 2031//1 1998//1 +f 1998//1 2031//1 1999//1 +f 2031//1 2032//1 1999//1 +f 1999//1 2032//1 2000//1 +f 2032//1 2033//1 2000//1 +f 2000//1 2033//1 2001//1 +f 2033//1 2034//1 2001//1 +f 2001//1 2034//1 2002//1 +f 2034//1 2035//1 2002//1 +f 2002//1 2035//1 2003//1 +f 2035//1 2036//1 2003//1 +f 2003//1 2036//1 2004//1 +f 2036//1 2037//1 2004//1 +f 2004//1 2037//1 2005//1 +f 2037//1 2038//1 2005//1 +f 2005//1 2038//1 2006//1 +f 2038//1 2039//1 2006//1 +f 2006//1 2039//1 2007//1 +f 2039//1 2040//1 2007//1 +f 2007//1 2040//1 22//1 +f 2040//1 21//1 22//1 +f 88//1 2041//1 2008//1 +f 2041//1 2042//1 2008//1 +f 2008//1 2042//1 2009//1 +f 2042//1 2043//1 2009//1 +f 2009//1 2043//1 2010//1 +f 2043//1 2044//1 2010//1 +f 2010//1 2044//1 2011//1 +f 2044//1 2045//1 2011//1 +f 2011//1 2045//1 2012//1 +f 2045//1 2046//1 2012//1 +f 2012//1 2046//1 2013//1 +f 2046//1 2047//1 2013//1 +f 2013//1 2047//1 2014//1 +f 2047//1 2048//1 2014//1 +f 2014//1 2048//1 2015//1 +f 2048//1 2049//1 2015//1 +f 2015//1 2049//1 2016//1 +f 2049//1 2050//1 2016//1 +f 2016//1 2050//1 2017//1 +f 2050//1 2051//1 2017//1 +f 2017//1 2051//1 2018//1 +f 2051//1 2052//1 2018//1 +f 2018//1 2052//1 2019//1 +f 2052//1 2053//1 2019//1 +f 2019//1 2053//1 2020//1 +f 2053//1 2054//1 2020//1 +f 2020//1 2054//1 2021//1 +f 2054//1 2055//1 2021//1 +f 2021//1 2055//1 2022//1 +f 2055//1 2056//1 2022//1 +f 2022//1 2056//1 2023//1 +f 2056//1 2057//1 2023//1 +f 2023//1 2057//1 2024//1 +f 2057//1 2058//1 2024//1 +f 2024//1 2058//1 2025//1 +f 2058//1 2059//1 2025//1 +f 2025//1 2059//1 2026//1 +f 2059//1 2060//1 2026//1 +f 2026//1 2060//1 2027//1 +f 2060//1 2061//1 2027//1 +f 2027//1 2061//1 2028//1 +f 2061//1 2062//1 2028//1 +f 2028//1 2062//1 2029//1 +f 2062//1 2063//1 2029//1 +f 2029//1 2063//1 2030//1 +f 2063//1 2064//1 2030//1 +f 2030//1 2064//1 2031//1 +f 2064//1 2065//1 2031//1 +f 2031//1 2065//1 2032//1 +f 2065//1 2066//1 2032//1 +f 2032//1 2066//1 2033//1 +f 2066//1 2067//1 2033//1 +f 2033//1 2067//1 2034//1 +f 2067//1 2068//1 2034//1 +f 2034//1 2068//1 2035//1 +f 2068//1 2069//1 2035//1 +f 2035//1 2069//1 2036//1 +f 2069//1 2070//1 2036//1 +f 2036//1 2070//1 2037//1 +f 2070//1 2071//1 2037//1 +f 2037//1 2071//1 2038//1 +f 2071//1 2072//1 2038//1 +f 2038//1 2072//1 2039//1 +f 2072//1 2073//1 2039//1 +f 2039//1 2073//1 2040//1 +f 2073//1 2074//1 2040//1 +f 2040//1 2074//1 21//1 +f 2074//1 20//1 21//1 +f 89//1 2075//1 2041//1 +f 2075//1 2076//1 2041//1 +f 2041//1 2076//1 2042//1 +f 2076//1 2077//1 2042//1 +f 2042//1 2077//1 2043//1 +f 2077//1 2078//1 2043//1 +f 2043//1 2078//1 2044//1 +f 2078//1 2079//1 2044//1 +f 2044//1 2079//1 2045//1 +f 2079//1 2080//1 2045//1 +f 2045//1 2080//1 2046//1 +f 2080//1 2081//1 2046//1 +f 2046//1 2081//1 2047//1 +f 2081//1 2082//1 2047//1 +f 2047//1 2082//1 2048//1 +f 2082//1 2083//1 2048//1 +f 2048//1 2083//1 2049//1 +f 2083//1 2084//1 2049//1 +f 2049//1 2084//1 2050//1 +f 2084//1 2085//1 2050//1 +f 2050//1 2085//1 2051//1 +f 2085//1 2086//1 2051//1 +f 2051//1 2086//1 2052//1 +f 2086//1 2087//1 2052//1 +f 2052//1 2087//1 2053//1 +f 2087//1 2088//1 2053//1 +f 2053//1 2088//1 2054//1 +f 2088//1 2089//1 2054//1 +f 2054//1 2089//1 2055//1 +f 2089//1 2090//1 2055//1 +f 2055//1 2090//1 2056//1 +f 2090//1 2091//1 2056//1 +f 2056//1 2091//1 2057//1 +f 2091//1 2092//1 2057//1 +f 2057//1 2092//1 2058//1 +f 2092//1 2093//1 2058//1 +f 2058//1 2093//1 2059//1 +f 2093//1 2094//1 2059//1 +f 2059//1 2094//1 2060//1 +f 2094//1 2095//1 2060//1 +f 2060//1 2095//1 2061//1 +f 2095//1 2096//1 2061//1 +f 2061//1 2096//1 2062//1 +f 2096//1 2097//1 2062//1 +f 2062//1 2097//1 2063//1 +f 2097//1 2098//1 2063//1 +f 2063//1 2098//1 2064//1 +f 2098//1 2099//1 2064//1 +f 2064//1 2099//1 2065//1 +f 2099//1 2100//1 2065//1 +f 2065//1 2100//1 2066//1 +f 2100//1 2101//1 2066//1 +f 2066//1 2101//1 2067//1 +f 2101//1 2102//1 2067//1 +f 2067//1 2102//1 2068//1 +f 2102//1 2103//1 2068//1 +f 2068//1 2103//1 2069//1 +f 2103//1 2104//1 2069//1 +f 2069//1 2104//1 2070//1 +f 2104//1 2105//1 2070//1 +f 2070//1 2105//1 2071//1 +f 2105//1 2106//1 2071//1 +f 2071//1 2106//1 2072//1 +f 2106//1 2107//1 2072//1 +f 2072//1 2107//1 2073//1 +f 2107//1 2108//1 2073//1 +f 2073//1 2108//1 2074//1 +f 2108//1 2109//1 2074//1 +f 2074//1 2109//1 20//1 +f 2109//1 19//1 20//1 +f 90//1 2110//1 2075//1 +f 2110//1 2111//1 2075//1 +f 2075//1 2111//1 2076//1 +f 2111//1 2112//1 2076//1 +f 2076//1 2112//1 2077//1 +f 2112//1 2113//1 2077//1 +f 2077//1 2113//1 2078//1 +f 2113//1 2114//1 2078//1 +f 2078//1 2114//1 2079//1 +f 2114//1 2115//1 2079//1 +f 2079//1 2115//1 2080//1 +f 2115//1 2116//1 2080//1 +f 2080//1 2116//1 2081//1 +f 2116//1 2117//1 2081//1 +f 2081//1 2117//1 2082//1 +f 2117//1 2118//1 2082//1 +f 2082//1 2118//1 2083//1 +f 2118//1 2119//1 2083//1 +f 2083//1 2119//1 2084//1 +f 2119//1 2120//1 2084//1 +f 2084//1 2120//1 2085//1 +f 2120//1 2121//1 2085//1 +f 2085//1 2121//1 2086//1 +f 2121//1 2122//1 2086//1 +f 2086//1 2122//1 2087//1 +f 2122//1 2123//1 2087//1 +f 2087//1 2123//1 2088//1 +f 2123//1 2124//1 2088//1 +f 2088//1 2124//1 2089//1 +f 2124//1 2125//1 2089//1 +f 2089//1 2125//1 2090//1 +f 2125//1 2126//1 2090//1 +f 2090//1 2126//1 2091//1 +f 2126//1 2127//1 2091//1 +f 2091//1 2127//1 2092//1 +f 2127//1 2128//1 2092//1 +f 2092//1 2128//1 2093//1 +f 2128//1 2129//1 2093//1 +f 2093//1 2129//1 2094//1 +f 2129//1 2130//1 2094//1 +f 2094//1 2130//1 2095//1 +f 2130//1 2131//1 2095//1 +f 2095//1 2131//1 2096//1 +f 2131//1 2132//1 2096//1 +f 2096//1 2132//1 2097//1 +f 2132//1 2133//1 2097//1 +f 2097//1 2133//1 2098//1 +f 2133//1 2134//1 2098//1 +f 2098//1 2134//1 2099//1 +f 2134//1 2135//1 2099//1 +f 2099//1 2135//1 2100//1 +f 2135//1 2136//1 2100//1 +f 2100//1 2136//1 2101//1 +f 2136//1 2137//1 2101//1 +f 2101//1 2137//1 2102//1 +f 2137//1 2138//1 2102//1 +f 2102//1 2138//1 2103//1 +f 2138//1 2139//1 2103//1 +f 2103//1 2139//1 2104//1 +f 2139//1 2140//1 2104//1 +f 2104//1 2140//1 2105//1 +f 2140//1 2141//1 2105//1 +f 2105//1 2141//1 2106//1 +f 2141//1 2142//1 2106//1 +f 2106//1 2142//1 2107//1 +f 2142//1 2143//1 2107//1 +f 2107//1 2143//1 2108//1 +f 2143//1 2144//1 2108//1 +f 2108//1 2144//1 2109//1 +f 2144//1 2145//1 2109//1 +f 2109//1 2145//1 19//1 +f 2145//1 18//1 19//1 +f 91//1 2146//1 2110//1 +f 2146//1 2147//1 2110//1 +f 2110//1 2147//1 2111//1 +f 2147//1 2148//1 2111//1 +f 2111//1 2148//1 2112//1 +f 2148//1 2149//1 2112//1 +f 2112//1 2149//1 2113//1 +f 2149//1 2150//1 2113//1 +f 2113//1 2150//1 2114//1 +f 2150//1 2151//1 2114//1 +f 2114//1 2151//1 2115//1 +f 2151//1 2152//1 2115//1 +f 2115//1 2152//1 2116//1 +f 2152//1 2153//1 2116//1 +f 2116//1 2153//1 2117//1 +f 2153//1 2154//1 2117//1 +f 2117//1 2154//1 2118//1 +f 2154//1 2155//1 2118//1 +f 2118//1 2155//1 2119//1 +f 2155//1 2156//1 2119//1 +f 2119//1 2156//1 2120//1 +f 2156//1 2157//1 2120//1 +f 2120//1 2157//1 2121//1 +f 2157//1 2158//1 2121//1 +f 2121//1 2158//1 2122//1 +f 2158//1 2159//1 2122//1 +f 2122//1 2159//1 2123//1 +f 2159//1 2160//1 2123//1 +f 2123//1 2160//1 2124//1 +f 2160//1 2161//1 2124//1 +f 2124//1 2161//1 2125//1 +f 2161//1 2162//1 2125//1 +f 2125//1 2162//1 2126//1 +f 2162//1 2163//1 2126//1 +f 2126//1 2163//1 2127//1 +f 2163//1 2164//1 2127//1 +f 2127//1 2164//1 2128//1 +f 2164//1 2165//1 2128//1 +f 2128//1 2165//1 2129//1 +f 2165//1 2166//1 2129//1 +f 2129//1 2166//1 2130//1 +f 2166//1 2167//1 2130//1 +f 2130//1 2167//1 2131//1 +f 2167//1 2168//1 2131//1 +f 2131//1 2168//1 2132//1 +f 2168//1 2169//1 2132//1 +f 2132//1 2169//1 2133//1 +f 2169//1 2170//1 2133//1 +f 2133//1 2170//1 2134//1 +f 2170//1 2171//1 2134//1 +f 2134//1 2171//1 2135//1 +f 2171//1 2172//1 2135//1 +f 2135//1 2172//1 2136//1 +f 2172//1 2173//1 2136//1 +f 2136//1 2173//1 2137//1 +f 2173//1 2174//1 2137//1 +f 2137//1 2174//1 2138//1 +f 2174//1 2175//1 2138//1 +f 2138//1 2175//1 2139//1 +f 2175//1 2176//1 2139//1 +f 2139//1 2176//1 2140//1 +f 2176//1 2177//1 2140//1 +f 2140//1 2177//1 2141//1 +f 2177//1 2178//1 2141//1 +f 2141//1 2178//1 2142//1 +f 2178//1 2179//1 2142//1 +f 2142//1 2179//1 2143//1 +f 2179//1 2180//1 2143//1 +f 2143//1 2180//1 2144//1 +f 2180//1 2181//1 2144//1 +f 2144//1 2181//1 2145//1 +f 2181//1 2182//1 2145//1 +f 2145//1 2182//1 18//1 +f 2182//1 17//1 18//1 +f 92//1 2183//1 2146//1 +f 2183//1 2184//1 2146//1 +f 2146//1 2184//1 2147//1 +f 2184//1 2185//1 2147//1 +f 2147//1 2185//1 2148//1 +f 2185//1 2186//1 2148//1 +f 2148//1 2186//1 2149//1 +f 2186//1 2187//1 2149//1 +f 2149//1 2187//1 2150//1 +f 2187//1 2188//1 2150//1 +f 2150//1 2188//1 2151//1 +f 2188//1 2189//1 2151//1 +f 2151//1 2189//1 2152//1 +f 2189//1 2190//1 2152//1 +f 2152//1 2190//1 2153//1 +f 2190//1 2191//1 2153//1 +f 2153//1 2191//1 2154//1 +f 2191//1 2192//1 2154//1 +f 2154//1 2192//1 2155//1 +f 2192//1 2193//1 2155//1 +f 2155//1 2193//1 2156//1 +f 2193//1 2194//1 2156//1 +f 2156//1 2194//1 2157//1 +f 2194//1 2195//1 2157//1 +f 2157//1 2195//1 2158//1 +f 2195//1 2196//1 2158//1 +f 2158//1 2196//1 2159//1 +f 2196//1 2197//1 2159//1 +f 2159//1 2197//1 2160//1 +f 2197//1 2198//1 2160//1 +f 2160//1 2198//1 2161//1 +f 2198//1 2199//1 2161//1 +f 2161//1 2199//1 2162//1 +f 2199//1 2200//1 2162//1 +f 2162//1 2200//1 2163//1 +f 2200//1 2201//1 2163//1 +f 2163//1 2201//1 2164//1 +f 2201//1 2202//1 2164//1 +f 2164//1 2202//1 2165//1 +f 2202//1 2203//1 2165//1 +f 2165//1 2203//1 2166//1 +f 2203//1 2204//1 2166//1 +f 2166//1 2204//1 2167//1 +f 2204//1 2205//1 2167//1 +f 2167//1 2205//1 2168//1 +f 2205//1 2206//1 2168//1 +f 2168//1 2206//1 2169//1 +f 2206//1 2207//1 2169//1 +f 2169//1 2207//1 2170//1 +f 2207//1 2208//1 2170//1 +f 2170//1 2208//1 2171//1 +f 2208//1 2209//1 2171//1 +f 2171//1 2209//1 2172//1 +f 2209//1 2210//1 2172//1 +f 2172//1 2210//1 2173//1 +f 2210//1 2211//1 2173//1 +f 2173//1 2211//1 2174//1 +f 2211//1 2212//1 2174//1 +f 2174//1 2212//1 2175//1 +f 2212//1 2213//1 2175//1 +f 2175//1 2213//1 2176//1 +f 2213//1 2214//1 2176//1 +f 2176//1 2214//1 2177//1 +f 2214//1 2215//1 2177//1 +f 2177//1 2215//1 2178//1 +f 2215//1 2216//1 2178//1 +f 2178//1 2216//1 2179//1 +f 2216//1 2217//1 2179//1 +f 2179//1 2217//1 2180//1 +f 2217//1 2218//1 2180//1 +f 2180//1 2218//1 2181//1 +f 2218//1 2219//1 2181//1 +f 2181//1 2219//1 2182//1 +f 2219//1 2220//1 2182//1 +f 2182//1 2220//1 17//1 +f 2220//1 16//1 17//1 +f 93//1 2221//1 2183//1 +f 2221//1 2222//1 2183//1 +f 2183//1 2222//1 2184//1 +f 2222//1 2223//1 2184//1 +f 2184//1 2223//1 2185//1 +f 2223//1 2224//1 2185//1 +f 2185//1 2224//1 2186//1 +f 2224//1 2225//1 2186//1 +f 2186//1 2225//1 2187//1 +f 2225//1 2226//1 2187//1 +f 2187//1 2226//1 2188//1 +f 2226//1 2227//1 2188//1 +f 2188//1 2227//1 2189//1 +f 2227//1 2228//1 2189//1 +f 2189//1 2228//1 2190//1 +f 2228//1 2229//1 2190//1 +f 2190//1 2229//1 2191//1 +f 2229//1 2230//1 2191//1 +f 2191//1 2230//1 2192//1 +f 2230//1 2231//1 2192//1 +f 2192//1 2231//1 2193//1 +f 2231//1 2232//1 2193//1 +f 2193//1 2232//1 2194//1 +f 2232//1 2233//1 2194//1 +f 2194//1 2233//1 2195//1 +f 2233//1 2234//1 2195//1 +f 2195//1 2234//1 2196//1 +f 2234//1 2235//1 2196//1 +f 2196//1 2235//1 2197//1 +f 2235//1 2236//1 2197//1 +f 2197//1 2236//1 2198//1 +f 2236//1 2237//1 2198//1 +f 2198//1 2237//1 2199//1 +f 2237//1 2238//1 2199//1 +f 2199//1 2238//1 2200//1 +f 2238//1 2239//1 2200//1 +f 2200//1 2239//1 2201//1 +f 2239//1 2240//1 2201//1 +f 2201//1 2240//1 2202//1 +f 2240//1 2241//1 2202//1 +f 2202//1 2241//1 2203//1 +f 2241//1 2242//1 2203//1 +f 2203//1 2242//1 2204//1 +f 2242//1 2243//1 2204//1 +f 2204//1 2243//1 2205//1 +f 2243//1 2244//1 2205//1 +f 2205//1 2244//1 2206//1 +f 2244//1 2245//1 2206//1 +f 2206//1 2245//1 2207//1 +f 2245//1 2246//1 2207//1 +f 2207//1 2246//1 2208//1 +f 2246//1 2247//1 2208//1 +f 2208//1 2247//1 2209//1 +f 2247//1 2248//1 2209//1 +f 2209//1 2248//1 2210//1 +f 2248//1 2249//1 2210//1 +f 2210//1 2249//1 2211//1 +f 2249//1 2250//1 2211//1 +f 2211//1 2250//1 2212//1 +f 2250//1 2251//1 2212//1 +f 2212//1 2251//1 2213//1 +f 2251//1 2252//1 2213//1 +f 2213//1 2252//1 2214//1 +f 2252//1 2253//1 2214//1 +f 2214//1 2253//1 2215//1 +f 2253//1 2254//1 2215//1 +f 2215//1 2254//1 2216//1 +f 2254//1 2255//1 2216//1 +f 2216//1 2255//1 2217//1 +f 2255//1 2256//1 2217//1 +f 2217//1 2256//1 2218//1 +f 2256//1 2257//1 2218//1 +f 2218//1 2257//1 2219//1 +f 2257//1 2258//1 2219//1 +f 2219//1 2258//1 2220//1 +f 2258//1 2259//1 2220//1 +f 2220//1 2259//1 16//1 +f 2259//1 15//1 16//1 +f 94//1 2260//1 2221//1 +f 2260//1 2261//1 2221//1 +f 2221//1 2261//1 2222//1 +f 2261//1 2262//1 2222//1 +f 2222//1 2262//1 2223//1 +f 2262//1 2263//1 2223//1 +f 2223//1 2263//1 2224//1 +f 2263//1 2264//1 2224//1 +f 2224//1 2264//1 2225//1 +f 2264//1 2265//1 2225//1 +f 2225//1 2265//1 2226//1 +f 2265//1 2266//1 2226//1 +f 2226//1 2266//1 2227//1 +f 2266//1 2267//1 2227//1 +f 2227//1 2267//1 2228//1 +f 2267//1 2268//1 2228//1 +f 2228//1 2268//1 2229//1 +f 2268//1 2269//1 2229//1 +f 2229//1 2269//1 2230//1 +f 2269//1 2270//1 2230//1 +f 2230//1 2270//1 2231//1 +f 2270//1 2271//1 2231//1 +f 2231//1 2271//1 2232//1 +f 2271//1 2272//1 2232//1 +f 2232//1 2272//1 2233//1 +f 2272//1 2273//1 2233//1 +f 2233//1 2273//1 2234//1 +f 2273//1 2274//1 2234//1 +f 2234//1 2274//1 2235//1 +f 2274//1 2275//1 2235//1 +f 2235//1 2275//1 2236//1 +f 2275//1 2276//1 2236//1 +f 2236//1 2276//1 2237//1 +f 2276//1 2277//1 2237//1 +f 2237//1 2277//1 2238//1 +f 2277//1 2278//1 2238//1 +f 2238//1 2278//1 2239//1 +f 2278//1 2279//1 2239//1 +f 2239//1 2279//1 2240//1 +f 2279//1 2280//1 2240//1 +f 2240//1 2280//1 2241//1 +f 2280//1 2281//1 2241//1 +f 2241//1 2281//1 2242//1 +f 2281//1 2282//1 2242//1 +f 2242//1 2282//1 2243//1 +f 2282//1 2283//1 2243//1 +f 2243//1 2283//1 2244//1 +f 2283//1 2284//1 2244//1 +f 2244//1 2284//1 2245//1 +f 2284//1 2285//1 2245//1 +f 2245//1 2285//1 2246//1 +f 2285//1 2286//1 2246//1 +f 2246//1 2286//1 2247//1 +f 2286//1 2287//1 2247//1 +f 2247//1 2287//1 2248//1 +f 2287//1 2288//1 2248//1 +f 2248//1 2288//1 2249//1 +f 2288//1 2289//1 2249//1 +f 2249//1 2289//1 2250//1 +f 2289//1 2290//1 2250//1 +f 2250//1 2290//1 2251//1 +f 2290//1 2291//1 2251//1 +f 2251//1 2291//1 2252//1 +f 2291//1 2292//1 2252//1 +f 2252//1 2292//1 2253//1 +f 2292//1 2293//1 2253//1 +f 2253//1 2293//1 2254//1 +f 2293//1 2294//1 2254//1 +f 2254//1 2294//1 2255//1 +f 2294//1 2295//1 2255//1 +f 2255//1 2295//1 2256//1 +f 2295//1 2296//1 2256//1 +f 2256//1 2296//1 2257//1 +f 2296//1 2297//1 2257//1 +f 2257//1 2297//1 2258//1 +f 2297//1 2298//1 2258//1 +f 2258//1 2298//1 2259//1 +f 2298//1 2299//1 2259//1 +f 2259//1 2299//1 15//1 +f 2299//1 14//1 15//1 +f 95//1 2300//1 2260//1 +f 2300//1 2301//1 2260//1 +f 2260//1 2301//1 2261//1 +f 2301//1 2302//1 2261//1 +f 2261//1 2302//1 2262//1 +f 2302//1 2303//1 2262//1 +f 2262//1 2303//1 2263//1 +f 2303//1 2304//1 2263//1 +f 2263//1 2304//1 2264//1 +f 2304//1 2305//1 2264//1 +f 2264//1 2305//1 2265//1 +f 2305//1 2306//1 2265//1 +f 2265//1 2306//1 2266//1 +f 2306//1 2307//1 2266//1 +f 2266//1 2307//1 2267//1 +f 2307//1 2308//1 2267//1 +f 2267//1 2308//1 2268//1 +f 2308//1 2309//1 2268//1 +f 2268//1 2309//1 2269//1 +f 2309//1 2310//1 2269//1 +f 2269//1 2310//1 2270//1 +f 2310//1 2311//1 2270//1 +f 2270//1 2311//1 2271//1 +f 2311//1 2312//1 2271//1 +f 2271//1 2312//1 2272//1 +f 2312//1 2313//1 2272//1 +f 2272//1 2313//1 2273//1 +f 2313//1 2314//1 2273//1 +f 2273//1 2314//1 2274//1 +f 2314//1 2315//1 2274//1 +f 2274//1 2315//1 2275//1 +f 2315//1 2316//1 2275//1 +f 2275//1 2316//1 2276//1 +f 2316//1 2317//1 2276//1 +f 2276//1 2317//1 2277//1 +f 2317//1 2318//1 2277//1 +f 2277//1 2318//1 2278//1 +f 2318//1 2319//1 2278//1 +f 2278//1 2319//1 2279//1 +f 2319//1 2320//1 2279//1 +f 2279//1 2320//1 2280//1 +f 2320//1 2321//1 2280//1 +f 2280//1 2321//1 2281//1 +f 2321//1 2322//1 2281//1 +f 2281//1 2322//1 2282//1 +f 2322//1 2323//1 2282//1 +f 2282//1 2323//1 2283//1 +f 2323//1 2324//1 2283//1 +f 2283//1 2324//1 2284//1 +f 2324//1 2325//1 2284//1 +f 2284//1 2325//1 2285//1 +f 2325//1 2326//1 2285//1 +f 2285//1 2326//1 2286//1 +f 2326//1 2327//1 2286//1 +f 2286//1 2327//1 2287//1 +f 2327//1 2328//1 2287//1 +f 2287//1 2328//1 2288//1 +f 2328//1 2329//1 2288//1 +f 2288//1 2329//1 2289//1 +f 2329//1 2330//1 2289//1 +f 2289//1 2330//1 2290//1 +f 2330//1 2331//1 2290//1 +f 2290//1 2331//1 2291//1 +f 2331//1 2332//1 2291//1 +f 2291//1 2332//1 2292//1 +f 2332//1 2333//1 2292//1 +f 2292//1 2333//1 2293//1 +f 2333//1 2334//1 2293//1 +f 2293//1 2334//1 2294//1 +f 2334//1 2335//1 2294//1 +f 2294//1 2335//1 2295//1 +f 2335//1 2336//1 2295//1 +f 2295//1 2336//1 2296//1 +f 2336//1 2337//1 2296//1 +f 2296//1 2337//1 2297//1 +f 2337//1 2338//1 2297//1 +f 2297//1 2338//1 2298//1 +f 2338//1 2339//1 2298//1 +f 2298//1 2339//1 2299//1 +f 2339//1 2340//1 2299//1 +f 2299//1 2340//1 14//1 +f 2340//1 13//1 14//1 +f 96//1 2341//1 2300//1 +f 2341//1 2342//1 2300//1 +f 2300//1 2342//1 2301//1 +f 2342//1 2343//1 2301//1 +f 2301//1 2343//1 2302//1 +f 2343//1 2344//1 2302//1 +f 2302//1 2344//1 2303//1 +f 2344//1 2345//1 2303//1 +f 2303//1 2345//1 2304//1 +f 2345//1 2346//1 2304//1 +f 2304//1 2346//1 2305//1 +f 2346//1 2347//1 2305//1 +f 2305//1 2347//1 2306//1 +f 2347//1 2348//1 2306//1 +f 2306//1 2348//1 2307//1 +f 2348//1 2349//1 2307//1 +f 2307//1 2349//1 2308//1 +f 2349//1 2350//1 2308//1 +f 2308//1 2350//1 2309//1 +f 2350//1 2351//1 2309//1 +f 2309//1 2351//1 2310//1 +f 2351//1 2352//1 2310//1 +f 2310//1 2352//1 2311//1 +f 2352//1 2353//1 2311//1 +f 2311//1 2353//1 2312//1 +f 2353//1 2354//1 2312//1 +f 2312//1 2354//1 2313//1 +f 2354//1 2355//1 2313//1 +f 2313//1 2355//1 2314//1 +f 2355//1 2356//1 2314//1 +f 2314//1 2356//1 2315//1 +f 2356//1 2357//1 2315//1 +f 2315//1 2357//1 2316//1 +f 2357//1 2358//1 2316//1 +f 2316//1 2358//1 2317//1 +f 2358//1 2359//1 2317//1 +f 2317//1 2359//1 2318//1 +f 2359//1 2360//1 2318//1 +f 2318//1 2360//1 2319//1 +f 2360//1 2361//1 2319//1 +f 2319//1 2361//1 2320//1 +f 2361//1 2362//1 2320//1 +f 2320//1 2362//1 2321//1 +f 2362//1 2363//1 2321//1 +f 2321//1 2363//1 2322//1 +f 2363//1 2364//1 2322//1 +f 2322//1 2364//1 2323//1 +f 2364//1 2365//1 2323//1 +f 2323//1 2365//1 2324//1 +f 2365//1 2366//1 2324//1 +f 2324//1 2366//1 2325//1 +f 2366//1 2367//1 2325//1 +f 2325//1 2367//1 2326//1 +f 2367//1 2368//1 2326//1 +f 2326//1 2368//1 2327//1 +f 2368//1 2369//1 2327//1 +f 2327//1 2369//1 2328//1 +f 2369//1 2370//1 2328//1 +f 2328//1 2370//1 2329//1 +f 2370//1 2371//1 2329//1 +f 2329//1 2371//1 2330//1 +f 2371//1 2372//1 2330//1 +f 2330//1 2372//1 2331//1 +f 2372//1 2373//1 2331//1 +f 2331//1 2373//1 2332//1 +f 2373//1 2374//1 2332//1 +f 2332//1 2374//1 2333//1 +f 2374//1 2375//1 2333//1 +f 2333//1 2375//1 2334//1 +f 2375//1 2376//1 2334//1 +f 2334//1 2376//1 2335//1 +f 2376//1 2377//1 2335//1 +f 2335//1 2377//1 2336//1 +f 2377//1 2378//1 2336//1 +f 2336//1 2378//1 2337//1 +f 2378//1 2379//1 2337//1 +f 2337//1 2379//1 2338//1 +f 2379//1 2380//1 2338//1 +f 2338//1 2380//1 2339//1 +f 2380//1 2381//1 2339//1 +f 2339//1 2381//1 2340//1 +f 2381//1 2382//1 2340//1 +f 2340//1 2382//1 13//1 +f 2382//1 12//1 13//1 +f 97//1 2383//1 2341//1 +f 2383//1 2384//1 2341//1 +f 2341//1 2384//1 2342//1 +f 2384//1 2385//1 2342//1 +f 2342//1 2385//1 2343//1 +f 2385//1 2386//1 2343//1 +f 2343//1 2386//1 2344//1 +f 2386//1 2387//1 2344//1 +f 2344//1 2387//1 2345//1 +f 2387//1 2388//1 2345//1 +f 2345//1 2388//1 2346//1 +f 2388//1 2389//1 2346//1 +f 2346//1 2389//1 2347//1 +f 2389//1 2390//1 2347//1 +f 2347//1 2390//1 2348//1 +f 2390//1 2391//1 2348//1 +f 2348//1 2391//1 2349//1 +f 2391//1 2392//1 2349//1 +f 2349//1 2392//1 2350//1 +f 2392//1 2393//1 2350//1 +f 2350//1 2393//1 2351//1 +f 2393//1 2394//1 2351//1 +f 2351//1 2394//1 2352//1 +f 2394//1 2395//1 2352//1 +f 2352//1 2395//1 2353//1 +f 2395//1 2396//1 2353//1 +f 2353//1 2396//1 2354//1 +f 2396//1 2397//1 2354//1 +f 2354//1 2397//1 2355//1 +f 2397//1 2398//1 2355//1 +f 2355//1 2398//1 2356//1 +f 2398//1 2399//1 2356//1 +f 2356//1 2399//1 2357//1 +f 2399//1 2400//1 2357//1 +f 2357//1 2400//1 2358//1 +f 2400//1 2401//1 2358//1 +f 2358//1 2401//1 2359//1 +f 2401//1 2402//1 2359//1 +f 2359//1 2402//1 2360//1 +f 2402//1 2403//1 2360//1 +f 2360//1 2403//1 2361//1 +f 2403//1 2404//1 2361//1 +f 2361//1 2404//1 2362//1 +f 2404//1 2405//1 2362//1 +f 2362//1 2405//1 2363//1 +f 2405//1 2406//1 2363//1 +f 2363//1 2406//1 2364//1 +f 2406//1 2407//1 2364//1 +f 2364//1 2407//1 2365//1 +f 2407//1 2408//1 2365//1 +f 2365//1 2408//1 2366//1 +f 2408//1 2409//1 2366//1 +f 2366//1 2409//1 2367//1 +f 2409//1 2410//1 2367//1 +f 2367//1 2410//1 2368//1 +f 2410//1 2411//1 2368//1 +f 2368//1 2411//1 2369//1 +f 2411//1 2412//1 2369//1 +f 2369//1 2412//1 2370//1 +f 2412//1 2413//1 2370//1 +f 2370//1 2413//1 2371//1 +f 2413//1 2414//1 2371//1 +f 2371//1 2414//1 2372//1 +f 2414//1 2415//1 2372//1 +f 2372//1 2415//1 2373//1 +f 2415//1 2416//1 2373//1 +f 2373//1 2416//1 2374//1 +f 2416//1 2417//1 2374//1 +f 2374//1 2417//1 2375//1 +f 2417//1 2418//1 2375//1 +f 2375//1 2418//1 2376//1 +f 2418//1 2419//1 2376//1 +f 2376//1 2419//1 2377//1 +f 2419//1 2420//1 2377//1 +f 2377//1 2420//1 2378//1 +f 2420//1 2421//1 2378//1 +f 2378//1 2421//1 2379//1 +f 2421//1 2422//1 2379//1 +f 2379//1 2422//1 2380//1 +f 2422//1 2423//1 2380//1 +f 2380//1 2423//1 2381//1 +f 2423//1 2424//1 2381//1 +f 2381//1 2424//1 2382//1 +f 2424//1 2425//1 2382//1 +f 2382//1 2425//1 12//1 +f 2425//1 11//1 12//1 +f 98//1 2426//1 2383//1 +f 2426//1 2427//1 2383//1 +f 2383//1 2427//1 2384//1 +f 2427//1 2428//1 2384//1 +f 2384//1 2428//1 2385//1 +f 2428//1 2429//1 2385//1 +f 2385//1 2429//1 2386//1 +f 2429//1 2430//1 2386//1 +f 2386//1 2430//1 2387//1 +f 2430//1 2431//1 2387//1 +f 2387//1 2431//1 2388//1 +f 2431//1 2432//1 2388//1 +f 2388//1 2432//1 2389//1 +f 2432//1 2433//1 2389//1 +f 2389//1 2433//1 2390//1 +f 2433//1 2434//1 2390//1 +f 2390//1 2434//1 2391//1 +f 2434//1 2435//1 2391//1 +f 2391//1 2435//1 2392//1 +f 2435//1 2436//1 2392//1 +f 2392//1 2436//1 2393//1 +f 2436//1 2437//1 2393//1 +f 2393//1 2437//1 2394//1 +f 2437//1 2438//1 2394//1 +f 2394//1 2438//1 2395//1 +f 2438//1 2439//1 2395//1 +f 2395//1 2439//1 2396//1 +f 2439//1 2440//1 2396//1 +f 2396//1 2440//1 2397//1 +f 2440//1 2441//1 2397//1 +f 2397//1 2441//1 2398//1 +f 2441//1 2442//1 2398//1 +f 2398//1 2442//1 2399//1 +f 2442//1 2443//1 2399//1 +f 2399//1 2443//1 2400//1 +f 2443//1 2444//1 2400//1 +f 2400//1 2444//1 2401//1 +f 2444//1 2445//1 2401//1 +f 2401//1 2445//1 2402//1 +f 2445//1 2446//1 2402//1 +f 2402//1 2446//1 2403//1 +f 2446//1 2447//1 2403//1 +f 2403//1 2447//1 2404//1 +f 2447//1 2448//1 2404//1 +f 2404//1 2448//1 2405//1 +f 2448//1 2449//1 2405//1 +f 2405//1 2449//1 2406//1 +f 2449//1 2450//1 2406//1 +f 2406//1 2450//1 2407//1 +f 2450//1 2451//1 2407//1 +f 2407//1 2451//1 2408//1 +f 2451//1 2452//1 2408//1 +f 2408//1 2452//1 2409//1 +f 2452//1 2453//1 2409//1 +f 2409//1 2453//1 2410//1 +f 2453//1 2454//1 2410//1 +f 2410//1 2454//1 2411//1 +f 2454//1 2455//1 2411//1 +f 2411//1 2455//1 2412//1 +f 2455//1 2456//1 2412//1 +f 2412//1 2456//1 2413//1 +f 2456//1 2457//1 2413//1 +f 2413//1 2457//1 2414//1 +f 2457//1 2458//1 2414//1 +f 2414//1 2458//1 2415//1 +f 2458//1 2459//1 2415//1 +f 2415//1 2459//1 2416//1 +f 2459//1 2460//1 2416//1 +f 2416//1 2460//1 2417//1 +f 2460//1 2461//1 2417//1 +f 2417//1 2461//1 2418//1 +f 2461//1 2462//1 2418//1 +f 2418//1 2462//1 2419//1 +f 2462//1 2463//1 2419//1 +f 2419//1 2463//1 2420//1 +f 2463//1 2464//1 2420//1 +f 2420//1 2464//1 2421//1 +f 2464//1 2465//1 2421//1 +f 2421//1 2465//1 2422//1 +f 2465//1 2466//1 2422//1 +f 2422//1 2466//1 2423//1 +f 2466//1 2467//1 2423//1 +f 2423//1 2467//1 2424//1 +f 2467//1 2468//1 2424//1 +f 2424//1 2468//1 2425//1 +f 2468//1 2469//1 2425//1 +f 2425//1 2469//1 11//1 +f 2469//1 10//1 11//1 +f 99//1 2470//1 2426//1 +f 2470//1 2471//1 2426//1 +f 2426//1 2471//1 2427//1 +f 2471//1 2472//1 2427//1 +f 2427//1 2472//1 2428//1 +f 2472//1 2473//1 2428//1 +f 2428//1 2473//1 2429//1 +f 2473//1 2474//1 2429//1 +f 2429//1 2474//1 2430//1 +f 2474//1 2475//1 2430//1 +f 2430//1 2475//1 2431//1 +f 2475//1 2476//1 2431//1 +f 2431//1 2476//1 2432//1 +f 2476//1 2477//1 2432//1 +f 2432//1 2477//1 2433//1 +f 2477//1 2478//1 2433//1 +f 2433//1 2478//1 2434//1 +f 2478//1 2479//1 2434//1 +f 2434//1 2479//1 2435//1 +f 2479//1 2480//1 2435//1 +f 2435//1 2480//1 2436//1 +f 2480//1 2481//1 2436//1 +f 2436//1 2481//1 2437//1 +f 2481//1 2482//1 2437//1 +f 2437//1 2482//1 2438//1 +f 2482//1 2483//1 2438//1 +f 2438//1 2483//1 2439//1 +f 2483//1 2484//1 2439//1 +f 2439//1 2484//1 2440//1 +f 2484//1 2485//1 2440//1 +f 2440//1 2485//1 2441//1 +f 2485//1 2486//1 2441//1 +f 2441//1 2486//1 2442//1 +f 2486//1 2487//1 2442//1 +f 2442//1 2487//1 2443//1 +f 2487//1 2488//1 2443//1 +f 2443//1 2488//1 2444//1 +f 2488//1 2489//1 2444//1 +f 2444//1 2489//1 2445//1 +f 2489//1 2490//1 2445//1 +f 2445//1 2490//1 2446//1 +f 2490//1 2491//1 2446//1 +f 2446//1 2491//1 2447//1 +f 2491//1 2492//1 2447//1 +f 2447//1 2492//1 2448//1 +f 2492//1 2493//1 2448//1 +f 2448//1 2493//1 2449//1 +f 2493//1 2494//1 2449//1 +f 2449//1 2494//1 2450//1 +f 2494//1 2495//1 2450//1 +f 2450//1 2495//1 2451//1 +f 2495//1 2496//1 2451//1 +f 2451//1 2496//1 2452//1 +f 2496//1 2497//1 2452//1 +f 2452//1 2497//1 2453//1 +f 2497//1 2498//1 2453//1 +f 2453//1 2498//1 2454//1 +f 2498//1 2499//1 2454//1 +f 2454//1 2499//1 2455//1 +f 2499//1 2500//1 2455//1 +f 2455//1 2500//1 2456//1 +f 2500//1 2501//1 2456//1 +f 2456//1 2501//1 2457//1 +f 2501//1 2502//1 2457//1 +f 2457//1 2502//1 2458//1 +f 2502//1 2503//1 2458//1 +f 2458//1 2503//1 2459//1 +f 2503//1 2504//1 2459//1 +f 2459//1 2504//1 2460//1 +f 2504//1 2505//1 2460//1 +f 2460//1 2505//1 2461//1 +f 2505//1 2506//1 2461//1 +f 2461//1 2506//1 2462//1 +f 2506//1 2507//1 2462//1 +f 2462//1 2507//1 2463//1 +f 2507//1 2508//1 2463//1 +f 2463//1 2508//1 2464//1 +f 2508//1 2509//1 2464//1 +f 2464//1 2509//1 2465//1 +f 2509//1 2510//1 2465//1 +f 2465//1 2510//1 2466//1 +f 2510//1 2511//1 2466//1 +f 2466//1 2511//1 2467//1 +f 2511//1 2512//1 2467//1 +f 2467//1 2512//1 2468//1 +f 2512//1 2513//1 2468//1 +f 2468//1 2513//1 2469//1 +f 2513//1 2514//1 2469//1 +f 2469//1 2514//1 10//1 +f 2514//1 9//1 10//1 +f 100//1 2515//1 2470//1 +f 2515//1 2516//1 2470//1 +f 2470//1 2516//1 2471//1 +f 2516//1 2517//1 2471//1 +f 2471//1 2517//1 2472//1 +f 2517//1 2518//1 2472//1 +f 2472//1 2518//1 2473//1 +f 2518//1 2519//1 2473//1 +f 2473//1 2519//1 2474//1 +f 2519//1 2520//1 2474//1 +f 2474//1 2520//1 2475//1 +f 2520//1 2521//1 2475//1 +f 2475//1 2521//1 2476//1 +f 2521//1 2522//1 2476//1 +f 2476//1 2522//1 2477//1 +f 2522//1 2523//1 2477//1 +f 2477//1 2523//1 2478//1 +f 2523//1 2524//1 2478//1 +f 2478//1 2524//1 2479//1 +f 2524//1 2525//1 2479//1 +f 2479//1 2525//1 2480//1 +f 2525//1 2526//1 2480//1 +f 2480//1 2526//1 2481//1 +f 2526//1 2527//1 2481//1 +f 2481//1 2527//1 2482//1 +f 2527//1 2528//1 2482//1 +f 2482//1 2528//1 2483//1 +f 2528//1 2529//1 2483//1 +f 2483//1 2529//1 2484//1 +f 2529//1 2530//1 2484//1 +f 2484//1 2530//1 2485//1 +f 2530//1 2531//1 2485//1 +f 2485//1 2531//1 2486//1 +f 2531//1 2532//1 2486//1 +f 2486//1 2532//1 2487//1 +f 2532//1 2533//1 2487//1 +f 2487//1 2533//1 2488//1 +f 2533//1 2534//1 2488//1 +f 2488//1 2534//1 2489//1 +f 2534//1 2535//1 2489//1 +f 2489//1 2535//1 2490//1 +f 2535//1 2536//1 2490//1 +f 2490//1 2536//1 2491//1 +f 2536//1 2537//1 2491//1 +f 2491//1 2537//1 2492//1 +f 2537//1 2538//1 2492//1 +f 2492//1 2538//1 2493//1 +f 2538//1 2539//1 2493//1 +f 2493//1 2539//1 2494//1 +f 2539//1 2540//1 2494//1 +f 2494//1 2540//1 2495//1 +f 2540//1 2541//1 2495//1 +f 2495//1 2541//1 2496//1 +f 2541//1 2542//1 2496//1 +f 2496//1 2542//1 2497//1 +f 2542//1 2543//1 2497//1 +f 2497//1 2543//1 2498//1 +f 2543//1 2544//1 2498//1 +f 2498//1 2544//1 2499//1 +f 2544//1 2545//1 2499//1 +f 2499//1 2545//1 2500//1 +f 2545//1 2546//1 2500//1 +f 2500//1 2546//1 2501//1 +f 2546//1 2547//1 2501//1 +f 2501//1 2547//1 2502//1 +f 2547//1 2548//1 2502//1 +f 2502//1 2548//1 2503//1 +f 2548//1 2549//1 2503//1 +f 2503//1 2549//1 2504//1 +f 2549//1 2550//1 2504//1 +f 2504//1 2550//1 2505//1 +f 2550//1 2551//1 2505//1 +f 2505//1 2551//1 2506//1 +f 2551//1 2552//1 2506//1 +f 2506//1 2552//1 2507//1 +f 2552//1 2553//1 2507//1 +f 2507//1 2553//1 2508//1 +f 2553//1 2554//1 2508//1 +f 2508//1 2554//1 2509//1 +f 2554//1 2555//1 2509//1 +f 2509//1 2555//1 2510//1 +f 2555//1 2556//1 2510//1 +f 2510//1 2556//1 2511//1 +f 2556//1 2557//1 2511//1 +f 2511//1 2557//1 2512//1 +f 2557//1 2558//1 2512//1 +f 2512//1 2558//1 2513//1 +f 2558//1 2559//1 2513//1 +f 2513//1 2559//1 2514//1 +f 2559//1 2560//1 2514//1 +f 2514//1 2560//1 9//1 +f 2560//1 8//1 9//1 +f 101//1 2561//1 2515//1 +f 2561//1 2562//1 2515//1 +f 2515//1 2562//1 2516//1 +f 2562//1 2563//1 2516//1 +f 2516//1 2563//1 2517//1 +f 2563//1 2564//1 2517//1 +f 2517//1 2564//1 2518//1 +f 2564//1 2565//1 2518//1 +f 2518//1 2565//1 2519//1 +f 2565//1 2566//1 2519//1 +f 2519//1 2566//1 2520//1 +f 2566//1 2567//1 2520//1 +f 2520//1 2567//1 2521//1 +f 2567//1 2568//1 2521//1 +f 2521//1 2568//1 2522//1 +f 2568//1 2569//1 2522//1 +f 2522//1 2569//1 2523//1 +f 2569//1 2570//1 2523//1 +f 2523//1 2570//1 2524//1 +f 2570//1 2571//1 2524//1 +f 2524//1 2571//1 2525//1 +f 2571//1 2572//1 2525//1 +f 2525//1 2572//1 2526//1 +f 2572//1 2573//1 2526//1 +f 2526//1 2573//1 2527//1 +f 2573//1 2574//1 2527//1 +f 2527//1 2574//1 2528//1 +f 2574//1 2575//1 2528//1 +f 2528//1 2575//1 2529//1 +f 2575//1 2576//1 2529//1 +f 2529//1 2576//1 2530//1 +f 2576//1 2577//1 2530//1 +f 2530//1 2577//1 2531//1 +f 2577//1 2578//1 2531//1 +f 2531//1 2578//1 2532//1 +f 2578//1 2579//1 2532//1 +f 2532//1 2579//1 2533//1 +f 2579//1 2580//1 2533//1 +f 2533//1 2580//1 2534//1 +f 2580//1 2581//1 2534//1 +f 2534//1 2581//1 2535//1 +f 2581//1 2582//1 2535//1 +f 2535//1 2582//1 2536//1 +f 2582//1 2583//1 2536//1 +f 2536//1 2583//1 2537//1 +f 2583//1 2584//1 2537//1 +f 2537//1 2584//1 2538//1 +f 2584//1 2585//1 2538//1 +f 2538//1 2585//1 2539//1 +f 2585//1 2586//1 2539//1 +f 2539//1 2586//1 2540//1 +f 2586//1 2587//1 2540//1 +f 2540//1 2587//1 2541//1 +f 2587//1 2588//1 2541//1 +f 2541//1 2588//1 2542//1 +f 2588//1 2589//1 2542//1 +f 2542//1 2589//1 2543//1 +f 2589//1 2590//1 2543//1 +f 2543//1 2590//1 2544//1 +f 2590//1 2591//1 2544//1 +f 2544//1 2591//1 2545//1 +f 2591//1 2592//1 2545//1 +f 2545//1 2592//1 2546//1 +f 2592//1 2593//1 2546//1 +f 2546//1 2593//1 2547//1 +f 2593//1 2594//1 2547//1 +f 2547//1 2594//1 2548//1 +f 2594//1 2595//1 2548//1 +f 2548//1 2595//1 2549//1 +f 2595//1 2596//1 2549//1 +f 2549//1 2596//1 2550//1 +f 2596//1 2597//1 2550//1 +f 2550//1 2597//1 2551//1 +f 2597//1 2598//1 2551//1 +f 2551//1 2598//1 2552//1 +f 2598//1 2599//1 2552//1 +f 2552//1 2599//1 2553//1 +f 2599//1 2600//1 2553//1 +f 2553//1 2600//1 2554//1 +f 2600//1 2601//1 2554//1 +f 2554//1 2601//1 2555//1 +f 2601//1 2602//1 2555//1 +f 2555//1 2602//1 2556//1 +f 2602//1 2603//1 2556//1 +f 2556//1 2603//1 2557//1 +f 2603//1 2604//1 2557//1 +f 2557//1 2604//1 2558//1 +f 2604//1 2605//1 2558//1 +f 2558//1 2605//1 2559//1 +f 2605//1 2606//1 2559//1 +f 2559//1 2606//1 2560//1 +f 2606//1 2607//1 2560//1 +f 2560//1 2607//1 8//1 +f 2607//1 7//1 8//1 +f 102//1 2608//1 2561//1 +f 2608//1 2609//1 2561//1 +f 2561//1 2609//1 2562//1 +f 2609//1 2610//1 2562//1 +f 2562//1 2610//1 2563//1 +f 2610//1 2611//1 2563//1 +f 2563//1 2611//1 2564//1 +f 2611//1 2612//1 2564//1 +f 2564//1 2612//1 2565//1 +f 2612//1 2613//1 2565//1 +f 2565//1 2613//1 2566//1 +f 2613//1 2614//1 2566//1 +f 2566//1 2614//1 2567//1 +f 2614//1 2615//1 2567//1 +f 2567//1 2615//1 2568//1 +f 2615//1 2616//1 2568//1 +f 2568//1 2616//1 2569//1 +f 2616//1 2617//1 2569//1 +f 2569//1 2617//1 2570//1 +f 2617//1 2618//1 2570//1 +f 2570//1 2618//1 2571//1 +f 2618//1 2619//1 2571//1 +f 2571//1 2619//1 2572//1 +f 2619//1 2620//1 2572//1 +f 2572//1 2620//1 2573//1 +f 2620//1 2621//1 2573//1 +f 2573//1 2621//1 2574//1 +f 2621//1 2622//1 2574//1 +f 2574//1 2622//1 2575//1 +f 2622//1 2623//1 2575//1 +f 2575//1 2623//1 2576//1 +f 2623//1 2624//1 2576//1 +f 2576//1 2624//1 2577//1 +f 2624//1 2625//1 2577//1 +f 2577//1 2625//1 2578//1 +f 2625//1 2626//1 2578//1 +f 2578//1 2626//1 2579//1 +f 2626//1 2627//1 2579//1 +f 2579//1 2627//1 2580//1 +f 2627//1 2628//1 2580//1 +f 2580//1 2628//1 2581//1 +f 2628//1 2629//1 2581//1 +f 2581//1 2629//1 2582//1 +f 2629//1 2630//1 2582//1 +f 2582//1 2630//1 2583//1 +f 2630//1 2631//1 2583//1 +f 2583//1 2631//1 2584//1 +f 2631//1 2632//1 2584//1 +f 2584//1 2632//1 2585//1 +f 2632//1 2633//1 2585//1 +f 2585//1 2633//1 2586//1 +f 2633//1 2634//1 2586//1 +f 2586//1 2634//1 2587//1 +f 2634//1 2635//1 2587//1 +f 2587//1 2635//1 2588//1 +f 2635//1 2636//1 2588//1 +f 2588//1 2636//1 2589//1 +f 2636//1 2637//1 2589//1 +f 2589//1 2637//1 2590//1 +f 2637//1 2638//1 2590//1 +f 2590//1 2638//1 2591//1 +f 2638//1 2639//1 2591//1 +f 2591//1 2639//1 2592//1 +f 2639//1 2640//1 2592//1 +f 2592//1 2640//1 2593//1 +f 2640//1 2641//1 2593//1 +f 2593//1 2641//1 2594//1 +f 2641//1 2642//1 2594//1 +f 2594//1 2642//1 2595//1 +f 2642//1 2643//1 2595//1 +f 2595//1 2643//1 2596//1 +f 2643//1 2644//1 2596//1 +f 2596//1 2644//1 2597//1 +f 2644//1 2645//1 2597//1 +f 2597//1 2645//1 2598//1 +f 2645//1 2646//1 2598//1 +f 2598//1 2646//1 2599//1 +f 2646//1 2647//1 2599//1 +f 2599//1 2647//1 2600//1 +f 2647//1 2648//1 2600//1 +f 2600//1 2648//1 2601//1 +f 2648//1 2649//1 2601//1 +f 2601//1 2649//1 2602//1 +f 2649//1 2650//1 2602//1 +f 2602//1 2650//1 2603//1 +f 2650//1 2651//1 2603//1 +f 2603//1 2651//1 2604//1 +f 2651//1 2652//1 2604//1 +f 2604//1 2652//1 2605//1 +f 2652//1 2653//1 2605//1 +f 2605//1 2653//1 2606//1 +f 2653//1 2654//1 2606//1 +f 2606//1 2654//1 2607//1 +f 2654//1 2655//1 2607//1 +f 2607//1 2655//1 7//1 +f 2655//1 6//1 7//1 +f 103//1 2656//1 2608//1 +f 2656//1 2657//1 2608//1 +f 2608//1 2657//1 2609//1 +f 2657//1 2658//1 2609//1 +f 2609//1 2658//1 2610//1 +f 2658//1 2659//1 2610//1 +f 2610//1 2659//1 2611//1 +f 2659//1 2660//1 2611//1 +f 2611//1 2660//1 2612//1 +f 2660//1 2661//1 2612//1 +f 2612//1 2661//1 2613//1 +f 2661//1 2662//1 2613//1 +f 2613//1 2662//1 2614//1 +f 2662//1 2663//1 2614//1 +f 2614//1 2663//1 2615//1 +f 2663//1 2664//1 2615//1 +f 2615//1 2664//1 2616//1 +f 2664//1 2665//1 2616//1 +f 2616//1 2665//1 2617//1 +f 2665//1 2666//1 2617//1 +f 2617//1 2666//1 2618//1 +f 2666//1 2667//1 2618//1 +f 2618//1 2667//1 2619//1 +f 2667//1 2668//1 2619//1 +f 2619//1 2668//1 2620//1 +f 2668//1 2669//1 2620//1 +f 2620//1 2669//1 2621//1 +f 2669//1 2670//1 2621//1 +f 2621//1 2670//1 2622//1 +f 2670//1 2671//1 2622//1 +f 2622//1 2671//1 2623//1 +f 2671//1 2672//1 2623//1 +f 2623//1 2672//1 2624//1 +f 2672//1 2673//1 2624//1 +f 2624//1 2673//1 2625//1 +f 2673//1 2674//1 2625//1 +f 2625//1 2674//1 2626//1 +f 2674//1 2675//1 2626//1 +f 2626//1 2675//1 2627//1 +f 2675//1 2676//1 2627//1 +f 2627//1 2676//1 2628//1 +f 2676//1 2677//1 2628//1 +f 2628//1 2677//1 2629//1 +f 2677//1 2678//1 2629//1 +f 2629//1 2678//1 2630//1 +f 2678//1 2679//1 2630//1 +f 2630//1 2679//1 2631//1 +f 2679//1 2680//1 2631//1 +f 2631//1 2680//1 2632//1 +f 2680//1 2681//1 2632//1 +f 2632//1 2681//1 2633//1 +f 2681//1 2682//1 2633//1 +f 2633//1 2682//1 2634//1 +f 2682//1 2683//1 2634//1 +f 2634//1 2683//1 2635//1 +f 2683//1 2684//1 2635//1 +f 2635//1 2684//1 2636//1 +f 2684//1 2685//1 2636//1 +f 2636//1 2685//1 2637//1 +f 2685//1 2686//1 2637//1 +f 2637//1 2686//1 2638//1 +f 2686//1 2687//1 2638//1 +f 2638//1 2687//1 2639//1 +f 2687//1 2688//1 2639//1 +f 2639//1 2688//1 2640//1 +f 2688//1 2689//1 2640//1 +f 2640//1 2689//1 2641//1 +f 2689//1 2690//1 2641//1 +f 2641//1 2690//1 2642//1 +f 2690//1 2691//1 2642//1 +f 2642//1 2691//1 2643//1 +f 2691//1 2692//1 2643//1 +f 2643//1 2692//1 2644//1 +f 2692//1 2693//1 2644//1 +f 2644//1 2693//1 2645//1 +f 2693//1 2694//1 2645//1 +f 2645//1 2694//1 2646//1 +f 2694//1 2695//1 2646//1 +f 2646//1 2695//1 2647//1 +f 2695//1 2696//1 2647//1 +f 2647//1 2696//1 2648//1 +f 2696//1 2697//1 2648//1 +f 2648//1 2697//1 2649//1 +f 2697//1 2698//1 2649//1 +f 2649//1 2698//1 2650//1 +f 2698//1 2699//1 2650//1 +f 2650//1 2699//1 2651//1 +f 2699//1 2700//1 2651//1 +f 2651//1 2700//1 2652//1 +f 2700//1 2701//1 2652//1 +f 2652//1 2701//1 2653//1 +f 2701//1 2702//1 2653//1 +f 2653//1 2702//1 2654//1 +f 2702//1 2703//1 2654//1 +f 2654//1 2703//1 2655//1 +f 2703//1 2704//1 2655//1 +f 2655//1 2704//1 6//1 +f 2704//1 5//1 6//1 +f 104//1 254//1 2656//1 +f 254//1 253//1 2656//1 +f 2656//1 253//1 2657//1 +f 253//1 252//1 2657//1 +f 2657//1 252//1 2658//1 +f 252//1 251//1 2658//1 +f 2658//1 251//1 2659//1 +f 251//1 250//1 2659//1 +f 2659//1 250//1 2660//1 +f 250//1 249//1 2660//1 +f 2660//1 249//1 2661//1 +f 249//1 248//1 2661//1 +f 2661//1 248//1 2662//1 +f 248//1 247//1 2662//1 +f 2662//1 247//1 2663//1 +f 247//1 246//1 2663//1 +f 2663//1 246//1 2664//1 +f 246//1 245//1 2664//1 +f 2664//1 245//1 2665//1 +f 245//1 244//1 2665//1 +f 2665//1 244//1 2666//1 +f 244//1 243//1 2666//1 +f 2666//1 243//1 2667//1 +f 243//1 242//1 2667//1 +f 2667//1 242//1 2668//1 +f 242//1 241//1 2668//1 +f 2668//1 241//1 2669//1 +f 241//1 240//1 2669//1 +f 2669//1 240//1 2670//1 +f 240//1 239//1 2670//1 +f 2670//1 239//1 2671//1 +f 239//1 238//1 2671//1 +f 2671//1 238//1 2672//1 +f 238//1 237//1 2672//1 +f 2672//1 237//1 2673//1 +f 237//1 236//1 2673//1 +f 2673//1 236//1 2674//1 +f 236//1 235//1 2674//1 +f 2674//1 235//1 2675//1 +f 235//1 234//1 2675//1 +f 2675//1 234//1 2676//1 +f 234//1 233//1 2676//1 +f 2676//1 233//1 2677//1 +f 233//1 232//1 2677//1 +f 2677//1 232//1 2678//1 +f 232//1 231//1 2678//1 +f 2678//1 231//1 2679//1 +f 231//1 230//1 2679//1 +f 2679//1 230//1 2680//1 +f 230//1 229//1 2680//1 +f 2680//1 229//1 2681//1 +f 229//1 228//1 2681//1 +f 2681//1 228//1 2682//1 +f 228//1 227//1 2682//1 +f 2682//1 227//1 2683//1 +f 227//1 226//1 2683//1 +f 2683//1 226//1 2684//1 +f 226//1 225//1 2684//1 +f 2684//1 225//1 2685//1 +f 225//1 224//1 2685//1 +f 2685//1 224//1 2686//1 +f 224//1 223//1 2686//1 +f 2686//1 223//1 2687//1 +f 223//1 222//1 2687//1 +f 2687//1 222//1 2688//1 +f 222//1 221//1 2688//1 +f 2688//1 221//1 2689//1 +f 221//1 220//1 2689//1 +f 2689//1 220//1 2690//1 +f 220//1 219//1 2690//1 +f 2690//1 219//1 2691//1 +f 219//1 218//1 2691//1 +f 2691//1 218//1 2692//1 +f 218//1 217//1 2692//1 +f 2692//1 217//1 2693//1 +f 217//1 216//1 2693//1 +f 2693//1 216//1 2694//1 +f 216//1 215//1 2694//1 +f 2694//1 215//1 2695//1 +f 215//1 214//1 2695//1 +f 2695//1 214//1 2696//1 +f 214//1 213//1 2696//1 +f 2696//1 213//1 2697//1 +f 213//1 212//1 2697//1 +f 2697//1 212//1 2698//1 +f 212//1 211//1 2698//1 +f 2698//1 211//1 2699//1 +f 211//1 210//1 2699//1 +f 2699//1 210//1 2700//1 +f 210//1 209//1 2700//1 +f 2700//1 209//1 2701//1 +f 209//1 208//1 2701//1 +f 2701//1 208//1 2702//1 +f 208//1 207//1 2702//1 +f 2702//1 207//1 2703//1 +f 207//1 206//1 2703//1 +f 2703//1 206//1 2704//1 +f 206//1 205//1 2704//1 +f 2704//1 205//1 5//1 +f 205//1 3//1 5//1 +o Torus +v 1.269537 0.006289 1.359776 +v 1.258843 0.006289 1.196618 +v 1.225636 0.131289 1.200990 +v 1.236043 0.131289 1.359776 +v 1.134912 0.222796 1.212934 +v 1.144537 0.222796 1.359776 +v 1.010982 0.256289 1.229250 +v 1.019537 0.256289 1.359776 +v 0.887051 0.222796 1.245565 +v 0.894537 0.222796 1.359776 +v 0.796328 0.131289 1.257509 +v 0.803031 0.131289 1.359776 +v 0.763121 0.006289 1.261881 +v 0.769537 0.006289 1.359776 +v 0.796328 -0.118711 1.257509 +v 0.803031 -0.118711 1.359776 +v 0.887051 -0.210217 1.245565 +v 0.894537 -0.210217 1.359776 +v 1.010982 -0.243711 1.229250 +v 1.019537 -0.243711 1.359776 +v 1.134912 -0.210217 1.212934 +v 1.144537 -0.210217 1.359776 +v 1.225636 -0.118711 1.200990 +v 1.236043 -0.118711 1.359776 +v 1.226944 0.006289 1.036252 +v 1.194592 0.131289 1.044921 +v 1.106204 0.222796 1.068604 +v 0.985463 0.256289 1.100957 +v 0.864722 0.222796 1.133309 +v 0.776334 0.131289 1.156993 +v 0.743981 0.006289 1.165661 +v 0.776334 -0.118711 1.156993 +v 0.864722 -0.210217 1.133309 +v 0.985463 -0.243711 1.100957 +v 1.106204 -0.210217 1.068604 +v 1.194592 -0.118711 1.044921 +v 1.174387 0.006289 0.881421 +v 1.143442 0.131289 0.894239 +v 1.058902 0.222796 0.929257 +v 0.943417 0.256289 0.977092 +v 0.827932 0.222796 1.024928 +v 0.743391 0.131289 1.059946 +v 0.712447 0.006289 1.072763 +v 0.743391 -0.118711 1.059946 +v 0.827932 -0.210217 1.024928 +v 0.943417 -0.243711 0.977092 +v 1.058902 -0.210217 0.929257 +v 1.143442 -0.118711 0.894239 +v 1.102069 0.006289 0.734776 +v 1.073062 0.131289 0.751522 +v 0.993815 0.222796 0.797276 +v 0.885562 0.256289 0.859776 +v 0.777309 0.222796 0.922276 +v 0.698062 0.131289 0.968029 +v 0.669056 0.006289 0.984776 +v 0.698062 -0.118711 0.968029 +v 0.777309 -0.210217 0.922276 +v 0.885562 -0.243711 0.859776 +v 0.993815 -0.210217 0.797276 +v 1.073062 -0.118711 0.751522 +v 1.011229 0.006289 0.598824 +v 0.984656 0.131289 0.619214 +v 0.912059 0.222796 0.674919 +v 0.812890 0.256289 0.751014 +v 0.713721 0.222796 0.827109 +v 0.641124 0.131289 0.882815 +v 0.614552 0.006289 0.903205 +v 0.641124 -0.118711 0.882815 +v 0.713721 -0.210217 0.827109 +v 0.812890 -0.243711 0.751014 +v 0.912059 -0.210217 0.674919 +v 0.984656 -0.118711 0.619214 +v 0.903420 0.006289 0.475892 +v 0.879737 0.131289 0.499576 +v 0.815032 0.222796 0.564281 +v 0.726644 0.256289 0.652669 +v 0.638255 0.222796 0.741057 +v 0.573551 0.131289 0.805762 +v 0.549867 0.006289 0.829446 +v 0.573551 -0.118711 0.805762 +v 0.638255 -0.210217 0.741057 +v 0.726644 -0.243711 0.652669 +v 0.815032 -0.210217 0.564281 +v 0.879737 -0.118711 0.499576 +v 0.780489 0.006289 0.368084 +v 0.760099 0.131289 0.394656 +v 0.704394 0.222796 0.467253 +v 0.628298 0.256289 0.566423 +v 0.552203 0.222796 0.665592 +v 0.496498 0.131289 0.738188 +v 0.476108 0.006289 0.764761 +v 0.496498 -0.118711 0.738188 +v 0.552203 -0.210217 0.665592 +v 0.628298 -0.243711 0.566423 +v 0.704394 -0.210217 0.467253 +v 0.760099 -0.118711 0.394656 +v 0.644537 0.006289 0.277244 +v 0.627790 0.131289 0.306250 +v 0.582037 0.222796 0.385497 +v 0.519537 0.256289 0.493750 +v 0.457037 0.222796 0.602003 +v 0.411284 0.131289 0.681250 +v 0.394537 0.006289 0.710257 +v 0.411284 -0.118711 0.681250 +v 0.457037 -0.210217 0.602003 +v 0.519537 -0.243711 0.493750 +v 0.582037 -0.210217 0.385497 +v 0.627790 -0.118711 0.306250 +v 0.497891 0.006289 0.204926 +v 0.485074 0.131289 0.235871 +v 0.450056 0.222796 0.320411 +v 0.402221 0.256289 0.435896 +v 0.354385 0.222796 0.551381 +v 0.319367 0.131289 0.635922 +v 0.306550 0.006289 0.666866 +v 0.319367 -0.118711 0.635922 +v 0.354385 -0.210217 0.551381 +v 0.402221 -0.243711 0.435896 +v 0.450056 -0.210217 0.320411 +v 0.485074 -0.118711 0.235871 +v 0.343061 0.006289 0.152368 +v 0.334392 0.131289 0.184721 +v 0.310708 0.222796 0.273109 +v 0.278356 0.256289 0.393850 +v 0.246004 0.222796 0.514591 +v 0.222320 0.131289 0.602979 +v 0.213651 0.006289 0.635331 +v 0.222320 -0.118711 0.602979 +v 0.246004 -0.210217 0.514591 +v 0.278356 -0.243711 0.393850 +v 0.310708 -0.210217 0.273109 +v 0.334392 -0.118711 0.184721 +v 0.182694 0.006289 0.120470 +v 0.178323 0.131289 0.153677 +v 0.166379 0.222796 0.244400 +v 0.150063 0.256289 0.368331 +v 0.133747 0.222796 0.492261 +v 0.121803 0.131289 0.582985 +v 0.117431 0.006289 0.616192 +v 0.121803 -0.118711 0.582985 +v 0.133747 -0.210217 0.492261 +v 0.150063 -0.243711 0.368331 +v 0.166379 -0.210217 0.244400 +v 0.178323 -0.118711 0.153677 +v 0.019537 0.006289 0.109776 +v 0.019537 0.131289 0.143269 +v 0.019537 0.222796 0.234776 +v 0.019537 0.256289 0.359776 +v 0.019537 0.222796 0.484776 +v 0.019537 0.131289 0.576282 +v 0.019537 0.006289 0.609776 +v 0.019537 -0.118711 0.576282 +v 0.019537 -0.210217 0.484776 +v 0.019537 -0.243711 0.359776 +v 0.019537 -0.210217 0.234776 +v 0.019537 -0.118711 0.143269 +v -0.143621 0.006289 0.120470 +v -0.139249 0.131289 0.153677 +v -0.127305 0.222796 0.244400 +v -0.110989 0.256289 0.368331 +v -0.094674 0.222796 0.492261 +v -0.082730 0.131289 0.582985 +v -0.078358 0.006289 0.616192 +v -0.082730 -0.118711 0.582985 +v -0.094674 -0.210217 0.492261 +v -0.110989 -0.243711 0.368331 +v -0.127305 -0.210217 0.244400 +v -0.139249 -0.118711 0.153677 +v -0.303987 0.006289 0.152368 +v -0.295318 0.131289 0.184721 +v -0.271634 0.222796 0.273109 +v -0.239282 0.256289 0.393850 +v -0.206930 0.222796 0.514590 +v -0.183246 0.131289 0.602979 +v -0.174577 0.006289 0.635331 +v -0.183246 -0.118711 0.602979 +v -0.206930 -0.210217 0.514590 +v -0.239282 -0.243711 0.393850 +v -0.271634 -0.210217 0.273109 +v -0.295318 -0.118711 0.184721 +v -0.458818 0.006289 0.204926 +v -0.446000 0.131289 0.235870 +v -0.410982 0.222796 0.320411 +v -0.363147 0.256289 0.435896 +v -0.315311 0.222796 0.551381 +v -0.280293 0.131289 0.635922 +v -0.267476 0.006289 0.666866 +v -0.280293 -0.118711 0.635922 +v -0.315311 -0.210217 0.551381 +v -0.363147 -0.243711 0.435896 +v -0.410982 -0.210217 0.320411 +v -0.446000 -0.118711 0.235870 +v -0.605463 0.006289 0.277244 +v -0.588716 0.131289 0.306250 +v -0.542963 0.222796 0.385497 +v -0.480463 0.256289 0.493750 +v -0.417963 0.222796 0.602003 +v -0.372210 0.131289 0.681250 +v -0.355463 0.006289 0.710257 +v -0.372210 -0.118711 0.681250 +v -0.417963 -0.210217 0.602003 +v -0.480463 -0.243711 0.493750 +v -0.542963 -0.210217 0.385497 +v -0.588716 -0.118711 0.306250 +v -0.741415 0.006289 0.368084 +v -0.721025 0.131289 0.394656 +v -0.665320 0.222796 0.467253 +v -0.589225 0.256289 0.566422 +v -0.513129 0.222796 0.665592 +v -0.457424 0.131289 0.738188 +v -0.437034 0.006289 0.764761 +v -0.457424 -0.118711 0.738188 +v -0.513129 -0.210217 0.665592 +v -0.589225 -0.243711 0.566422 +v -0.665320 -0.210217 0.467253 +v -0.721025 -0.118711 0.394656 +v -0.864347 0.006289 0.475893 +v -0.840663 0.131289 0.499576 +v -0.775958 0.222796 0.564281 +v -0.687570 0.256289 0.652669 +v -0.599182 0.222796 0.741057 +v -0.534477 0.131289 0.805762 +v -0.510793 0.006289 0.829446 +v -0.534477 -0.118711 0.805762 +v -0.599182 -0.210217 0.741057 +v -0.687570 -0.243711 0.652669 +v -0.775958 -0.210217 0.564281 +v -0.840663 -0.118711 0.499576 +v -0.972155 0.006289 0.598824 +v -0.945583 0.131289 0.619214 +v -0.872986 0.222796 0.674919 +v -0.773816 0.256289 0.751014 +v -0.674647 0.222796 0.827109 +v -0.602050 0.131289 0.882815 +v -0.575478 0.006289 0.903205 +v -0.602050 -0.118711 0.882815 +v -0.674647 -0.210217 0.827109 +v -0.773816 -0.243711 0.751014 +v -0.872986 -0.210217 0.674919 +v -0.945583 -0.118711 0.619214 +v -1.062995 0.006289 0.734775 +v -1.033988 0.131289 0.751522 +v -0.954742 0.222796 0.797275 +v -0.846488 0.256289 0.859775 +v -0.738235 0.222796 0.922275 +v -0.658988 0.131289 0.968029 +v -0.629982 0.006289 0.984775 +v -0.658988 -0.118711 0.968029 +v -0.738235 -0.210217 0.922275 +v -0.846488 -0.243711 0.859775 +v -0.954742 -0.210217 0.797275 +v -1.033988 -0.118711 0.751522 +v -1.135312 0.006289 0.881421 +v -1.104368 0.131289 0.894239 +v -1.019827 0.222796 0.929257 +v -0.904343 0.256289 0.977092 +v -0.788858 0.222796 1.024928 +v -0.704317 0.131289 1.059946 +v -0.673373 0.006289 1.072763 +v -0.704317 -0.118711 1.059946 +v -0.788858 -0.210217 1.024928 +v -0.904343 -0.243711 0.977092 +v -1.019827 -0.210217 0.929257 +v -1.104368 -0.118711 0.894239 +v -1.187871 0.006289 1.036252 +v -1.155518 0.131289 1.044921 +v -1.067130 0.222796 1.068604 +v -0.946389 0.256289 1.100957 +v -0.825648 0.222796 1.133309 +v -0.737260 0.131289 1.156993 +v -0.704908 0.006289 1.165662 +v -0.737260 -0.118711 1.156993 +v -0.825648 -0.210217 1.133309 +v -0.946389 -0.243711 1.100957 +v -1.067130 -0.210217 1.068604 +v -1.155518 -0.118711 1.044921 +v -1.219769 0.006289 1.196618 +v -1.186562 0.131289 1.200990 +v -1.095839 0.222796 1.212934 +v -0.971908 0.256289 1.229249 +v -0.847977 0.222796 1.245565 +v -0.757254 0.131289 1.257509 +v -0.724047 0.006289 1.261881 +v -0.757254 -0.118711 1.257509 +v -0.847977 -0.210217 1.245565 +v -0.971908 -0.243711 1.229249 +v -1.095839 -0.210217 1.212934 +v -1.186562 -0.118711 1.200990 +v -1.230463 0.006289 1.359776 +v -1.196970 0.131289 1.359776 +v -1.105463 0.222796 1.359776 +v -0.980463 0.256289 1.359776 +v -0.855463 0.222796 1.359776 +v -0.763957 0.131289 1.359776 +v -0.730463 0.006289 1.359776 +v -0.763957 -0.118711 1.359776 +v -0.855463 -0.210217 1.359776 +v -0.980463 -0.243711 1.359776 +v -1.105463 -0.210217 1.359776 +v -1.196970 -0.118711 1.359776 +v -1.219769 0.006289 1.522934 +v -1.186562 0.131289 1.518562 +v -1.095839 0.222796 1.506618 +v -0.971908 0.256289 1.490302 +v -0.847977 0.222796 1.473986 +v -0.757254 0.131289 1.462042 +v -0.724047 0.006289 1.457670 +v -0.757254 -0.118711 1.462042 +v -0.847977 -0.210217 1.473986 +v -0.971908 -0.243711 1.490302 +v -1.095839 -0.210217 1.506618 +v -1.186562 -0.118711 1.518562 +v -1.187871 0.006289 1.683299 +v -1.155518 0.131289 1.674631 +v -1.067130 0.222796 1.650947 +v -0.946389 0.256289 1.618595 +v -0.825648 0.222796 1.586242 +v -0.737260 0.131289 1.562559 +v -0.704908 0.006289 1.553890 +v -0.737260 -0.118711 1.562559 +v -0.825648 -0.210217 1.586242 +v -0.946389 -0.243711 1.618595 +v -1.067130 -0.210217 1.650947 +v -1.155518 -0.118711 1.674631 +v -1.135313 0.006289 1.838130 +v -1.104369 0.131289 1.825312 +v -1.019828 0.222796 1.790294 +v -0.904343 0.256289 1.742459 +v -0.788858 0.222796 1.694623 +v -0.704317 0.131289 1.659605 +v -0.673373 0.006289 1.646788 +v -0.704317 -0.118711 1.659605 +v -0.788858 -0.210217 1.694623 +v -0.904343 -0.243711 1.742459 +v -1.019828 -0.210217 1.790294 +v -1.104369 -0.118711 1.825312 +v -1.062995 0.006289 1.984776 +v -1.033989 0.131289 1.968029 +v -0.954742 0.222796 1.922276 +v -0.846489 0.256289 1.859776 +v -0.738235 0.222796 1.797276 +v -0.658989 0.131289 1.751522 +v -0.629982 0.006289 1.734776 +v -0.658989 -0.118711 1.751522 +v -0.738235 -0.210217 1.797276 +v -0.846489 -0.243711 1.859776 +v -0.954742 -0.210217 1.922276 +v -1.033989 -0.118711 1.968029 +v -0.972155 0.006289 2.120728 +v -0.945583 0.131289 2.100338 +v -0.872986 0.222796 2.044632 +v -0.773816 0.256289 1.968537 +v -0.674647 0.222796 1.892442 +v -0.602050 0.131289 1.836736 +v -0.575478 0.006289 1.816347 +v -0.602050 -0.118711 1.836736 +v -0.674647 -0.210217 1.892442 +v -0.773816 -0.243711 1.968537 +v -0.872986 -0.210217 2.044632 +v -0.945583 -0.118711 2.100338 +v -0.864347 0.006289 2.243659 +v -0.840663 0.131289 2.219975 +v -0.775958 0.222796 2.155271 +v -0.687570 0.256289 2.066882 +v -0.599182 0.222796 1.978494 +v -0.534477 0.131289 1.913789 +v -0.510793 0.006289 1.890106 +v -0.534477 -0.118711 1.913789 +v -0.599182 -0.210217 1.978494 +v -0.687570 -0.243711 2.066882 +v -0.775958 -0.210217 2.155271 +v -0.840663 -0.118711 2.219975 +v -0.741416 0.006289 2.351467 +v -0.721026 0.131289 2.324895 +v -0.665320 0.222796 2.252298 +v -0.589225 0.256289 2.153129 +v -0.513130 0.222796 2.053960 +v -0.457424 0.131289 1.981363 +v -0.437034 0.006289 1.954791 +v -0.457424 -0.118711 1.981363 +v -0.513130 -0.210217 2.053960 +v -0.589225 -0.243711 2.153129 +v -0.665320 -0.210217 2.252298 +v -0.721026 -0.118711 2.324895 +v -0.605463 0.006289 2.442308 +v -0.588716 0.131289 2.413301 +v -0.542963 0.222796 2.334054 +v -0.480463 0.256289 2.225801 +v -0.417963 0.222796 2.117548 +v -0.372210 0.131289 2.038301 +v -0.355463 0.006289 2.009295 +v -0.372210 -0.118711 2.038301 +v -0.417963 -0.210217 2.117548 +v -0.480463 -0.243711 2.225801 +v -0.542963 -0.210217 2.334054 +v -0.588716 -0.118711 2.413301 +v -0.458818 0.006289 2.514625 +v -0.446000 0.131289 2.483681 +v -0.410982 0.222796 2.399140 +v -0.363147 0.256289 2.283655 +v -0.315311 0.222796 2.168170 +v -0.280293 0.131289 2.083629 +v -0.267476 0.006289 2.052685 +v -0.280293 -0.118711 2.083629 +v -0.315311 -0.210217 2.168170 +v -0.363147 -0.243711 2.283655 +v -0.410982 -0.210217 2.399140 +v -0.446000 -0.118711 2.483681 +v -0.303987 0.006289 2.567183 +v -0.295318 0.131289 2.534830 +v -0.271635 0.222796 2.446442 +v -0.239282 0.256289 2.325701 +v -0.206930 0.222796 2.204961 +v -0.183246 0.131289 2.116572 +v -0.174578 0.006289 2.084220 +v -0.183246 -0.118711 2.116572 +v -0.206930 -0.210217 2.204961 +v -0.239282 -0.243711 2.325701 +v -0.271635 -0.210217 2.446442 +v -0.295318 -0.118711 2.534830 +v -0.143622 0.006289 2.599082 +v -0.139250 0.131289 2.565874 +v -0.127306 0.222796 2.475151 +v -0.110990 0.256289 2.351220 +v -0.094674 0.222796 2.227290 +v -0.082730 0.131289 2.136566 +v -0.078358 0.006289 2.103359 +v -0.082730 -0.118711 2.136566 +v -0.094674 -0.210217 2.227290 +v -0.110990 -0.243711 2.351220 +v -0.127306 -0.210217 2.475151 +v -0.139250 -0.118711 2.565874 +v 0.019537 0.006289 2.609776 +v 0.019537 0.131289 2.576282 +v 0.019537 0.222796 2.484776 +v 0.019537 0.256289 2.359776 +v 0.019537 0.222796 2.234776 +v 0.019537 0.131289 2.143269 +v 0.019537 0.006289 2.109776 +v 0.019537 -0.118711 2.143269 +v 0.019537 -0.210217 2.234776 +v 0.019537 -0.243711 2.359776 +v 0.019537 -0.210217 2.484776 +v 0.019537 -0.118711 2.576282 +v 0.182694 0.006289 2.599082 +v 0.178323 0.131289 2.565875 +v 0.166379 0.222796 2.475151 +v 0.150063 0.256289 2.351221 +v 0.133747 0.222796 2.227290 +v 0.121803 0.131289 2.136566 +v 0.117431 0.006289 2.103359 +v 0.121803 -0.118711 2.136566 +v 0.133747 -0.210217 2.227290 +v 0.150063 -0.243711 2.351221 +v 0.166379 -0.210217 2.475151 +v 0.178323 -0.118711 2.565875 +v 0.343060 0.006289 2.567183 +v 0.334391 0.131289 2.534831 +v 0.310708 0.222796 2.446442 +v 0.278356 0.256289 2.325702 +v 0.246003 0.222796 2.204961 +v 0.222320 0.131289 2.116573 +v 0.213651 0.006289 2.084220 +v 0.222320 -0.118711 2.116573 +v 0.246003 -0.210217 2.204961 +v 0.278356 -0.243711 2.325702 +v 0.310708 -0.210217 2.446442 +v 0.334391 -0.118711 2.534831 +v 0.497891 0.006289 2.514625 +v 0.485074 0.131289 2.483681 +v 0.450056 0.222796 2.399140 +v 0.402221 0.256289 2.283655 +v 0.354385 0.222796 2.168170 +v 0.319367 0.131289 2.083629 +v 0.306550 0.006289 2.052685 +v 0.319367 -0.118711 2.083629 +v 0.354385 -0.210217 2.168170 +v 0.402221 -0.243711 2.283655 +v 0.450056 -0.210217 2.399140 +v 0.485074 -0.118711 2.483681 +v 0.644537 0.006289 2.442307 +v 0.627790 0.131289 2.413301 +v 0.582037 0.222796 2.334054 +v 0.519537 0.256289 2.225801 +v 0.457037 0.222796 2.117548 +v 0.411284 0.131289 2.038301 +v 0.394537 0.006289 2.009295 +v 0.411284 -0.118711 2.038301 +v 0.457037 -0.210217 2.117548 +v 0.519537 -0.243711 2.225801 +v 0.582037 -0.210217 2.334054 +v 0.627790 -0.118711 2.413301 +v 0.780488 0.006289 2.351468 +v 0.760099 0.131289 2.324895 +v 0.704393 0.222796 2.252298 +v 0.628298 0.256289 2.153129 +v 0.552203 0.222796 2.053960 +v 0.496497 0.131289 1.981363 +v 0.476108 0.006289 1.954791 +v 0.496497 -0.118711 1.981363 +v 0.552203 -0.210217 2.053960 +v 0.628298 -0.243711 2.153129 +v 0.704393 -0.210217 2.252298 +v 0.760099 -0.118711 2.324895 +v 0.903420 0.006289 2.243660 +v 0.879736 0.131289 2.219976 +v 0.815032 0.222796 2.155271 +v 0.726643 0.256289 2.066883 +v 0.638255 0.222796 1.978495 +v 0.573550 0.131289 1.913790 +v 0.549867 0.006289 1.890106 +v 0.573550 -0.118711 1.913790 +v 0.638255 -0.210217 1.978495 +v 0.726643 -0.243711 2.066883 +v 0.815032 -0.210217 2.155271 +v 0.879736 -0.118711 2.219976 +v 1.011229 0.006289 2.120727 +v 0.984656 0.131289 2.100338 +v 0.912059 0.222796 2.044632 +v 0.812890 0.256289 1.968537 +v 0.713721 0.222796 1.892442 +v 0.641124 0.131289 1.836736 +v 0.614552 0.006289 1.816347 +v 0.641124 -0.118711 1.836736 +v 0.713721 -0.210217 1.892442 +v 0.812890 -0.243711 1.968537 +v 0.912059 -0.210217 2.044632 +v 0.984656 -0.118711 2.100338 +v 1.102069 0.006289 1.984776 +v 1.073062 0.131289 1.968029 +v 0.993815 0.222796 1.922276 +v 0.885562 0.256289 1.859776 +v 0.777309 0.222796 1.797276 +v 0.698062 0.131289 1.751523 +v 0.669056 0.006289 1.734776 +v 0.698062 -0.118711 1.751523 +v 0.777309 -0.210217 1.797276 +v 0.885562 -0.243711 1.859776 +v 0.993815 -0.210217 1.922276 +v 1.073062 -0.118711 1.968029 +v 1.174386 0.006289 1.838130 +v 1.143442 0.131289 1.825313 +v 1.058901 0.222796 1.790295 +v 0.943416 0.256289 1.742460 +v 0.827931 0.222796 1.694624 +v 0.743391 0.131289 1.659606 +v 0.712446 0.006289 1.646789 +v 0.743391 -0.118711 1.659606 +v 0.827931 -0.210217 1.694624 +v 0.943416 -0.243711 1.742460 +v 1.058901 -0.210217 1.790295 +v 1.143442 -0.118711 1.825313 +v 1.226944 0.006289 1.683299 +v 1.194592 0.131289 1.674630 +v 1.106204 0.222796 1.650947 +v 0.985463 0.256289 1.618594 +v 0.864722 0.222796 1.586242 +v 0.776334 0.131289 1.562559 +v 0.743981 0.006289 1.553890 +v 0.776334 -0.118711 1.562559 +v 0.864722 -0.210217 1.586242 +v 0.985463 -0.243711 1.618594 +v 1.106204 -0.210217 1.650947 +v 1.194592 -0.118711 1.674630 +v 1.258843 0.006289 1.522933 +v 1.225636 0.131289 1.518562 +v 1.134912 0.222796 1.506618 +v 1.010982 0.256289 1.490302 +v 0.887051 0.222796 1.473986 +v 0.796328 0.131289 1.462042 +v 0.763121 0.006289 1.457670 +v 0.796328 -0.118711 1.462042 +v 0.887051 -0.210217 1.473986 +v 1.010982 -0.243711 1.490302 +v 1.134912 -0.210217 1.506618 +v 1.225636 -0.118711 1.518562 +vn 0.9640 0.2583 -0.0632 +vn 0.7064 0.7063 -0.0463 +vn 0.2588 0.9658 -0.0170 +vn -0.2588 0.9658 0.0170 +vn -0.7064 0.7063 0.0463 +vn -0.9640 0.2583 0.0632 +vn -0.9640 -0.2583 0.0632 +vn -0.7063 -0.7063 0.0463 +vn -0.2588 -0.9658 0.0170 +vn 0.2588 -0.9658 -0.0170 +vn 0.7063 -0.7064 -0.0463 +vn 0.9640 -0.2583 -0.0632 +vn 0.9475 0.2583 -0.1885 +vn 0.6943 0.7063 -0.1381 +vn 0.2543 0.9658 -0.0506 +vn -0.2543 0.9658 0.0506 +vn -0.6943 0.7063 0.1381 +vn -0.9475 0.2583 0.1885 +vn -0.9475 -0.2583 0.1885 +vn -0.6943 -0.7063 0.1381 +vn -0.2544 -0.9658 0.0506 +vn 0.2544 -0.9658 -0.0506 +vn 0.6943 -0.7063 -0.1381 +vn 0.9475 -0.2583 -0.1885 +vn 0.9148 0.2583 -0.3105 +vn 0.6703 0.7063 -0.2275 +vn 0.2456 0.9658 -0.0834 +vn -0.2456 0.9658 0.0834 +vn -0.6703 0.7063 0.2275 +vn -0.9148 0.2583 0.3105 +vn -0.9148 -0.2583 0.3105 +vn -0.6703 -0.7064 0.2275 +vn -0.2456 -0.9658 0.0834 +vn 0.2456 -0.9658 -0.0834 +vn 0.6703 -0.7063 -0.2275 +vn 0.9148 -0.2583 -0.3105 +vn 0.8664 0.2583 -0.4273 +vn 0.6349 0.7063 -0.3131 +vn 0.2326 0.9658 -0.1147 +vn -0.2326 0.9658 0.1147 +vn -0.6349 0.7063 0.3131 +vn -0.8664 0.2583 0.4273 +vn -0.8664 -0.2583 0.4273 +vn -0.6349 -0.7064 0.3131 +vn -0.2326 -0.9658 0.1147 +vn 0.2326 -0.9658 -0.1147 +vn 0.6349 -0.7064 -0.3131 +vn 0.8664 -0.2583 -0.4273 +vn 0.8033 0.2583 -0.5367 +vn 0.5886 0.7063 -0.3933 +vn 0.2156 0.9658 -0.1441 +vn -0.2156 0.9658 0.1441 +vn -0.5886 0.7063 0.3933 +vn -0.8033 0.2583 0.5367 +vn -0.8033 -0.2583 0.5367 +vn -0.5886 -0.7064 0.3933 +vn -0.2156 -0.9658 0.1441 +vn 0.2156 -0.9658 -0.1441 +vn 0.5886 -0.7063 -0.3933 +vn 0.8033 -0.2583 -0.5367 +vn 0.7263 0.2583 -0.6370 +vn 0.5322 0.7063 -0.4667 +vn 0.1950 0.9658 -0.1710 +vn -0.1950 0.9658 0.1710 +vn -0.5322 0.7063 0.4667 +vn -0.7263 0.2583 0.6370 +vn -0.7263 -0.2583 0.6370 +vn -0.5322 -0.7064 0.4667 +vn -0.1950 -0.9658 0.1710 +vn 0.1950 -0.9658 -0.1710 +vn 0.5322 -0.7063 -0.4667 +vn 0.7263 -0.2583 -0.6370 +vn 0.6370 0.2583 -0.7263 +vn 0.4667 0.7063 -0.5322 +vn 0.1710 0.9658 -0.1950 +vn -0.1710 0.9658 0.1950 +vn -0.4667 0.7063 0.5322 +vn -0.6370 0.2583 0.7263 +vn -0.6370 -0.2583 0.7263 +vn -0.4667 -0.7063 0.5322 +vn -0.1710 -0.9658 0.1950 +vn 0.1710 -0.9658 -0.1950 +vn 0.4667 -0.7064 -0.5322 +vn 0.6370 -0.2583 -0.7263 +vn 0.5367 0.2583 -0.8033 +vn 0.3933 0.7063 -0.5886 +vn 0.1441 0.9658 -0.2156 +vn -0.1441 0.9658 0.2156 +vn -0.3933 0.7063 0.5886 +vn -0.5367 0.2583 0.8033 +vn -0.5367 -0.2583 0.8033 +vn -0.3933 -0.7063 0.5886 +vn -0.1441 -0.9658 0.2156 +vn 0.1441 -0.9658 -0.2156 +vn 0.3933 -0.7063 -0.5886 +vn 0.5367 -0.2583 -0.8033 +vn 0.4273 0.2583 -0.8664 +vn 0.3131 0.7063 -0.6349 +vn 0.1147 0.9658 -0.2326 +vn -0.1147 0.9658 0.2326 +vn -0.3131 0.7063 0.6349 +vn -0.4273 0.2583 0.8664 +vn -0.4273 -0.2583 0.8664 +vn -0.3131 -0.7064 0.6349 +vn -0.1147 -0.9658 0.2326 +vn 0.1147 -0.9658 -0.2326 +vn 0.3131 -0.7063 -0.6349 +vn 0.4273 -0.2583 -0.8664 +vn 0.3105 0.2583 -0.9148 +vn 0.2275 0.7063 -0.6703 +vn 0.0834 0.9658 -0.2456 +vn -0.0834 0.9658 0.2456 +vn -0.2275 0.7063 0.6703 +vn -0.3105 0.2583 0.9148 +vn -0.3105 -0.2583 0.9148 +vn -0.2275 -0.7064 0.6703 +vn -0.0834 -0.9658 0.2456 +vn 0.0834 -0.9658 -0.2456 +vn 0.2275 -0.7063 -0.6703 +vn 0.3105 -0.2583 -0.9148 +vn 0.1885 0.2583 -0.9475 +vn 0.1381 0.7063 -0.6943 +vn 0.0506 0.9658 -0.2543 +vn -0.0506 0.9658 0.2543 +vn -0.1381 0.7063 0.6943 +vn -0.1885 0.2583 0.9475 +vn -0.1885 -0.2583 0.9475 +vn -0.1381 -0.7064 0.6943 +vn -0.0506 -0.9658 0.2544 +vn 0.0506 -0.9658 -0.2544 +vn 0.1381 -0.7063 -0.6943 +vn 0.1885 -0.2583 -0.9475 +vn 0.0632 0.2583 -0.9640 +vn 0.0463 0.7063 -0.7064 +vn 0.0170 0.9658 -0.2588 +vn -0.0170 0.9658 0.2588 +vn -0.0463 0.7063 0.7064 +vn -0.0632 0.2583 0.9640 +vn -0.0632 -0.2583 0.9640 +vn -0.0463 -0.7064 0.7063 +vn -0.0170 -0.9658 0.2588 +vn 0.0170 -0.9658 -0.2588 +vn 0.0463 -0.7064 -0.7063 +vn 0.0632 -0.2583 -0.9640 +vn -0.0632 0.2583 -0.9640 +vn -0.0463 0.7063 -0.7064 +vn -0.0170 0.9658 -0.2588 +vn 0.0170 0.9658 0.2588 +vn 0.0463 0.7063 0.7064 +vn 0.0632 0.2583 0.9640 +vn 0.0632 -0.2583 0.9640 +vn 0.0463 -0.7064 0.7063 +vn 0.0170 -0.9658 0.2588 +vn -0.0170 -0.9658 -0.2588 +vn -0.0463 -0.7064 -0.7063 +vn -0.0632 -0.2583 -0.9640 +vn -0.1885 0.2583 -0.9475 +vn -0.1381 0.7063 -0.6943 +vn -0.0506 0.9658 -0.2543 +vn 0.0506 0.9658 0.2544 +vn 0.1381 0.7063 0.6943 +vn 0.1885 0.2583 0.9475 +vn 0.1885 -0.2583 0.9475 +vn 0.1381 -0.7064 0.6943 +vn 0.0506 -0.9658 0.2544 +vn -0.0506 -0.9658 -0.2544 +vn -0.1381 -0.7063 -0.6943 +vn -0.1885 -0.2583 -0.9475 +vn -0.3105 0.2583 -0.9148 +vn -0.2275 0.7063 -0.6703 +vn -0.0834 0.9658 -0.2456 +vn 0.0834 0.9658 0.2456 +vn 0.2275 0.7063 0.6703 +vn 0.3105 0.2583 0.9148 +vn 0.3105 -0.2583 0.9148 +vn 0.2275 -0.7064 0.6703 +vn 0.0834 -0.9658 0.2456 +vn -0.0834 -0.9658 -0.2456 +vn -0.2275 -0.7063 -0.6703 +vn -0.3105 -0.2583 -0.9148 +vn -0.4273 0.2583 -0.8664 +vn -0.3131 0.7063 -0.6349 +vn -0.1147 0.9658 -0.2326 +vn 0.1147 0.9658 0.2326 +vn 0.3131 0.7063 0.6349 +vn 0.4273 0.2583 0.8664 +vn 0.4273 -0.2583 0.8664 +vn 0.3131 -0.7064 0.6349 +vn 0.1147 -0.9658 0.2326 +vn -0.1147 -0.9658 -0.2326 +vn -0.3131 -0.7064 -0.6349 +vn -0.4273 -0.2583 -0.8664 +vn -0.5367 0.2583 -0.8033 +vn -0.3933 0.7063 -0.5886 +vn -0.1441 0.9658 -0.2156 +vn 0.1441 0.9658 0.2156 +vn 0.3933 0.7063 0.5886 +vn 0.5367 0.2583 0.8033 +vn 0.5367 -0.2583 0.8033 +vn 0.3933 -0.7063 0.5886 +vn 0.1441 -0.9658 0.2156 +vn -0.1441 -0.9658 -0.2156 +vn -0.3933 -0.7063 -0.5886 +vn -0.5367 -0.2583 -0.8033 +vn -0.6370 0.2583 -0.7263 +vn -0.4667 0.7063 -0.5322 +vn -0.1710 0.9658 -0.1950 +vn 0.1710 0.9658 0.1950 +vn 0.4667 0.7063 0.5322 +vn 0.6370 0.2583 0.7263 +vn 0.6370 -0.2583 0.7263 +vn 0.4667 -0.7063 0.5322 +vn 0.1710 -0.9658 0.1950 +vn -0.1710 -0.9658 -0.1950 +vn -0.4667 -0.7063 -0.5322 +vn -0.6370 -0.2583 -0.7263 +vn -0.7263 0.2583 -0.6370 +vn -0.5322 0.7063 -0.4667 +vn -0.1950 0.9658 -0.1710 +vn 0.1950 0.9658 0.1710 +vn 0.5322 0.7063 0.4667 +vn 0.7263 0.2583 0.6370 +vn 0.7263 -0.2583 0.6370 +vn 0.5322 -0.7064 0.4667 +vn 0.1950 -0.9658 0.1710 +vn -0.1950 -0.9658 -0.1710 +vn -0.5322 -0.7063 -0.4667 +vn -0.7263 -0.2583 -0.6370 +vn -0.8033 0.2583 -0.5367 +vn -0.5886 0.7063 -0.3933 +vn -0.2156 0.9658 -0.1441 +vn 0.2156 0.9658 0.1441 +vn 0.5886 0.7063 0.3933 +vn 0.8033 0.2583 0.5367 +vn 0.8033 -0.2583 0.5367 +vn 0.5886 -0.7064 0.3933 +vn 0.2156 -0.9658 0.1441 +vn -0.2156 -0.9658 -0.1441 +vn -0.5886 -0.7063 -0.3933 +vn -0.8033 -0.2583 -0.5367 +vn -0.8664 0.2583 -0.4273 +vn -0.6349 0.7063 -0.3131 +vn -0.2326 0.9658 -0.1147 +vn 0.2326 0.9658 0.1147 +vn 0.6349 0.7063 0.3131 +vn 0.8664 0.2583 0.4273 +vn 0.8664 -0.2583 0.4273 +vn 0.6349 -0.7064 0.3131 +vn 0.2326 -0.9658 0.1147 +vn -0.2326 -0.9658 -0.1147 +vn -0.6349 -0.7063 -0.3131 +vn -0.8664 -0.2583 -0.4273 +vn -0.9148 0.2583 -0.3105 +vn -0.6703 0.7063 -0.2275 +vn -0.2456 0.9658 -0.0834 +vn 0.2456 0.9658 0.0834 +vn 0.6703 0.7063 0.2275 +vn 0.9148 0.2583 0.3105 +vn 0.9148 -0.2583 0.3105 +vn 0.6703 -0.7064 0.2275 +vn 0.2456 -0.9658 0.0834 +vn -0.2456 -0.9658 -0.0834 +vn -0.6703 -0.7063 -0.2275 +vn -0.9148 -0.2583 -0.3105 +vn -0.9475 0.2583 -0.1885 +vn -0.6943 0.7063 -0.1381 +vn -0.2543 0.9658 -0.0506 +vn 0.2543 0.9658 0.0506 +vn 0.6943 0.7063 0.1381 +vn 0.9475 0.2583 0.1885 +vn 0.9475 -0.2583 0.1885 +vn 0.6943 -0.7063 0.1381 +vn 0.2544 -0.9658 0.0506 +vn -0.2544 -0.9658 -0.0506 +vn -0.6943 -0.7063 -0.1381 +vn -0.9475 -0.2583 -0.1885 +vn -0.9640 0.2583 -0.0632 +vn -0.7064 0.7063 -0.0463 +vn -0.2588 0.9658 -0.0170 +vn 0.2588 0.9658 0.0170 +vn 0.7064 0.7063 0.0463 +vn 0.9640 0.2583 0.0632 +vn 0.9640 -0.2583 0.0632 +vn 0.7063 -0.7063 0.0463 +vn 0.2588 -0.9658 0.0170 +vn -0.2588 -0.9658 -0.0170 +vn -0.7063 -0.7064 -0.0463 +vn -0.9640 -0.2583 -0.0632 +vn 0.7063 -0.7063 -0.0463 +vn -0.7063 -0.7064 0.0463 +vn 0.6349 -0.7063 -0.3131 +vn 0.5886 -0.7064 -0.3933 +vn 0.5322 -0.7064 -0.4667 +vn -0.4667 -0.7064 0.5322 +vn 0.3933 -0.7064 -0.5886 +vn -0.3933 -0.7064 0.5886 +vn 0.3131 -0.7064 -0.6349 +vn 0.2275 -0.7064 -0.6703 +vn -0.2275 -0.7063 0.6703 +vn 0.0506 0.9658 -0.2544 +vn 0.1381 -0.7064 -0.6943 +vn -0.1381 -0.7063 0.6943 +vn 0.0463 0.7063 -0.7063 +vn -0.0463 -0.7063 0.7063 +vn -0.0463 0.7063 -0.7063 +vn -0.3933 -0.7064 -0.5886 +vn 0.3933 -0.7064 0.5886 +vn -0.4667 -0.7064 -0.5322 +vn 0.4667 -0.7064 0.5322 +vn -0.5322 -0.7064 -0.4667 +vn -0.5886 -0.7064 -0.3933 +vn 0.6703 -0.7063 0.2275 +vn 0.2544 0.9658 0.0506 +vn 0.6943 -0.7064 0.1381 +vn -0.7063 -0.7063 -0.0463 +vn 0.7063 -0.7064 0.0463 +usemtl None +s 1 +f 2705//2 2706//2 2707//2 2708//2 +f 2708//3 2707//3 2709//3 2710//3 +f 2710//4 2709//4 2711//4 2712//4 +f 2712//5 2711//5 2713//5 2714//5 +f 2714//6 2713//6 2715//6 2716//6 +f 2716//7 2715//7 2717//7 2718//7 +f 2718//8 2717//8 2719//8 2720//8 +f 2720//9 2719//9 2721//9 2722//9 +f 2722//10 2721//10 2723//10 2724//10 +f 2724//11 2723//11 2725//11 2726//11 +f 2726//12 2725//12 2727//12 2728//12 +f 2705//13 2728//13 2727//13 2706//13 +f 2706//14 2729//14 2730//14 2707//14 +f 2707//15 2730//15 2731//15 2709//15 +f 2709//16 2731//16 2732//16 2711//16 +f 2711//17 2732//17 2733//17 2713//17 +f 2713//18 2733//18 2734//18 2715//18 +f 2715//19 2734//19 2735//19 2717//19 +f 2717//20 2735//20 2736//20 2719//20 +f 2719//21 2736//21 2737//21 2721//21 +f 2721//22 2737//22 2738//22 2723//22 +f 2723//23 2738//23 2739//23 2725//23 +f 2725//24 2739//24 2740//24 2727//24 +f 2727//25 2740//25 2729//25 2706//25 +f 2729//26 2741//26 2742//26 2730//26 +f 2730//27 2742//27 2743//27 2731//27 +f 2731//28 2743//28 2744//28 2732//28 +f 2732//29 2744//29 2745//29 2733//29 +f 2733//30 2745//30 2746//30 2734//30 +f 2734//31 2746//31 2747//31 2735//31 +f 2735//32 2747//32 2748//32 2736//32 +f 2736//33 2748//33 2749//33 2737//33 +f 2737//34 2749//34 2750//34 2738//34 +f 2738//35 2750//35 2751//35 2739//35 +f 2739//36 2751//36 2752//36 2740//36 +f 2740//37 2752//37 2741//37 2729//37 +f 2741//38 2753//38 2754//38 2742//38 +f 2742//39 2754//39 2755//39 2743//39 +f 2743//40 2755//40 2756//40 2744//40 +f 2744//41 2756//41 2757//41 2745//41 +f 2745//42 2757//42 2758//42 2746//42 +f 2746//43 2758//43 2759//43 2747//43 +f 2747//44 2759//44 2760//44 2748//44 +f 2748//45 2760//45 2761//45 2749//45 +f 2749//46 2761//46 2762//46 2750//46 +f 2750//47 2762//47 2763//47 2751//47 +f 2751//48 2763//48 2764//48 2752//48 +f 2752//49 2764//49 2753//49 2741//49 +f 2753//50 2765//50 2766//50 2754//50 +f 2754//51 2766//51 2767//51 2755//51 +f 2755//52 2767//52 2768//52 2756//52 +f 2756//53 2768//53 2769//53 2757//53 +f 2757//54 2769//54 2770//54 2758//54 +f 2758//55 2770//55 2771//55 2759//55 +f 2759//56 2771//56 2772//56 2760//56 +f 2760//57 2772//57 2773//57 2761//57 +f 2761//58 2773//58 2774//58 2762//58 +f 2762//59 2774//59 2775//59 2763//59 +f 2763//60 2775//60 2776//60 2764//60 +f 2764//61 2776//61 2765//61 2753//61 +f 2765//62 2777//62 2778//62 2766//62 +f 2766//63 2778//63 2779//63 2767//63 +f 2767//64 2779//64 2780//64 2768//64 +f 2768//65 2780//65 2781//65 2769//65 +f 2769//66 2781//66 2782//66 2770//66 +f 2770//67 2782//67 2783//67 2771//67 +f 2771//68 2783//68 2784//68 2772//68 +f 2772//69 2784//69 2785//69 2773//69 +f 2773//70 2785//70 2786//70 2774//70 +f 2774//71 2786//71 2787//71 2775//71 +f 2775//72 2787//72 2788//72 2776//72 +f 2776//73 2788//73 2777//73 2765//73 +f 2777//74 2789//74 2790//74 2778//74 +f 2778//75 2790//75 2791//75 2779//75 +f 2779//76 2791//76 2792//76 2780//76 +f 2780//77 2792//77 2793//77 2781//77 +f 2781//78 2793//78 2794//78 2782//78 +f 2782//79 2794//79 2795//79 2783//79 +f 2783//80 2795//80 2796//80 2784//80 +f 2784//81 2796//81 2797//81 2785//81 +f 2785//82 2797//82 2798//82 2786//82 +f 2786//83 2798//83 2799//83 2787//83 +f 2787//84 2799//84 2800//84 2788//84 +f 2788//85 2800//85 2789//85 2777//85 +f 2789//86 2801//86 2802//86 2790//86 +f 2790//87 2802//87 2803//87 2791//87 +f 2791//88 2803//88 2804//88 2792//88 +f 2792//89 2804//89 2805//89 2793//89 +f 2793//90 2805//90 2806//90 2794//90 +f 2794//91 2806//91 2807//91 2795//91 +f 2795//92 2807//92 2808//92 2796//92 +f 2796//93 2808//93 2809//93 2797//93 +f 2797//94 2809//94 2810//94 2798//94 +f 2798//95 2810//95 2811//95 2799//95 +f 2799//96 2811//96 2812//96 2800//96 +f 2800//97 2812//97 2801//97 2789//97 +f 2801//98 2813//98 2814//98 2802//98 +f 2802//99 2814//99 2815//99 2803//99 +f 2803//100 2815//100 2816//100 2804//100 +f 2804//101 2816//101 2817//101 2805//101 +f 2805//102 2817//102 2818//102 2806//102 +f 2806//103 2818//103 2819//103 2807//103 +f 2807//104 2819//104 2820//104 2808//104 +f 2808//105 2820//105 2821//105 2809//105 +f 2809//106 2821//106 2822//106 2810//106 +f 2810//107 2822//107 2823//107 2811//107 +f 2811//108 2823//108 2824//108 2812//108 +f 2812//109 2824//109 2813//109 2801//109 +f 2813//110 2825//110 2826//110 2814//110 +f 2814//111 2826//111 2827//111 2815//111 +f 2815//112 2827//112 2828//112 2816//112 +f 2816//113 2828//113 2829//113 2817//113 +f 2817//114 2829//114 2830//114 2818//114 +f 2818//115 2830//115 2831//115 2819//115 +f 2819//116 2831//116 2832//116 2820//116 +f 2820//117 2832//117 2833//117 2821//117 +f 2821//118 2833//118 2834//118 2822//118 +f 2822//119 2834//119 2835//119 2823//119 +f 2823//120 2835//120 2836//120 2824//120 +f 2824//121 2836//121 2825//121 2813//121 +f 2825//122 2837//122 2838//122 2826//122 +f 2826//123 2838//123 2839//123 2827//123 +f 2827//124 2839//124 2840//124 2828//124 +f 2828//125 2840//125 2841//125 2829//125 +f 2829//126 2841//126 2842//126 2830//126 +f 2830//127 2842//127 2843//127 2831//127 +f 2831//128 2843//128 2844//128 2832//128 +f 2832//129 2844//129 2845//129 2833//129 +f 2833//130 2845//130 2846//130 2834//130 +f 2834//131 2846//131 2847//131 2835//131 +f 2835//132 2847//132 2848//132 2836//132 +f 2836//133 2848//133 2837//133 2825//133 +f 2837//134 2849//134 2850//134 2838//134 +f 2838//135 2850//135 2851//135 2839//135 +f 2839//136 2851//136 2852//136 2840//136 +f 2840//137 2852//137 2853//137 2841//137 +f 2841//138 2853//138 2854//138 2842//138 +f 2842//139 2854//139 2855//139 2843//139 +f 2843//140 2855//140 2856//140 2844//140 +f 2844//141 2856//141 2857//141 2845//141 +f 2845//142 2857//142 2858//142 2846//142 +f 2846//143 2858//143 2859//143 2847//143 +f 2847//144 2859//144 2860//144 2848//144 +f 2848//145 2860//145 2849//145 2837//145 +f 2849//146 2861//146 2862//146 2850//146 +f 2850//147 2862//147 2863//147 2851//147 +f 2851//148 2863//148 2864//148 2852//148 +f 2852//149 2864//149 2865//149 2853//149 +f 2853//150 2865//150 2866//150 2854//150 +f 2854//151 2866//151 2867//151 2855//151 +f 2855//152 2867//152 2868//152 2856//152 +f 2856//153 2868//153 2869//153 2857//153 +f 2857//154 2869//154 2870//154 2858//154 +f 2858//155 2870//155 2871//155 2859//155 +f 2859//156 2871//156 2872//156 2860//156 +f 2860//157 2872//157 2861//157 2849//157 +f 2861//158 2873//158 2874//158 2862//158 +f 2862//159 2874//159 2875//159 2863//159 +f 2863//160 2875//160 2876//160 2864//160 +f 2864//161 2876//161 2877//161 2865//161 +f 2865//162 2877//162 2878//162 2866//162 +f 2866//163 2878//163 2879//163 2867//163 +f 2867//164 2879//164 2880//164 2868//164 +f 2868//165 2880//165 2881//165 2869//165 +f 2869//166 2881//166 2882//166 2870//166 +f 2870//167 2882//167 2883//167 2871//167 +f 2871//168 2883//168 2884//168 2872//168 +f 2872//169 2884//169 2873//169 2861//169 +f 2873//170 2885//170 2886//170 2874//170 +f 2874//171 2886//171 2887//171 2875//171 +f 2875//172 2887//172 2888//172 2876//172 +f 2876//173 2888//173 2889//173 2877//173 +f 2877//174 2889//174 2890//174 2878//174 +f 2878//175 2890//175 2891//175 2879//175 +f 2879//176 2891//176 2892//176 2880//176 +f 2880//177 2892//177 2893//177 2881//177 +f 2881//178 2893//178 2894//178 2882//178 +f 2882//179 2894//179 2895//179 2883//179 +f 2883//180 2895//180 2896//180 2884//180 +f 2884//181 2896//181 2885//181 2873//181 +f 2885//182 2897//182 2898//182 2886//182 +f 2886//183 2898//183 2899//183 2887//183 +f 2887//184 2899//184 2900//184 2888//184 +f 2888//185 2900//185 2901//185 2889//185 +f 2889//186 2901//186 2902//186 2890//186 +f 2890//187 2902//187 2903//187 2891//187 +f 2891//188 2903//188 2904//188 2892//188 +f 2892//189 2904//189 2905//189 2893//189 +f 2893//190 2905//190 2906//190 2894//190 +f 2894//191 2906//191 2907//191 2895//191 +f 2895//192 2907//192 2908//192 2896//192 +f 2896//193 2908//193 2897//193 2885//193 +f 2897//194 2909//194 2910//194 2898//194 +f 2898//195 2910//195 2911//195 2899//195 +f 2899//196 2911//196 2912//196 2900//196 +f 2900//197 2912//197 2913//197 2901//197 +f 2901//198 2913//198 2914//198 2902//198 +f 2902//199 2914//199 2915//199 2903//199 +f 2903//200 2915//200 2916//200 2904//200 +f 2904//201 2916//201 2917//201 2905//201 +f 2905//202 2917//202 2918//202 2906//202 +f 2906//203 2918//203 2919//203 2907//203 +f 2907//204 2919//204 2920//204 2908//204 +f 2908//205 2920//205 2909//205 2897//205 +f 2909//206 2921//206 2922//206 2910//206 +f 2910//207 2922//207 2923//207 2911//207 +f 2911//208 2923//208 2924//208 2912//208 +f 2912//209 2924//209 2925//209 2913//209 +f 2913//210 2925//210 2926//210 2914//210 +f 2914//211 2926//211 2927//211 2915//211 +f 2915//212 2927//212 2928//212 2916//212 +f 2916//213 2928//213 2929//213 2917//213 +f 2917//214 2929//214 2930//214 2918//214 +f 2918//215 2930//215 2931//215 2919//215 +f 2919//216 2931//216 2932//216 2920//216 +f 2920//217 2932//217 2921//217 2909//217 +f 2921//218 2933//218 2934//218 2922//218 +f 2922//219 2934//219 2935//219 2923//219 +f 2923//220 2935//220 2936//220 2924//220 +f 2924//221 2936//221 2937//221 2925//221 +f 2925//222 2937//222 2938//222 2926//222 +f 2926//223 2938//223 2939//223 2927//223 +f 2927//224 2939//224 2940//224 2928//224 +f 2928//225 2940//225 2941//225 2929//225 +f 2929//226 2941//226 2942//226 2930//226 +f 2930//227 2942//227 2943//227 2931//227 +f 2931//228 2943//228 2944//228 2932//228 +f 2932//229 2944//229 2933//229 2921//229 +f 2933//230 2945//230 2946//230 2934//230 +f 2934//231 2946//231 2947//231 2935//231 +f 2935//232 2947//232 2948//232 2936//232 +f 2936//233 2948//233 2949//233 2937//233 +f 2937//234 2949//234 2950//234 2938//234 +f 2938//235 2950//235 2951//235 2939//235 +f 2939//236 2951//236 2952//236 2940//236 +f 2940//237 2952//237 2953//237 2941//237 +f 2941//238 2953//238 2954//238 2942//238 +f 2942//239 2954//239 2955//239 2943//239 +f 2943//240 2955//240 2956//240 2944//240 +f 2944//241 2956//241 2945//241 2933//241 +f 2945//242 2957//242 2958//242 2946//242 +f 2946//243 2958//243 2959//243 2947//243 +f 2947//244 2959//244 2960//244 2948//244 +f 2948//245 2960//245 2961//245 2949//245 +f 2949//246 2961//246 2962//246 2950//246 +f 2950//247 2962//247 2963//247 2951//247 +f 2951//248 2963//248 2964//248 2952//248 +f 2952//249 2964//249 2965//249 2953//249 +f 2953//250 2965//250 2966//250 2954//250 +f 2954//251 2966//251 2967//251 2955//251 +f 2955//252 2967//252 2968//252 2956//252 +f 2956//253 2968//253 2957//253 2945//253 +f 2957//254 2969//254 2970//254 2958//254 +f 2958//255 2970//255 2971//255 2959//255 +f 2959//256 2971//256 2972//256 2960//256 +f 2960//257 2972//257 2973//257 2961//257 +f 2961//258 2973//258 2974//258 2962//258 +f 2962//259 2974//259 2975//259 2963//259 +f 2963//260 2975//260 2976//260 2964//260 +f 2964//261 2976//261 2977//261 2965//261 +f 2965//262 2977//262 2978//262 2966//262 +f 2966//263 2978//263 2979//263 2967//263 +f 2967//264 2979//264 2980//264 2968//264 +f 2968//265 2980//265 2969//265 2957//265 +f 2969//266 2981//266 2982//266 2970//266 +f 2970//267 2982//267 2983//267 2971//267 +f 2971//268 2983//268 2984//268 2972//268 +f 2972//269 2984//269 2985//269 2973//269 +f 2973//270 2985//270 2986//270 2974//270 +f 2974//271 2986//271 2987//271 2975//271 +f 2975//272 2987//272 2988//272 2976//272 +f 2976//273 2988//273 2989//273 2977//273 +f 2977//274 2989//274 2990//274 2978//274 +f 2978//275 2990//275 2991//275 2979//275 +f 2979//276 2991//276 2992//276 2980//276 +f 2980//277 2992//277 2981//277 2969//277 +f 2981//278 2993//278 2994//278 2982//278 +f 2982//279 2994//279 2995//279 2983//279 +f 2983//280 2995//280 2996//280 2984//280 +f 2984//281 2996//281 2997//281 2985//281 +f 2985//282 2997//282 2998//282 2986//282 +f 2986//283 2998//283 2999//283 2987//283 +f 2987//284 2999//284 3000//284 2988//284 +f 2988//285 3000//285 3001//285 2989//285 +f 2989//286 3001//286 3002//286 2990//286 +f 2990//287 3002//287 3003//287 2991//287 +f 2991//288 3003//288 3004//288 2992//288 +f 2992//289 3004//289 2993//289 2981//289 +f 2993//7 3005//7 3006//7 2994//7 +f 2994//6 3006//6 3007//6 2995//6 +f 2995//5 3007//5 3008//5 2996//5 +f 2996//4 3008//4 3009//4 2997//4 +f 2997//3 3009//3 3010//3 2998//3 +f 2998//2 3010//2 3011//2 2999//2 +f 2999//13 3011//13 3012//13 3000//13 +f 3000//290 3012//290 3013//290 3001//290 +f 3001//11 3013//11 3014//11 3002//11 +f 3002//10 3014//10 3015//10 3003//10 +f 3003//291 3015//291 3016//291 3004//291 +f 3004//8 3016//8 3005//8 2993//8 +f 3005//19 3017//19 3018//19 3006//19 +f 3006//18 3018//18 3019//18 3007//18 +f 3007//17 3019//17 3020//17 3008//17 +f 3008//16 3020//16 3021//16 3009//16 +f 3009//15 3021//15 3022//15 3010//15 +f 3010//14 3022//14 3023//14 3011//14 +f 3011//25 3023//25 3024//25 3012//25 +f 3012//24 3024//24 3025//24 3013//24 +f 3013//23 3025//23 3026//23 3014//23 +f 3014//22 3026//22 3027//22 3015//22 +f 3015//21 3027//21 3028//21 3016//21 +f 3016//20 3028//20 3017//20 3005//20 +f 3017//31 3029//31 3030//31 3018//31 +f 3018//30 3030//30 3031//30 3019//30 +f 3019//29 3031//29 3032//29 3020//29 +f 3020//28 3032//28 3033//28 3021//28 +f 3021//27 3033//27 3034//27 3022//27 +f 3022//26 3034//26 3035//26 3023//26 +f 3023//37 3035//37 3036//37 3024//37 +f 3024//36 3036//36 3037//36 3025//36 +f 3025//35 3037//35 3038//35 3026//35 +f 3026//34 3038//34 3039//34 3027//34 +f 3027//33 3039//33 3040//33 3028//33 +f 3028//32 3040//32 3029//32 3017//32 +f 3029//43 3041//43 3042//43 3030//43 +f 3030//42 3042//42 3043//42 3031//42 +f 3031//41 3043//41 3044//41 3032//41 +f 3032//40 3044//40 3045//40 3033//40 +f 3033//39 3045//39 3046//39 3034//39 +f 3034//38 3046//38 3047//38 3035//38 +f 3035//49 3047//49 3048//49 3036//49 +f 3036//292 3048//292 3049//292 3037//292 +f 3037//47 3049//47 3050//47 3038//47 +f 3038//46 3050//46 3051//46 3039//46 +f 3039//45 3051//45 3052//45 3040//45 +f 3040//44 3052//44 3041//44 3029//44 +f 3041//55 3053//55 3054//55 3042//55 +f 3042//54 3054//54 3055//54 3043//54 +f 3043//53 3055//53 3056//53 3044//53 +f 3044//52 3056//52 3057//52 3045//52 +f 3045//51 3057//51 3058//51 3046//51 +f 3046//50 3058//50 3059//50 3047//50 +f 3047//61 3059//61 3060//61 3048//61 +f 3048//293 3060//293 3061//293 3049//293 +f 3049//59 3061//59 3062//59 3050//59 +f 3050//58 3062//58 3063//58 3051//58 +f 3051//57 3063//57 3064//57 3052//57 +f 3052//56 3064//56 3053//56 3041//56 +f 3053//67 3065//67 3066//67 3054//67 +f 3054//66 3066//66 3067//66 3055//66 +f 3055//65 3067//65 3068//65 3056//65 +f 3056//64 3068//64 3069//64 3057//64 +f 3057//63 3069//63 3070//63 3058//63 +f 3058//62 3070//62 3071//62 3059//62 +f 3059//73 3071//73 3072//73 3060//73 +f 3060//294 3072//294 3073//294 3061//294 +f 3061//71 3073//71 3074//71 3062//71 +f 3062//70 3074//70 3075//70 3063//70 +f 3063//69 3075//69 3076//69 3064//69 +f 3064//68 3076//68 3065//68 3053//68 +f 3065//79 3077//79 3078//79 3066//79 +f 3066//78 3078//78 3079//78 3067//78 +f 3067//77 3079//77 3080//77 3068//77 +f 3068//76 3080//76 3081//76 3069//76 +f 3069//75 3081//75 3082//75 3070//75 +f 3070//74 3082//74 3083//74 3071//74 +f 3071//85 3083//85 3084//85 3072//85 +f 3072//84 3084//84 3085//84 3073//84 +f 3073//83 3085//83 3086//83 3074//83 +f 3074//82 3086//82 3087//82 3075//82 +f 3075//295 3087//295 3088//295 3076//295 +f 3076//80 3088//80 3077//80 3065//80 +f 3077//91 3089//91 3090//91 3078//91 +f 3078//90 3090//90 3091//90 3079//90 +f 3079//89 3091//89 3092//89 3080//89 +f 3080//88 3092//88 3093//88 3081//88 +f 3081//87 3093//87 3094//87 3082//87 +f 3082//86 3094//86 3095//86 3083//86 +f 3083//97 3095//97 3096//97 3084//97 +f 3084//296 3096//296 3097//296 3085//296 +f 3085//95 3097//95 3098//95 3086//95 +f 3086//94 3098//94 3099//94 3087//94 +f 3087//297 3099//297 3100//297 3088//297 +f 3088//92 3100//92 3089//92 3077//92 +f 3089//103 3101//103 3102//103 3090//103 +f 3090//102 3102//102 3103//102 3091//102 +f 3091//101 3103//101 3104//101 3092//101 +f 3092//100 3104//100 3105//100 3093//100 +f 3093//99 3105//99 3106//99 3094//99 +f 3094//98 3106//98 3107//98 3095//98 +f 3095//109 3107//109 3108//109 3096//109 +f 3096//298 3108//298 3109//298 3097//298 +f 3097//107 3109//107 3110//107 3098//107 +f 3098//106 3110//106 3111//106 3099//106 +f 3099//105 3111//105 3112//105 3100//105 +f 3100//104 3112//104 3101//104 3089//104 +f 3101//115 3113//115 3114//115 3102//115 +f 3102//114 3114//114 3115//114 3103//114 +f 3103//113 3115//113 3116//113 3104//113 +f 3104//112 3116//112 3117//112 3105//112 +f 3105//111 3117//111 3118//111 3106//111 +f 3106//110 3118//110 3119//110 3107//110 +f 3107//121 3119//121 3120//121 3108//121 +f 3108//299 3120//299 3121//299 3109//299 +f 3109//119 3121//119 3122//119 3110//119 +f 3110//118 3122//118 3123//118 3111//118 +f 3111//300 3123//300 3124//300 3112//300 +f 3112//116 3124//116 3113//116 3101//116 +f 3113//127 3125//127 3126//127 3114//127 +f 3114//126 3126//126 3127//126 3115//126 +f 3115//125 3127//125 3128//125 3116//125 +f 3116//301 3128//301 3129//301 3117//301 +f 3117//123 3129//123 3130//123 3118//123 +f 3118//122 3130//122 3131//122 3119//122 +f 3119//133 3131//133 3132//133 3120//133 +f 3120//302 3132//302 3133//302 3121//302 +f 3121//131 3133//131 3134//131 3122//131 +f 3122//130 3134//130 3135//130 3123//130 +f 3123//303 3135//303 3136//303 3124//303 +f 3124//128 3136//128 3125//128 3113//128 +f 3125//139 3137//139 3138//139 3126//139 +f 3126//138 3138//138 3139//138 3127//138 +f 3127//137 3139//137 3140//137 3128//137 +f 3128//136 3140//136 3141//136 3129//136 +f 3129//304 3141//304 3142//304 3130//304 +f 3130//134 3142//134 3143//134 3131//134 +f 3131//145 3143//145 3144//145 3132//145 +f 3132//144 3144//144 3145//144 3133//144 +f 3133//143 3145//143 3146//143 3134//143 +f 3134//142 3146//142 3147//142 3135//142 +f 3135//305 3147//305 3148//305 3136//305 +f 3136//140 3148//140 3137//140 3125//140 +f 3137//151 3149//151 3150//151 3138//151 +f 3138//150 3150//150 3151//150 3139//150 +f 3139//149 3151//149 3152//149 3140//149 +f 3140//148 3152//148 3153//148 3141//148 +f 3141//306 3153//306 3154//306 3142//306 +f 3142//146 3154//146 3155//146 3143//146 +f 3143//157 3155//157 3156//157 3144//157 +f 3144//156 3156//156 3157//156 3145//156 +f 3145//155 3157//155 3158//155 3146//155 +f 3146//154 3158//154 3159//154 3147//154 +f 3147//153 3159//153 3160//153 3148//153 +f 3148//152 3160//152 3149//152 3137//152 +f 3149//163 3161//163 3162//163 3150//163 +f 3150//162 3162//162 3163//162 3151//162 +f 3151//161 3163//161 3164//161 3152//161 +f 3152//160 3164//160 3165//160 3153//160 +f 3153//159 3165//159 3166//159 3154//159 +f 3154//158 3166//158 3167//158 3155//158 +f 3155//169 3167//169 3168//169 3156//169 +f 3156//168 3168//168 3169//168 3157//168 +f 3157//167 3169//167 3170//167 3158//167 +f 3158//166 3170//166 3171//166 3159//166 +f 3159//165 3171//165 3172//165 3160//165 +f 3160//164 3172//164 3161//164 3149//164 +f 3161//175 3173//175 3174//175 3162//175 +f 3162//174 3174//174 3175//174 3163//174 +f 3163//173 3175//173 3176//173 3164//173 +f 3164//172 3176//172 3177//172 3165//172 +f 3165//171 3177//171 3178//171 3166//171 +f 3166//170 3178//170 3179//170 3167//170 +f 3167//181 3179//181 3180//181 3168//181 +f 3168//180 3180//180 3181//180 3169//180 +f 3169//179 3181//179 3182//179 3170//179 +f 3170//178 3182//178 3183//178 3171//178 +f 3171//177 3183//177 3184//177 3172//177 +f 3172//176 3184//176 3173//176 3161//176 +f 3173//187 3185//187 3186//187 3174//187 +f 3174//186 3186//186 3187//186 3175//186 +f 3175//185 3187//185 3188//185 3176//185 +f 3176//184 3188//184 3189//184 3177//184 +f 3177//183 3189//183 3190//183 3178//183 +f 3178//182 3190//182 3191//182 3179//182 +f 3179//193 3191//193 3192//193 3180//193 +f 3180//192 3192//192 3193//192 3181//192 +f 3181//191 3193//191 3194//191 3182//191 +f 3182//190 3194//190 3195//190 3183//190 +f 3183//189 3195//189 3196//189 3184//189 +f 3184//188 3196//188 3185//188 3173//188 +f 3185//199 3197//199 3198//199 3186//199 +f 3186//198 3198//198 3199//198 3187//198 +f 3187//197 3199//197 3200//197 3188//197 +f 3188//196 3200//196 3201//196 3189//196 +f 3189//195 3201//195 3202//195 3190//195 +f 3190//194 3202//194 3203//194 3191//194 +f 3191//205 3203//205 3204//205 3192//205 +f 3192//307 3204//307 3205//307 3193//307 +f 3193//203 3205//203 3206//203 3194//203 +f 3194//202 3206//202 3207//202 3195//202 +f 3195//308 3207//308 3208//308 3196//308 +f 3196//200 3208//200 3197//200 3185//200 +f 3197//211 3209//211 3210//211 3198//211 +f 3198//210 3210//210 3211//210 3199//210 +f 3199//209 3211//209 3212//209 3200//209 +f 3200//208 3212//208 3213//208 3201//208 +f 3201//207 3213//207 3214//207 3202//207 +f 3202//206 3214//206 3215//206 3203//206 +f 3203//217 3215//217 3216//217 3204//217 +f 3204//309 3216//309 3217//309 3205//309 +f 3205//215 3217//215 3218//215 3206//215 +f 3206//214 3218//214 3219//214 3207//214 +f 3207//310 3219//310 3220//310 3208//310 +f 3208//212 3220//212 3209//212 3197//212 +f 3209//223 3221//223 3222//223 3210//223 +f 3210//222 3222//222 3223//222 3211//222 +f 3211//221 3223//221 3224//221 3212//221 +f 3212//220 3224//220 3225//220 3213//220 +f 3213//219 3225//219 3226//219 3214//219 +f 3214//218 3226//218 3227//218 3215//218 +f 3215//229 3227//229 3228//229 3216//229 +f 3216//311 3228//311 3229//311 3217//311 +f 3217//227 3229//227 3230//227 3218//227 +f 3218//226 3230//226 3231//226 3219//226 +f 3219//225 3231//225 3232//225 3220//225 +f 3220//224 3232//224 3221//224 3209//224 +f 3221//235 3233//235 3234//235 3222//235 +f 3222//234 3234//234 3235//234 3223//234 +f 3223//233 3235//233 3236//233 3224//233 +f 3224//232 3236//232 3237//232 3225//232 +f 3225//231 3237//231 3238//231 3226//231 +f 3226//230 3238//230 3239//230 3227//230 +f 3227//241 3239//241 3240//241 3228//241 +f 3228//312 3240//312 3241//312 3229//312 +f 3229//239 3241//239 3242//239 3230//239 +f 3230//238 3242//238 3243//238 3231//238 +f 3231//237 3243//237 3244//237 3232//237 +f 3232//236 3244//236 3233//236 3221//236 +f 3233//247 3245//247 3246//247 3234//247 +f 3234//246 3246//246 3247//246 3235//246 +f 3235//245 3247//245 3248//245 3236//245 +f 3236//244 3248//244 3249//244 3237//244 +f 3237//243 3249//243 3250//243 3238//243 +f 3238//242 3250//242 3251//242 3239//242 +f 3239//253 3251//253 3252//253 3240//253 +f 3240//252 3252//252 3253//252 3241//252 +f 3241//251 3253//251 3254//251 3242//251 +f 3242//250 3254//250 3255//250 3243//250 +f 3243//249 3255//249 3256//249 3244//249 +f 3244//248 3256//248 3245//248 3233//248 +f 3245//259 3257//259 3258//259 3246//259 +f 3246//258 3258//258 3259//258 3247//258 +f 3247//257 3259//257 3260//257 3248//257 +f 3248//256 3260//256 3261//256 3249//256 +f 3249//255 3261//255 3262//255 3250//255 +f 3250//254 3262//254 3263//254 3251//254 +f 3251//265 3263//265 3264//265 3252//265 +f 3252//264 3264//264 3265//264 3253//264 +f 3253//263 3265//263 3266//263 3254//263 +f 3254//262 3266//262 3267//262 3255//262 +f 3255//313 3267//313 3268//313 3256//313 +f 3256//260 3268//260 3257//260 3245//260 +f 3257//271 3269//271 3270//271 3258//271 +f 3258//270 3270//270 3271//270 3259//270 +f 3259//314 3271//314 3272//314 3260//314 +f 3260//268 3272//268 3273//268 3261//268 +f 3261//267 3273//267 3274//267 3262//267 +f 3262//266 3274//266 3275//266 3263//266 +f 3263//277 3275//277 3276//277 3264//277 +f 3264//276 3276//276 3277//276 3265//276 +f 3265//275 3277//275 3278//275 3266//275 +f 3266//274 3278//274 3279//274 3267//274 +f 3267//315 3279//315 3280//315 3268//315 +f 3268//272 3280//272 3269//272 3257//272 +f 3269//283 2705//283 2708//283 3270//283 +f 3270//282 2708//282 2710//282 3271//282 +f 3271//281 2710//281 2712//281 3272//281 +f 3272//280 2712//280 2714//280 3273//280 +f 3273//279 2714//279 2716//279 3274//279 +f 3274//278 2716//278 2718//278 3275//278 +f 3275//289 2718//289 2720//289 3276//289 +f 3276//316 2720//316 2722//316 3277//316 +f 3277//287 2722//287 2724//287 3278//287 +f 3278//286 2724//286 2726//286 3279//286 +f 3279//317 2726//317 2728//317 3280//317 +f 3280//284 2728//284 2705//284 3269//284 diff --git a/data/torus/torus_with_plane.urdf b/data/torus/torus_with_plane.urdf new file mode 100644 index 000000000..3db35dec2 --- /dev/null +++ b/data/torus/torus_with_plane.urdf @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/torus/torus_with_separate_plane.urdf b/data/torus/torus_with_separate_plane.urdf new file mode 100644 index 000000000..050301f4a --- /dev/null +++ b/data/torus/torus_with_separate_plane.urdf @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 33849d923..a6aa6aca3 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -242,7 +242,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) { case CMD_LOAD_URDF: { - b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "torus/torus.urdf"); + b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "torus/torus_with_separate_plane.urdf"); //setting the initial position, orientation and other arguments are optional double startPosX = 0; static double startPosY = 0; diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 53d19c503..7afdada11 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -36,6 +36,8 @@ subject to the following restrictions: #include "../TinyRenderer/model.h" #include "../ThirdPartyLibs/stb_image/stb_image.h" +extern int count; + enum MyFileType { @@ -721,6 +723,8 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo lightColor = m_data->m_lightColor; } + count = 0; + // printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size()); for (int i=0;im_swRenderInstances.size();i++) { @@ -757,7 +761,48 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo renderObj->m_lightColor = lightColor; } } - TinyRenderer::renderObject(*renderObj); + TinyRenderer::renderObjectDepth(*renderObj); + } + } + + count = 0; + + for (int i=0;im_swRenderInstances.size();i++) + { + TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(i); + if (0==visualArrayPtr) + continue;//can this ever happen? + TinyRendererObjectArray* visualArray = *visualArrayPtr; + + btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(i); + + + const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer(); + + for (int v=0;vm_renderObjects.size();v++) + { + + TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v]; + + + //sync the object transform + const btTransform& tr = colObj->getWorldTransform(); + tr.getOpenGLMatrix(modelMat); + + for (int i=0;i<4;i++) + { + for (int j=0;j<4;j++) + { + + renderObj->m_projectionMatrix[i][j] = projMat[i+4*j]; + renderObj->m_modelMatrix[i][j] = modelMat[i+4*j]; + renderObj->m_viewMatrix[i][j] = viewMat[i+4*j]; + renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); + renderObj->m_lightDirWorld = lightDirWorld; + renderObj->m_lightColor = lightColor; + } + } + TinyRenderer::renderObjectShadow(*renderObj); } } //printf("write tga \n"); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index d41e6450f..d449e4a3a 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -455,14 +455,13 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) count++; } - for (int k = 0; k < 76800; ++k) - { - if (shadowbuffer[k] > -1e30f+0.00001) - { - printf("[%d]: %f\n", k, shadowbuffer[k]); - } - } - + for (int k = 0; k < 76800; ++k) + { + if (shadowbuffer[k] > -1e30f+0.00001) + { + //printf("[%d]: %f\n", k, shadowbuffer[k]); + } + } ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); @@ -496,3 +495,102 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) } } + +void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) +{ + int width = renderData.m_rgbColorBuffer.get_width(); + int height = renderData.m_rgbColorBuffer.get_height(); + + Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); + Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]); + Model* model = renderData.m_model; + if (0==model) + return; + + renderData.m_viewportMatrix = viewport(0,0,width, height); + + b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; + b3AlignedObjectArray& shadowbuffer = renderData.m_shadowBuffer; + int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; + + TGAImage tempFrame(width, height, TGAImage::RGB); + TGAImage& frame = renderData.m_rgbColorBuffer; + + { + Matrix lightViewMatrix = lookat(light_dir_local*depth, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); + Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; + Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; + Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; + viewportmat = renderData.m_viewportMatrix; + Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); + + + DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling); + + setindex = true; + + for (int i=0; infaces(); i++) + { + for (int j=0; j<3; j++) { + shader.vertex(i, j); + } + triangle(shader.varying_tri, shader, tempFrame, &shadowbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + count++; + } + + for (int k = 0; k < 76800; ++k) + { + if (shadowbuffer[k] > -1e30f+0.00001) + { + //printf("[%d]: %f\n", k, shadowbuffer[k]); + } + } + + } + +} + +void TinyRenderer::renderObjectShadow(TinyRenderObjectData& renderData) +{ + int width = renderData.m_rgbColorBuffer.get_width(); + int height = renderData.m_rgbColorBuffer.get_height(); + + Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); + Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]); + Model* model = renderData.m_model; + if (0==model) + return; + + renderData.m_viewportMatrix = viewport(0,0,width, height); + + b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; + b3AlignedObjectArray& shadowbuffer = renderData.m_shadowBuffer; + int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; + + TGAImage tempFrame(width, height, TGAImage::RGB); + TGAImage& frame = renderData.m_rgbColorBuffer; + + { + Matrix lightViewMatrix = lookat(light_dir_local*depth, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); + Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; + Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; + Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; + viewportmat = renderData.m_viewportMatrix; + Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); + + ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); + + setindex = false; + + for (int i=0; infaces(); i++) + { + for (int j=0; j<3; j++) { + shadowShader.vertex(i, j); + } + triangle(shadowShader.varying_tri, shadowShader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + printf("count: %d\n", count); + count++; + } + } + +} diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index 745667782..39a4743c6 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -53,6 +53,8 @@ class TinyRenderer { public: static void renderObject(TinyRenderObjectData& renderData); + static void renderObjectDepth(TinyRenderObjectData& renderData); + static void renderObjectShadow(TinyRenderObjectData& renderData); }; #endif // TINY_RENDERER_Hbla From d48b03f23b7da6b6a26428deb006f42cad1cae97 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Mon, 28 Nov 2016 10:13:09 -0800 Subject: [PATCH 21/39] Use the barycentric coordinate to get the coordinate in shadow buffer. --- examples/TinyRenderer/TinyRenderer.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index d449e4a3a..1b7013487 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -202,14 +202,14 @@ struct ShadowShader : public IShader { virtual bool fragment(Vec3f bar, TGAColor &color) { Vec4f p = viewportmat*(varying_tri_light_view*bar); float depth = p[2]; - //p = p/p[3]; - //int index_x = b3Min(m_width-1, int(p[0])); - //index_x = b3Max(0, index_x); - //int index_y = b3Min(m_height-1, int(p[1])); - //index_y = b3Max(0, index_y); - //int idx = index_x + index_y*m_width; // index in the shadowbuffer array - int idx = indexmap[count]; - float shadow = 0.8+0.2*(m_shadowBuffer[idx]<-depth+0.43); // magic coeff to avoid z-fighting + p = p/p[3]; + int index_x = b3Min(m_width-1, int(p[0])); + index_x = b3Max(0, index_x); + int index_y = b3Min(m_height-1, int(p[1])); + index_y = b3Max(0, index_y); + int idx = index_x + index_y*m_width; // index in the shadowbuffer array + //int idx = indexmap[count]; + float shadow = 0.8+0.2*(m_shadowBuffer[idx]<-depth+0.2); // magic coeff to avoid z-fighting //printf("count: %d, idx: %d\n", count, idx); //printf("shadowbuffer: %f, depth: %f\n", m_shadowBuffer[idx], -depth+0.43); From 2e372a525e05443e757041ac95f6823908e565e4 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 28 Nov 2016 12:36:52 -0800 Subject: [PATCH 22/39] remove duplicate 'setTimeStep' in pybullet.c --- examples/pybullet/pybullet.c | 5 ----- 1 file changed, 5 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 1947ec103..61b57c083 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -3301,11 +3301,6 @@ static PyMethodDef SpamMethods[] = { "Set the amount of time to proceed at each call to stepSimulation. (unit " "is seconds, typically range is 0.01 or 0.001)"}, - - {"setTimeStep", pybullet_setTimeStep, METH_VARARGS, - "Set the amount of time to proceed at each call to stepSimulation." - " (unit is seconds, typically range is 0.01 or 0.001)"}, - {"setDefaultContactERP", pybullet_setDefaultContactERP, METH_VARARGS, "Set the amount of contact penetration Error Recovery Paramater " "(ERP) in each time step. \ From 2d42c7963a545c1822289ee45ba41c574bc535ea Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 28 Nov 2016 15:11:34 -0800 Subject: [PATCH 23/39] add pybullet getBaseVelocity / resetBaseVelocity C-API b3CreatePoseCommandSetBaseLinearVelocity/b3CreatePoseCommandSetBaseAngularVelocity --- examples/SharedMemory/PhysicsClientC_API.cpp | 36 ++ examples/SharedMemory/PhysicsClientC_API.h | 3 + .../PhysicsServerCommandProcessor.cpp | 26 +- examples/SharedMemory/SharedMemoryCommands.h | 6 +- examples/pybullet/pybullet.c | 420 +++++++++++++----- 5 files changed, 373 insertions(+), 118 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index e60953750..24d7e298c 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -672,6 +672,40 @@ int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHan return 0; } +int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_INIT_POSE); + command->m_updateFlags |= INIT_POSE_HAS_BASE_LINEAR_VELOCITY; + command->m_initPoseArgs.m_hasInitialStateQdot[0] = 1; + command->m_initPoseArgs.m_hasInitialStateQdot[1] = 1; + command->m_initPoseArgs.m_hasInitialStateQdot[2] = 1; + + command->m_initPoseArgs.m_initialStateQdot[0] = linVel[0]; + command->m_initPoseArgs.m_initialStateQdot[1] = linVel[1]; + command->m_initPoseArgs.m_initialStateQdot[2] = linVel[2]; + + return 0; +} + +int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, double angVel[3]) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_INIT_POSE); + command->m_updateFlags |= INIT_POSE_HAS_BASE_ANGULAR_VELOCITY; + command->m_initPoseArgs.m_hasInitialStateQdot[3] = 1; + command->m_initPoseArgs.m_hasInitialStateQdot[4] = 1; + command->m_initPoseArgs.m_hasInitialStateQdot[5] = 1; + + command->m_initPoseArgs.m_initialStateQdot[3] = angVel[0]; + command->m_initPoseArgs.m_initialStateQdot[4] = angVel[1]; + command->m_initPoseArgs.m_initialStateQdot[5] = angVel[2]; + + return 0; +} + int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; @@ -686,6 +720,8 @@ int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHand return 0; } + + int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index b9da28cd5..f8377c089 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -256,6 +256,9 @@ int b3CreateBoxCommandSetColorRGBA(b3SharedMemoryCommandHandle commandHandle, do b3SharedMemoryCommandHandle b3CreatePoseCommandInit(b3PhysicsClientHandle physClient, int bodyIndex); int b3CreatePoseCommandSetBasePosition(b3SharedMemoryCommandHandle commandHandle, double startPosX,double startPosY,double startPosZ); int b3CreatePoseCommandSetBaseOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX,double startOrnY,double startOrnZ, double startOrnW); +int b3CreatePoseCommandSetBaseLinearVelocity(b3SharedMemoryCommandHandle commandHandle, double linVel[3]); +int b3CreatePoseCommandSetBaseAngularVelocity(b3SharedMemoryCommandHandle commandHandle, double angVel[3]); + int b3CreatePoseCommandSetJointPositions(b3SharedMemoryCommandHandle commandHandle, int numJointPositions, const double* jointPositions); int b3CreatePoseCommandSetJointPosition(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle, int jointIndex, double jointPosition); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 18231566f..d0a3dca38 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -2342,6 +2342,28 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm if (body && body->m_multiBody) { btMultiBody* mb = body->m_multiBody; + btVector3 baseLinVel(0, 0, 0); + btVector3 baseAngVel(0, 0, 0); + + + if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_LINEAR_VELOCITY) + { + baseLinVel.setValue(clientCmd.m_initPoseArgs.m_initialStateQdot[0], + clientCmd.m_initPoseArgs.m_initialStateQdot[1], + clientCmd.m_initPoseArgs.m_initialStateQdot[2]); + mb->setBaseVel(baseLinVel); + + } + + if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_ANGULAR_VELOCITY) + { + baseAngVel.setValue(clientCmd.m_initPoseArgs.m_initialStateQdot[3], + clientCmd.m_initPoseArgs.m_initialStateQdot[4], + clientCmd.m_initPoseArgs.m_initialStateQdot[5]); + mb->setBaseOmega(baseAngVel); + } + + if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_POSITION) { btVector3 zero(0,0,0); @@ -2349,7 +2371,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm clientCmd.m_initPoseArgs.m_hasInitialStateQ[1] && clientCmd.m_initPoseArgs.m_hasInitialStateQ[2]); - mb->setBaseVel(zero); + mb->setBaseVel(baseLinVel); mb->setBasePos(btVector3( clientCmd.m_initPoseArgs.m_initialStateQ[0], clientCmd.m_initPoseArgs.m_initialStateQ[1], @@ -2362,7 +2384,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm clientCmd.m_initPoseArgs.m_hasInitialStateQ[5] && clientCmd.m_initPoseArgs.m_hasInitialStateQ[6]); - mb->setBaseOmega(btVector3(0,0,0)); + mb->setBaseOmega(baseAngVel); btQuaternion invOrn(clientCmd.m_initPoseArgs.m_initialStateQ[3], clientCmd.m_initPoseArgs.m_initialStateQ[4], clientCmd.m_initPoseArgs.m_initialStateQ[5], diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 5b3346433..5d25059c2 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -109,7 +109,9 @@ enum EnumInitPoseFlags { INIT_POSE_HAS_INITIAL_POSITION=1, INIT_POSE_HAS_INITIAL_ORIENTATION=2, - INIT_POSE_HAS_JOINT_STATE=4 + INIT_POSE_HAS_JOINT_STATE=4, + INIT_POSE_HAS_BASE_LINEAR_VELOCITY = 8, + INIT_POSE_HAS_BASE_ANGULAR_VELOCITY = 16, }; @@ -122,6 +124,8 @@ struct InitPoseArgs int m_bodyUniqueId; int m_hasInitialStateQ[MAX_DEGREE_OF_FREEDOM]; double m_initialStateQ[MAX_DEGREE_OF_FREEDOM]; + int m_hasInitialStateQdot[MAX_DEGREE_OF_FREEDOM]; + double m_initialStateQdot[MAX_DEGREE_OF_FREEDOM]; }; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 61b57c083..7aeaab7e0 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -30,6 +30,123 @@ enum eCONNECT_METHOD { static PyObject* SpamError; static b3PhysicsClientHandle sm = 0; + +static double pybullet_internalGetFloatFromSequence(PyObject* seq, int index) { + double v = 0.0; + PyObject* item; + + if (PyList_Check(seq)) { + item = PyList_GET_ITEM(seq, index); + v = PyFloat_AsDouble(item); + } + else { + item = PyTuple_GET_ITEM(seq, index); + v = PyFloat_AsDouble(item); + } + return v; +} + + +// internal function to set a float matrix[16] +// used to initialize camera position with +// a view and projection matrix in renderImage() +// +// // Args: +// matrix - float[16] which will be set by values from objMat +static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) { + int i, len; + PyObject* seq; + + seq = PySequence_Fast(objMat, "expected a sequence"); + if (seq) + { + len = PySequence_Size(objMat); + if (len == 16) { + for (i = 0; i < len; i++) { + matrix[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + Py_DECREF(seq); + return 1; + } + Py_DECREF(seq); + } + return 0; +} + +// internal function to set a float vector[3] +// used to initialize camera position with +// a view and projection matrix in renderImage() +// +// // Args: +// vector - float[3] which will be set by values from objMat +static int pybullet_internalSetVector(PyObject* objVec, float vector[3]) { + int i, len; + PyObject* seq = 0; + if (objVec == NULL) + return 0; + + seq = PySequence_Fast(objVec, "expected a sequence"); + if (seq) + { + + len = PySequence_Size(objVec); + if (len == 3) { + for (i = 0; i < len; i++) { + vector[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + Py_DECREF(seq); + return 1; + } + Py_DECREF(seq); + } + return 0; +} + +// vector - double[3] which will be set by values from obVec +static int pybullet_internalSetVectord(PyObject* obVec, double vector[3]) { + int i, len; + PyObject* seq; + if (obVec == NULL) + return 0; + + seq = PySequence_Fast(obVec, "expected a sequence"); + if (seq) + { + len = PySequence_Size(obVec); + if (len == 3) { + for (i = 0; i < len; i++) { + vector[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + Py_DECREF(seq); + return 1; + } + Py_DECREF(seq); + } + return 0; +} + +// vector - double[3] which will be set by values from obVec +static int pybullet_internalSetVector4d(PyObject* obVec, double vector[4]) { + int i, len; + PyObject* seq; + if (obVec == NULL) + return 0; + + seq = PySequence_Fast(obVec, "expected a sequence"); + len = PySequence_Size(obVec); + if (len == 4) { + for (i = 0; i < len; i++) { + vector[i] = pybullet_internalGetFloatFromSequence(seq, i); + } + Py_DECREF(seq); + return 1; + } + Py_DECREF(seq); + return 0; +} + + + // Step through one timestep of the simulation static PyObject* pybullet_stepSimulation(PyObject* self, PyObject* args) { if (0 == sm) { @@ -371,19 +488,6 @@ static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args) { return PyLong_FromLong(bodyIndex); } -static double pybullet_internalGetFloatFromSequence(PyObject* seq, int index) { - double v = 0.0; - PyObject* item; - - if (PyList_Check(seq)) { - item = PyList_GET_ITEM(seq, index); - v = PyFloat_AsDouble(item); - } else { - item = PyTuple_GET_ITEM(seq, index); - v = PyFloat_AsDouble(item); - } - return v; -} @@ -768,11 +872,68 @@ pybullet_setDefaultContactERP(PyObject* self, PyObject* args) return Py_None; } +static int pybullet_internalGetBaseVelocity( + int bodyIndex, double baseLinearVelocity[3], double baseAngularVelocity[3]) { + baseLinearVelocity[0] = 0.; + baseLinearVelocity[1] = 0.; + baseLinearVelocity[2] = 0.; + + baseAngularVelocity[0] = 0.; + baseAngularVelocity[1] = 0.; + baseAngularVelocity[2] = 0.; + + if (0 == sm) { + PyErr_SetString(SpamError, "Not connected to physics server."); + return 0; + } + + { + { + b3SharedMemoryCommandHandle cmd_handle = + b3RequestActualStateCommandInit(sm, bodyIndex); + b3SharedMemoryStatusHandle status_handle = + b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); + + const int status_type = b3GetStatusType(status_handle); + const double* actualStateQdot; + // const double* jointReactionForces[]; + + + if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) { + PyErr_SetString(SpamError, "getBaseVelocity failed."); + return 0; + } + + b3GetStatusActualState( + status_handle, 0 /* body_unique_id */, + 0 /* num_degree_of_freedom_q */, 0 /* num_degree_of_freedom_u */, + 0 /*root_local_inertial_frame*/, 0, + &actualStateQdot, 0 /* joint_reaction_forces */); + + // printf("joint reaction forces="); + // for (i=0; i < (sizeof(jointReactionForces)/sizeof(double)); i++) { + // printf("%f ", jointReactionForces[i]); + // } + // now, position x,y,z = actualStateQ[0],actualStateQ[1],actualStateQ[2] + // and orientation x,y,z,w = + // actualStateQ[3],actualStateQ[4],actualStateQ[5],actualStateQ[6] + baseLinearVelocity[0] = actualStateQdot[0]; + baseLinearVelocity[1] = actualStateQdot[1]; + baseLinearVelocity[2] = actualStateQdot[2]; + + baseAngularVelocity[0] = actualStateQdot[3]; + baseAngularVelocity[1] = actualStateQdot[4]; + baseAngularVelocity[2] = actualStateQdot[5]; + + } + } + return 1; +} // Internal function used to get the base position and orientation // Orientation is returned in quaternions static int pybullet_internalGetBasePositionAndOrientation( - int bodyIndex, double basePosition[3], double baseOrientation[3]) { + int bodyIndex, double basePosition[3], double baseOrientation[4]) { basePosition[0] = 0.; basePosition[1] = 0.; basePosition[2] = 0.; @@ -855,8 +1016,7 @@ static PyObject* pybullet_getBasePositionAndOrientation(PyObject* self, if (0 == pybullet_internalGetBasePositionAndOrientation( bodyIndex, basePosition, baseOrientation)) { PyErr_SetString(SpamError, - "GetBasePositionAndOrientation failed (#joints/links " - "exceeds maximum?)."); + "GetBasePositionAndOrientation failed."); return NULL; } @@ -891,6 +1051,62 @@ static PyObject* pybullet_getBasePositionAndOrientation(PyObject* self, } } + +static PyObject* pybullet_getBaseVelocity(PyObject* self, + PyObject* args) { + int bodyIndex = -1; + double baseLinearVelocity[3]; + double baseAngularVelocity[3]; + PyObject* pylistLinVel=0; + PyObject* pylistAngVel=0; + + if (0 == sm) { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + if (!PyArg_ParseTuple(args, "i", &bodyIndex)) { + PyErr_SetString(SpamError, "Expected a body index (integer)."); + return NULL; + } + + if (0 == pybullet_internalGetBaseVelocity( + bodyIndex, baseLinearVelocity, baseAngularVelocity)) { + PyErr_SetString(SpamError, + "getBaseVelocity failed."); + return NULL; + } + + { + PyObject* item; + int i; + int num = 3; + pylistLinVel = PyTuple_New(num); + for (i = 0; i < num; i++) { + item = PyFloat_FromDouble(baseLinearVelocity[i]); + PyTuple_SetItem(pylistLinVel, i, item); + } + } + + { + PyObject* item; + int i; + int num = 3; + pylistAngVel = PyTuple_New(num); + for (i = 0; i < num; i++) { + item = PyFloat_FromDouble(baseAngularVelocity[i]); + PyTuple_SetItem(pylistAngVel, i, item); + } + } + + { + PyObject* pylist; + pylist = PyTuple_New(2); + PyTuple_SetItem(pylist, 0, pylistLinVel); + PyTuple_SetItem(pylist, 1, pylistAngVel); + return pylist; + } +} static PyObject* pybullet_getNumBodies(PyObject* self, PyObject* args) { if (0 == sm) { @@ -1035,6 +1251,66 @@ static PyObject* pybullet_resetJointState(PyObject* self, PyObject* args) { return NULL; } + + + +static PyObject* pybullet_resetBaseVelocity(PyObject* self, PyObject* args, PyObject *keywds) +{ + static char *kwlist[] = { "objectUniqueId", "linearVelocity", "angularVelocity", NULL }; + + if (0 == sm) + { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + { + int bodyIndex=0; + PyObject* linVelObj=0; + PyObject* angVelObj=0; + double linVel[3] = { 0, 0, 0 }; + double angVel[3] = { 0, 0, 0 }; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OO", kwlist, &bodyIndex, &linVelObj, &angVelObj)) + { + return NULL; + } + if (linVelObj || angVelObj) + { + + b3SharedMemoryCommandHandle commandHandle; + b3SharedMemoryStatusHandle statusHandle; + + commandHandle = b3CreatePoseCommandInit(sm, bodyIndex); + + if (linVelObj) + { + pybullet_internalSetVectord(linVelObj, linVel); + b3CreatePoseCommandSetBaseLinearVelocity(commandHandle, linVel); + } + + if (angVelObj) + { + pybullet_internalSetVectord(angVelObj, angVel); + b3CreatePoseCommandSetBaseAngularVelocity(commandHandle, angVel); + } + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); + Py_INCREF(Py_None); + return Py_None; + } + else + { + PyErr_SetString(SpamError, "expected at least linearVelocity and/or angularVelocity."); + return NULL; + } + } + PyErr_SetString(SpamError, "error in resetJointState."); + return NULL; +} + + + // Reset the position and orientation of the base/root link, position [x,y,z] // and orientation quaternion [x,y,z,w] static PyObject* pybullet_resetBasePositionAndOrientation(PyObject* self, @@ -1366,105 +1642,6 @@ static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args) { return Py_None; } -// internal function to set a float matrix[16] -// used to initialize camera position with -// a view and projection matrix in renderImage() -// -// // Args: -// matrix - float[16] which will be set by values from objMat -static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) { - int i, len; - PyObject* seq; - - seq = PySequence_Fast(objMat, "expected a sequence"); - if (seq) - { - len = PySequence_Size(objMat); - if (len == 16) { - for (i = 0; i < len; i++) { - matrix[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - Py_DECREF(seq); - return 1; - } - Py_DECREF(seq); - } - return 0; -} - -// internal function to set a float vector[3] -// used to initialize camera position with -// a view and projection matrix in renderImage() -// -// // Args: -// vector - float[3] which will be set by values from objMat -static int pybullet_internalSetVector(PyObject* objVec, float vector[3]) { - int i, len; - PyObject* seq=0; - if (objVec==NULL) - return 0; - - seq = PySequence_Fast(objVec, "expected a sequence"); - if (seq) - { - - len = PySequence_Size(objVec); - if (len == 3) { - for (i = 0; i < len; i++) { - vector[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - Py_DECREF(seq); - return 1; - } - Py_DECREF(seq); - } - return 0; -} - -// vector - double[3] which will be set by values from obVec -static int pybullet_internalSetVectord(PyObject* obVec, double vector[3]) { - int i, len; - PyObject* seq; - if (obVec==NULL) - return 0; - - seq = PySequence_Fast(obVec, "expected a sequence"); - if (seq) - { - len = PySequence_Size(obVec); - if (len == 3) { - for (i = 0; i < len; i++) { - vector[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - Py_DECREF(seq); - return 1; - } - Py_DECREF(seq); - } - return 0; -} - -// vector - double[3] which will be set by values from obVec -static int pybullet_internalSetVector4d(PyObject* obVec, double vector[4]) { - int i, len; - PyObject* seq; - if (obVec==NULL) - return 0; - - seq = PySequence_Fast(obVec, "expected a sequence"); - len = PySequence_Size(obVec); - if (len == 4) { - for (i = 0; i < len; i++) { - vector[i] = pybullet_internalGetFloatFromSequence(seq, i); - } - Py_DECREF(seq); - return 1; - } - Py_DECREF(seq); - return 0; -} - - static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObject *keywds) { @@ -3361,6 +3538,19 @@ static PyMethodDef SpamMethods[] = { "instantaneously, not through physics simulation. (x,y,z) position vector " "and (x,y,z,w) quaternion orientation."}, + { "getBaseVelocity", pybullet_getBaseVelocity, + METH_VARARGS, + "Get the linear and angular velocity of the base of the object " + " in world space coordinates. " + "(x,y,z) linear velocity vector and (x,y,z) angular velocity vector." }, + + { "resetBaseVelocity", (PyCFunction)pybullet_resetBaseVelocity, METH_VARARGS | METH_KEYWORDS, + "Reset the linear and/or angular velocity of the base of the object " + " in world space coordinates. " + "linearVelocity (x,y,z) and angularVelocity (x,y,z)." }, + + + {"getNumJoints", pybullet_getNumJoints, METH_VARARGS, "Get the number of joints for an object."}, From 8de35cf01cc4c6024c3732852dd1b1bad63365d3 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 29 Nov 2016 09:09:35 -0800 Subject: [PATCH 24/39] remove prefix/postfix from pybullet, so it becomes pybullet.so and pybullet_d.so in debug mode (and on Windows, pybullet.pyd and pybullet_d.pyd) fix build_cmake_pybullet_win32.bat, so it links against correct version of pythonx.lib pythonx_d.lib. Still, I would prefer using premake on Windows, it has more native Visual Studio features. --- build_cmake_pybullet_win32.bat | 2 +- examples/pybullet/CMakeLists.txt | 3 +++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/build_cmake_pybullet_win32.bat b/build_cmake_pybullet_win32.bat index 33317f2c1..f3e672899 100644 --- a/build_cmake_pybullet_win32.bat +++ b/build_cmake_pybullet_win32.bat @@ -1,4 +1,4 @@ mkdir cm cd cm -cmake -DBUILD_PYBULLET=ON -DCMAKE_BUILD_TYPE=Release -DPYTHON_INCLUDE_DIR=c:\python-3.5.2\include -DPYTHON_LIBRARY=c:\python-3.5.2\libs\python35_d.lib .. +cmake -DBUILD_PYBULLET=ON -DCMAKE_BUILD_TYPE=Release -DPYTHON_INCLUDE_DIR=c:\python-3.5.2\include -DPYTHON_LIBRARY=c:\python-3.5.2\libs\python35.lib -DPYTHON_DEBUG_LIBRARY=c:\python-3.5.2\libs\python35_d.lib .. start . diff --git a/examples/pybullet/CMakeLists.txt b/examples/pybullet/CMakeLists.txt index 8d95cc67e..85de30a69 100644 --- a/examples/pybullet/CMakeLists.txt +++ b/examples/pybullet/CMakeLists.txt @@ -110,6 +110,9 @@ ELSE(BUILD_PYBULLET_ENET) ADD_LIBRARY(pybullet SHARED ${pybullet_SRCS}) ENDIF(BUILD_PYBULLET_ENET) +SET_TARGET_PROPERTIES(pybullet PROPERTIES PREFIX "") +SET_TARGET_PROPERTIES(pybullet PROPERTIES POSTFIX "") + SET_TARGET_PROPERTIES(pybullet PROPERTIES VERSION ${BULLET_VERSION}) SET_TARGET_PROPERTIES(pybullet PROPERTIES SOVERSION ${BULLET_VERSION}) SET_TARGET_PROPERTIES(pybullet PROPERTIES DEBUG_POSTFIX "_d") From 5fe36ca2001f0c04f9870285a0a25e2f6ace71d6 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Tue, 29 Nov 2016 11:11:41 -0800 Subject: [PATCH 25/39] Clean global variables. --- .../TinyRendererVisualShapeConverter.cpp | 36 ++-- examples/TinyRenderer/TinyRenderer.cpp | 161 ++++-------------- examples/TinyRenderer/TinyRenderer.h | 1 + examples/TinyRenderer/our_gl.cpp | 8 - 4 files changed, 47 insertions(+), 159 deletions(-) diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 7afdada11..13aa4b19b 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -36,9 +36,6 @@ subject to the following restrictions: #include "../TinyRenderer/model.h" #include "../ThirdPartyLibs/stb_image/stb_image.h" -extern int count; - - enum MyFileType { MY_FILE_STL=1, @@ -723,17 +720,16 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo lightColor = m_data->m_lightColor; } - count = 0; + float lightDistance = 2.0; - // printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size()); - for (int i=0;im_swRenderInstances.size();i++) + for (int n=0;nm_swRenderInstances.size();n++) { - TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(i); + TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n); if (0==visualArrayPtr) continue;//can this ever happen? TinyRendererObjectArray* visualArray = *visualArrayPtr; - btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(i); + btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(n); const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer(); @@ -756,25 +752,24 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo renderObj->m_projectionMatrix[i][j] = projMat[i+4*j]; renderObj->m_modelMatrix[i][j] = modelMat[i+4*j]; renderObj->m_viewMatrix[i][j] = viewMat[i+4*j]; - renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); - renderObj->m_lightDirWorld = lightDirWorld; - renderObj->m_lightColor = lightColor; } } + renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); + renderObj->m_lightDirWorld = lightDirWorld; + renderObj->m_lightColor = lightColor; + renderObj->m_lightDistance = lightDistance; TinyRenderer::renderObjectDepth(*renderObj); } } - - count = 0; - - for (int i=0;im_swRenderInstances.size();i++) + + for (int n=0;nm_swRenderInstances.size();n++) { - TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(i); + TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n); if (0==visualArrayPtr) continue;//can this ever happen? TinyRendererObjectArray* visualArray = *visualArrayPtr; - btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(i); + btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(n); const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer(); @@ -797,11 +792,12 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo renderObj->m_projectionMatrix[i][j] = projMat[i+4*j]; renderObj->m_modelMatrix[i][j] = modelMat[i+4*j]; renderObj->m_viewMatrix[i][j] = viewMat[i+4*j]; - renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); - renderObj->m_lightDirWorld = lightDirWorld; - renderObj->m_lightColor = lightColor; } } + renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); + renderObj->m_lightDirWorld = lightDirWorld; + renderObj->m_lightColor = lightColor; + renderObj->m_lightDistance = lightDistance; TinyRenderer::renderObjectShadow(*renderObj); } } diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 1b7013487..974a8db5e 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -13,12 +13,6 @@ #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" -Matrix viewportmat; -float depth = 2.0; -int indexmap[10000000]; -int count = 0; -bool setindex = true; - struct Shader : public IShader { Model* m_model; @@ -28,7 +22,7 @@ struct Shader : public IShader { Matrix m_invModelMat; Matrix& m_modelView1; - Matrix& m_projectionMatrix; + Matrix& m_projectionMat; Vec3f m_localScaling; Vec4f m_colorRGBA; @@ -37,12 +31,12 @@ struct Shader : public IShader { mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS //mat<3,3,float> ndc_tri; // triangle in normalized device coordinates - Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) + Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& projectionMat, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) :m_model(model), m_light_dir_local(light_dir_local), m_light_color(light_color), m_modelView1(modelView), - m_projectionMatrix(projectionMatrix), + m_projectionMat(projectionMat), m_modelMat(modelMat), m_localScaling(localScaling), m_colorRGBA(colorRGBA) @@ -63,7 +57,7 @@ struct Shader : public IShader { unScaledVert[1]*m_localScaling[1], unScaledVert[2]*m_localScaling[2]); - Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert); + Vec4f gl_Vertex = m_projectionMat*m_modelView1*embed<4>(scaledVert); varying_tri.set_col(nthvert, gl_Vertex); return gl_Vertex; } @@ -104,21 +98,23 @@ struct DepthShader : public IShader { Matrix& m_modelMat; Matrix m_invModelMat; - Matrix& m_projectionMatrix; + Matrix& m_projectionMat; Vec3f m_localScaling; Matrix& m_lightModelView; + float m_lightDistance; mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - DepthShader(Model* model, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling) + DepthShader(Model* model, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Vec3f localScaling, float lightDistance) :m_model(model), m_lightModelView(lightModelView), - m_projectionMatrix(projectionMatrix), + m_projectionMat(projectionMat), m_modelMat(modelMat), - m_localScaling(localScaling) + m_localScaling(localScaling), + m_lightDistance(lightDistance) { m_invModelMat = m_modelMat.invert_transpose(); } @@ -130,14 +126,14 @@ struct DepthShader : public IShader { Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0], unScaledVert[1]*m_localScaling[1], unScaledVert[2]*m_localScaling[2]); - Vec4f gl_Vertex = m_projectionMatrix*m_lightModelView*embed<4>(scaledVert); + Vec4f gl_Vertex = m_projectionMat*m_lightModelView*embed<4>(scaledVert); varying_tri.set_col(nthvert, gl_Vertex); return gl_Vertex; } virtual bool fragment(Vec3f bar, TGAColor &color) { Vec4f p = varying_tri*bar; - color = TGAColor(255, 255, 255)*(p[2]/depth); + color = TGAColor(255, 255, 255)*(p[2]/m_lightDistance); return false; } }; @@ -151,10 +147,11 @@ struct ShadowShader : public IShader { Matrix m_invModelMat; Matrix& m_modelView1; - Matrix& m_projectionMatrix; + Matrix& m_projectionMat; Vec3f m_localScaling; Matrix& m_lightModelView; Vec4f m_colorRGBA; + Matrix& m_viewportMat; b3AlignedObjectArray& m_shadowBuffer; @@ -168,14 +165,15 @@ struct ShadowShader : public IShader { mat<4,3,float> varying_tri_light_view; mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray& shadowBuffer) + ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Matrix& viewportMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray& shadowBuffer) :m_model(model), m_light_dir_local(light_dir_local), m_light_color(light_color), m_modelView1(modelView), m_lightModelView(lightModelView), - m_projectionMatrix(projectionMatrix), + m_projectionMat(projectionMat), m_modelMat(modelMat), + m_viewportMat(viewportMat), m_localScaling(localScaling), m_colorRGBA(colorRGBA), m_width(width), @@ -192,28 +190,24 @@ struct ShadowShader : public IShader { Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0], unScaledVert[1]*m_localScaling[1], unScaledVert[2]*m_localScaling[2]); - Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert); + Vec4f gl_Vertex = m_projectionMat*m_modelView1*embed<4>(scaledVert); varying_tri.set_col(nthvert, gl_Vertex); - Vec4f gl_VertexLightView = m_projectionMatrix*m_lightModelView*embed<4>(scaledVert); + Vec4f gl_VertexLightView = m_projectionMat*m_lightModelView*embed<4>(scaledVert); varying_tri_light_view.set_col(nthvert, gl_VertexLightView); return gl_Vertex; } virtual bool fragment(Vec3f bar, TGAColor &color) { - Vec4f p = viewportmat*(varying_tri_light_view*bar); + Vec4f p = m_viewportMat*(varying_tri_light_view*bar); float depth = p[2]; p = p/p[3]; - int index_x = b3Min(m_width-1, int(p[0])); - index_x = b3Max(0, index_x); - int index_y = b3Min(m_height-1, int(p[1])); - index_y = b3Max(0, index_y); + + int index_x = b3Max(0, b3Min(m_width-1, int(p[0]))); + int index_y = b3Max(0, b3Min(m_height-1, int(p[1]))); int idx = index_x + index_y*m_width; // index in the shadowbuffer array //int idx = indexmap[count]; float shadow = 0.8+0.2*(m_shadowBuffer[idx]<-depth+0.2); // magic coeff to avoid z-fighting - //printf("count: %d, idx: %d\n", count, idx); - //printf("shadowbuffer: %f, depth: %f\n", m_shadowBuffer[idx], -depth+0.43); - Vec3f bn = (varying_nrm*bar).normalize(); Vec2f uv = varying_uv*bar; @@ -414,86 +408,7 @@ TinyRenderObjectData::~TinyRenderObjectData() void TinyRenderer::renderObject(TinyRenderObjectData& renderData) { - int width = renderData.m_rgbColorBuffer.get_width(); - int height = renderData.m_rgbColorBuffer.get_height(); - - Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); - Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]); - Model* model = renderData.m_model; - if (0==model) - return; - - renderData.m_viewportMatrix = viewport(0,0,width, height); - - b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; - b3AlignedObjectArray& shadowbuffer = renderData.m_shadowBuffer; - int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; - - TGAImage tempFrame(width, height, TGAImage::RGB); - TGAImage& frame = renderData.m_rgbColorBuffer; - - { - Matrix lightViewMatrix = lookat(light_dir_local*depth, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); - Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; - Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; - Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; - viewportmat = renderData.m_viewportMatrix; - Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - - - DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling); - - setindex = true; - count = 0; - - for (int i=0; infaces(); i++) - { - for (int j=0; j<3; j++) { - shader.vertex(i, j); - } - triangle(shader.varying_tri, shader, tempFrame, &shadowbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); - count++; - } - - for (int k = 0; k < 76800; ++k) - { - if (shadowbuffer[k] > -1e30f+0.00001) - { - //printf("[%d]: %f\n", k, shadowbuffer[k]); - } - } - - ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); - - setindex = false; - count = 0; - - for (int i=0; infaces(); i++) - { - for (int j=0; j<3; j++) { - shadowShader.vertex(i, j); - } - triangle(shadowShader.varying_tri, shadowShader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); - count++; - } - - - /* - Shader shader(model, light_dir_local, light_color, modelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA()); - - //printf("Render %d triangles.\n",model->nfaces()); - for (int i=0; infaces(); i++) - { - - for (int j=0; j<3; j++) { - shader.vertex(i, j); - } - triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); - } - */ - - } - + } void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) @@ -503,6 +418,7 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]); + float light_distance = renderData.m_lightDistance; Model* model = renderData.m_model; if (0==model) return; @@ -517,17 +433,14 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) TGAImage& frame = renderData.m_rgbColorBuffer; { - Matrix lightViewMatrix = lookat(light_dir_local*depth, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); + Matrix lightViewMatrix = lookat(light_dir_local*light_distance, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; - viewportmat = renderData.m_viewportMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling); - - setindex = true; + DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling, light_distance); for (int i=0; infaces(); i++) { @@ -535,17 +448,7 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) shader.vertex(i, j); } triangle(shader.varying_tri, shader, tempFrame, &shadowbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); - count++; } - - for (int k = 0; k < 76800; ++k) - { - if (shadowbuffer[k] > -1e30f+0.00001) - { - //printf("[%d]: %f\n", k, shadowbuffer[k]); - } - } - } } @@ -557,6 +460,7 @@ void TinyRenderer::renderObjectShadow(TinyRenderObjectData& renderData) Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]); + float light_distance = renderData.m_lightDistance; Model* model = renderData.m_model; if (0==model) return; @@ -571,16 +475,13 @@ void TinyRenderer::renderObjectShadow(TinyRenderObjectData& renderData) TGAImage& frame = renderData.m_rgbColorBuffer; { - Matrix lightViewMatrix = lookat(light_dir_local*depth, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); + Matrix lightViewMatrix = lookat(light_dir_local*light_distance, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; - viewportmat = renderData.m_viewportMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); - - setindex = false; + ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); for (int i=0; infaces(); i++) { @@ -588,8 +489,6 @@ void TinyRenderer::renderObjectShadow(TinyRenderObjectData& renderData) shadowShader.vertex(i, j); } triangle(shadowShader.varying_tri, shadowShader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); - printf("count: %d\n", count); - count++; } } diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index 39a4743c6..28c684b36 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -19,6 +19,7 @@ struct TinyRenderObjectData btVector3 m_localScaling; btVector3 m_lightDirWorld; btVector3 m_lightColor; + float m_lightDistance; //Model (vertices, indices, textures, shader) Matrix m_modelMatrix; diff --git a/examples/TinyRenderer/our_gl.cpp b/examples/TinyRenderer/our_gl.cpp index 46c08dd45..cd38a9ab7 100644 --- a/examples/TinyRenderer/our_gl.cpp +++ b/examples/TinyRenderer/our_gl.cpp @@ -4,10 +4,6 @@ #include "our_gl.h" #include "Bullet3Common/b3MinMax.h" -extern int indexmap[10000000]; -extern int count; -extern bool setindex; - IShader::~IShader() {} Matrix viewport(int x, int y, int w, int h) @@ -144,10 +140,6 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb Vec3f bc_clip = Vec3f(bc_screen.x/pts[0][3], bc_screen.y/pts[1][3], bc_screen.z/pts[2][3]); bc_clip = bc_clip/(bc_clip.x+bc_clip.y+bc_clip.z); float frag_depth = -1*(clipc[2]*bc_clip); - if (setindex) - { - indexmap[count] = P.x+P.y*image.get_width(); - } if (bc_screen.x<0 || bc_screen.y<0 || bc_screen.z<0 || zbuffer[P.x+P.y*image.get_width()]>frag_depth) continue; From 86c5dfe8f4fe43cf0068743b1a1f719a3e36a245 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Tue, 29 Nov 2016 11:43:52 -0800 Subject: [PATCH 26/39] Fix the light color issue in box rendering example. --- examples/RenderingExamples/TinyRendererSetup.cpp | 4 +++- examples/SharedMemory/TinyRendererVisualShapeConverter.cpp | 2 +- examples/TinyRenderer/TinyRenderer.cpp | 7 +------ examples/TinyRenderer/TinyRenderer.h | 3 +-- 4 files changed, 6 insertions(+), 10 deletions(-) diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index 84f7b0033..21906d787 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -154,7 +154,6 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui) const char* fileName = "textured_sphere_smooth.obj"; fileName = "cube.obj"; - { @@ -373,6 +372,9 @@ void TinyRendererSetup::stepSimulation(float deltaTime) }; m_internalData->m_renderObjects[o]->m_lightDirWorld = lightDirWorld.normalized(); + + btVector3 lightColor(1.0,1.0,1.0); + m_internalData->m_renderObjects[o]->m_lightColor = lightColor; } } diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 13aa4b19b..aed5ae467 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -798,7 +798,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo renderObj->m_lightDirWorld = lightDirWorld; renderObj->m_lightColor = lightColor; renderObj->m_lightDistance = lightDistance; - TinyRenderer::renderObjectShadow(*renderObj); + TinyRenderer::renderObject(*renderObj); } } //printf("write tga \n"); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 974a8db5e..592667309 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -406,11 +406,6 @@ TinyRenderObjectData::~TinyRenderObjectData() delete m_model; } -void TinyRenderer::renderObject(TinyRenderObjectData& renderData) -{ - -} - void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) { int width = renderData.m_rgbColorBuffer.get_width(); @@ -453,7 +448,7 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) } -void TinyRenderer::renderObjectShadow(TinyRenderObjectData& renderData) +void TinyRenderer::renderObject(TinyRenderObjectData& renderData) { int width = renderData.m_rgbColorBuffer.get_width(); int height = renderData.m_rgbColorBuffer.get_height(); diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index 28c684b36..d82060382 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -53,9 +53,8 @@ struct TinyRenderObjectData class TinyRenderer { public: - static void renderObject(TinyRenderObjectData& renderData); static void renderObjectDepth(TinyRenderObjectData& renderData); - static void renderObjectShadow(TinyRenderObjectData& renderData); + static void renderObject(TinyRenderObjectData& renderData); }; #endif // TINY_RENDERER_Hbla From 8aa90a7427e9723a4f0466accfa9859d584a3bad Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Tue, 29 Nov 2016 12:53:50 -0800 Subject: [PATCH 27/39] Refactor shader and render pipeline code. --- .../TinyRendererVisualShapeConverter.cpp | 88 +++++++++------ .../TinyRendererVisualShapeConverter.h | 2 + examples/TinyRenderer/TinyRenderer.cpp | 105 ++---------------- 3 files changed, 67 insertions(+), 128 deletions(-) diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index aed5ae467..a36dc4b1f 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -77,6 +77,9 @@ struct TinyRendererVisualShapeConverterInternalData bool m_hasLightDirection; btVector3 m_lightColor; bool m_hasLightColor; + float m_lightDistance; + bool m_hasLightDistance; + bool m_hasShadow; SimpleCamera m_camera; @@ -86,7 +89,8 @@ struct TinyRendererVisualShapeConverterInternalData m_swHeight(START_HEIGHT), m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB), m_hasLightDirection(false), - m_hasLightColor(false) + m_hasLightColor(false), + m_hasShadow(true) { m_depthBuffer.resize(m_swWidth*m_swHeight); m_shadowBuffer.resize(m_swWidth*m_swHeight); @@ -127,6 +131,17 @@ void TinyRendererVisualShapeConverter::setLightColor(float x, float y, float z) m_data->m_hasLightColor = true; } +void TinyRendererVisualShapeConverter::setLightDistance(float dist) +{ + m_data->m_lightDistance = dist; + m_data->m_hasLightDistance = true; +} + +void TinyRendererVisualShapeConverter::setShadow(bool hasShadow) +{ + m_data->m_hasShadow = hasShadow; +} + void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray& verticesOut, btAlignedObjectArray& indicesOut, btAlignedObjectArray& texturesOut, b3VisualShapeData& visualShapeOut) { @@ -721,44 +736,51 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo } float lightDistance = 2.0; - - for (int n=0;nm_swRenderInstances.size();n++) + if (m_data->m_hasLightDistance) { - TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n); - if (0==visualArrayPtr) - continue;//can this ever happen? - TinyRendererObjectArray* visualArray = *visualArrayPtr; - - btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(n); - - - const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer(); - - for (int v=0;vm_renderObjects.size();v++) - { - - TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v]; - - - //sync the object transform - const btTransform& tr = colObj->getWorldTransform(); - tr.getOpenGLMatrix(modelMat); + lightDistance = m_data->m_hasLightDistance; + } - for (int i=0;i<4;i++) + if (m_data->m_hasShadow) + { + for (int n=0;nm_swRenderInstances.size();n++) + { + TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n); + if (0==visualArrayPtr) + continue;//can this ever happen? + TinyRendererObjectArray* visualArray = *visualArrayPtr; + + btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(n); + + + const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer(); + + for (int v=0;vm_renderObjects.size();v++) { - for (int j=0;j<4;j++) + + TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v]; + + + //sync the object transform + const btTransform& tr = colObj->getWorldTransform(); + tr.getOpenGLMatrix(modelMat); + + for (int i=0;i<4;i++) { - - renderObj->m_projectionMatrix[i][j] = projMat[i+4*j]; - renderObj->m_modelMatrix[i][j] = modelMat[i+4*j]; - renderObj->m_viewMatrix[i][j] = viewMat[i+4*j]; + for (int j=0;j<4;j++) + { + + renderObj->m_projectionMatrix[i][j] = projMat[i+4*j]; + renderObj->m_modelMatrix[i][j] = modelMat[i+4*j]; + renderObj->m_viewMatrix[i][j] = viewMat[i+4*j]; + } } + renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); + renderObj->m_lightDirWorld = lightDirWorld; + renderObj->m_lightColor = lightColor; + renderObj->m_lightDistance = lightDistance; + TinyRenderer::renderObjectDepth(*renderObj); } - renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling(); - renderObj->m_lightDirWorld = lightDirWorld; - renderObj->m_lightColor = lightColor; - renderObj->m_lightDistance = lightDistance; - TinyRenderer::renderObjectDepth(*renderObj); } } diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.h b/examples/SharedMemory/TinyRendererVisualShapeConverter.h index b2ed166e6..a081b4d22 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.h +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.h @@ -34,6 +34,8 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter void setWidthAndHeight(int width, int height); void setLightDirection(float x, float y, float z); void setLightColor(float x, float y, float z); + void setLightDistance(float dist); + void setShadow(bool hasShadow); void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied); diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 592667309..9607d43c4 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -13,85 +13,6 @@ #include "LinearMath/btAlignedObjectArray.h" #include "LinearMath/btVector3.h" -struct Shader : public IShader { - - Model* m_model; - Vec3f m_light_dir_local; - Vec3f m_light_color; - Matrix& m_modelMat; - Matrix m_invModelMat; - - Matrix& m_modelView1; - Matrix& m_projectionMat; - Vec3f m_localScaling; - Vec4f m_colorRGBA; - - mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader - mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS - mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - //mat<3,3,float> ndc_tri; // triangle in normalized device coordinates - - Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& projectionMat, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA) - :m_model(model), - m_light_dir_local(light_dir_local), - m_light_color(light_color), - m_modelView1(modelView), - m_projectionMat(projectionMat), - m_modelMat(modelMat), - m_localScaling(localScaling), - m_colorRGBA(colorRGBA) - { - m_invModelMat = m_modelMat.invert_transpose(); - } - - virtual Vec4f vertex(int iface, int nthvert) { - Vec2f uv = m_model->uv(iface, nthvert); - varying_uv.set_col(nthvert, uv); - //varying_nrm.set_col(nthvert, proj<3>((m_projectionMatrix*m_modelView).invert_transpose()*embed<4>(m_model->normal(iface, nthvert), 0.f))); - varying_nrm.set_col(nthvert, proj<3>(m_invModelMat*embed<4>(m_model->normal(iface, nthvert), 0.f))); - //m_localNormal = m_model->normal(iface, nthvert); - //varying_nrm.set_col(nthvert, m_model->normal(iface, nthvert)); - Vec3f unScaledVert = m_model->vert(iface, nthvert); - - Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0], - unScaledVert[1]*m_localScaling[1], - unScaledVert[2]*m_localScaling[2]); - - Vec4f gl_Vertex = m_projectionMat*m_modelView1*embed<4>(scaledVert); - varying_tri.set_col(nthvert, gl_Vertex); - return gl_Vertex; - } - - virtual bool fragment(Vec3f bar, TGAColor &color) { - Vec3f bn = (varying_nrm*bar).normalize(); - Vec2f uv = varying_uv*bar; - - Vec3f reflection_direction = (bn * (bn * m_light_dir_local * 2.f) - m_light_dir_local).normalize(); - float specular = pow(b3Max(reflection_direction.z, 0.f), m_model->specular(uv)); - float diffuse = b3Max(0.f, bn * m_light_dir_local); - - float ambient_coefficient = 0.6; - float diffuse_coefficient = 0.35; - float specular_coefficient = 0.05; - - float intensity = ambient_coefficient + b3Min(diffuse * diffuse_coefficient + specular * specular_coefficient, 1.0f - ambient_coefficient); - - color = m_model->diffuse(uv) * intensity; - - //warning: bgra color is swapped to rgba to upload texture - color.bgra[0] *= m_colorRGBA[0]; - color.bgra[1] *= m_colorRGBA[1]; - color.bgra[2] *= m_colorRGBA[2]; - color.bgra[3] *= m_colorRGBA[3]; - - color.bgra[0] *= m_light_color[0]; - color.bgra[1] *= m_light_color[1]; - color.bgra[2] *= m_light_color[2]; - - return false; - } -}; - struct DepthShader : public IShader { Model* m_model; @@ -138,7 +59,7 @@ struct DepthShader : public IShader { } }; -struct ShadowShader : public IShader { +struct Shader : public IShader { Model* m_model; Vec3f m_light_dir_local; @@ -165,7 +86,7 @@ struct ShadowShader : public IShader { mat<4,3,float> varying_tri_light_view; mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - ShadowShader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Matrix& viewportMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray& shadowBuffer) + Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Matrix& viewportMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray& shadowBuffer) :m_model(model), m_light_dir_local(light_dir_local), m_light_color(light_color), @@ -205,7 +126,6 @@ struct ShadowShader : public IShader { int index_x = b3Max(0, b3Min(m_width-1, int(p[0]))); int index_y = b3Max(0, b3Min(m_height-1, int(p[1]))); int idx = index_x + index_y*m_width; // index in the shadowbuffer array - //int idx = indexmap[count]; float shadow = 0.8+0.2*(m_shadowBuffer[idx]<-depth+0.2); // magic coeff to avoid z-fighting Vec3f bn = (varying_nrm*bar).normalize(); @@ -412,7 +332,6 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) int height = renderData.m_rgbColorBuffer.get_height(); Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]); - Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]); float light_distance = renderData.m_lightDistance; Model* model = renderData.m_model; if (0==model) @@ -420,21 +339,18 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) renderData.m_viewportMatrix = viewport(0,0,width, height); - b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; b3AlignedObjectArray& shadowbuffer = renderData.m_shadowBuffer; - int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; + int* segmentationMaskBufferPtr = 0; - TGAImage tempFrame(width, height, TGAImage::RGB); - TGAImage& frame = renderData.m_rgbColorBuffer; + TGAImage depthFrame(width, height, TGAImage::RGB); { + // light target is set to be the origin, and the up direction is set to be vertical up. Matrix lightViewMatrix = lookat(light_dir_local*light_distance, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; - Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling, light_distance); for (int i=0; infaces(); i++) @@ -442,7 +358,7 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) for (int j=0; j<3; j++) { shader.vertex(i, j); } - triangle(shader.varying_tri, shader, tempFrame, &shadowbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + triangle(shader.varying_tri, shader, depthFrame, &shadowbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); } } @@ -466,24 +382,23 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) b3AlignedObjectArray& shadowbuffer = renderData.m_shadowBuffer; int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; - TGAImage tempFrame(width, height, TGAImage::RGB); TGAImage& frame = renderData.m_rgbColorBuffer; { + // light target is set to be the origin, and the up direction is set to be vertical up. Matrix lightViewMatrix = lookat(light_dir_local*light_distance, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0)); Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix; - Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix; Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - ShadowShader shadowShader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); + Shader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); for (int i=0; infaces(); i++) { for (int j=0; j<3; j++) { - shadowShader.vertex(i, j); + shader.vertex(i, j); } - triangle(shadowShader.varying_tri, shadowShader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); } } From 1fbd78ece55dc50664125905f606db4d77f0ea87 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Tue, 29 Nov 2016 13:19:35 -0800 Subject: [PATCH 28/39] Add shared memory API for setting shadow and light source distance. --- examples/SharedMemory/PhysicsClientC_API.cpp | 18 +++++++++++++ examples/SharedMemory/PhysicsClientC_API.h | 2 ++ .../SharedMemory/PhysicsClientExample.cpp | 27 +++++++++++++++---- .../PhysicsServerCommandProcessor.cpp | 10 +++++++ examples/SharedMemory/SharedMemoryCommands.h | 4 +++ examples/SharedMemory/SharedMemoryPublic.h | 1 + .../TinyRendererVisualShapeConverter.cpp | 2 +- 7 files changed, 58 insertions(+), 6 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 1edfc5edf..5cabfc362 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -1256,6 +1256,24 @@ void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR; } +void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + command->m_requestPixelDataArguments.m_lightDistance = lightDistance; + command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE; +} + +void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, bool hasShadow) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command); + b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA); + command->m_requestPixelDataArguments.m_hasShadow = hasShadow; + command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SHADOW; +} + void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]) { b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]); diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 023962c2a..a28a6d09f 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -98,6 +98,8 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command, void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height ); void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]); void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]); +void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance); +void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, bool hasShadow); void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer); void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index a6aa6aca3..98c59b2d5 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -89,10 +89,10 @@ protected: virtual void resetCamera() { - float dist = 1.233281; - float pitch = 193; - float yaw = 25; - float targetPos[3]={0.103042,-0.469102,0.631005};//-3,2.8,-2.5}; + float dist = 4; + float pitch = 193; + float yaw = 25; + float targetPos[3]={0,0,0.5};//-3,2.8,-2.5}; m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); } @@ -242,7 +242,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) { case CMD_LOAD_URDF: { - b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "torus/torus_with_separate_plane.urdf"); + b3SharedMemoryCommandHandle commandHandle = b3LoadUrdfCommandInit(m_physicsClientHandle, "kuka_iiwa/model.urdf"); //setting the initial position, orientation and other arguments are optional double startPosX = 0; static double startPosY = 0; @@ -481,6 +481,22 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId) } break; } + case CMD_SET_SHADOW: + { + b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle); + float viewMatrix[16]; + float projectionMatrix[16]; + m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); + m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); + + b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix); + b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight); + bool hasShadow = true; + b3RequestCameraImageSetShadow(commandHandle, hasShadow); + b3SubmitClientCommand(m_physicsClientHandle, commandHandle); + break; + } + default: { b3Error("Unknown buttonId"); @@ -556,6 +572,7 @@ void PhysicsClientExample::createButtons() createButton("Load URDF",CMD_LOAD_URDF, isTrigger); createButton("Load SDF",CMD_LOAD_SDF, isTrigger); createButton("Save World",CMD_SAVE_WORLD, isTrigger); + createButton("Set Shadow",CMD_SET_SHADOW, isTrigger); createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger); createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger); createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 373f11989..68cb5ce8b 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1425,6 +1425,16 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { m_data->m_visualConverter.setLightColor(clientCmd.m_requestPixelDataArguments.m_lightColor[0], clientCmd.m_requestPixelDataArguments.m_lightColor[1], clientCmd.m_requestPixelDataArguments.m_lightColor[2]); } + + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE) != 0) + { + m_data->m_visualConverter.setLightDistance(clientCmd.m_requestPixelDataArguments.m_lightDistance); + } + + if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SHADOW) != 0) + { + m_data->m_visualConverter.setShadow(clientCmd.m_requestPixelDataArguments.m_hasShadow); + } if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0) { diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 07c40d90c..7f9f4771b 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -140,6 +140,8 @@ struct RequestPixelDataArgs int m_pixelHeight; float m_lightDirection[3]; float m_lightColor[3]; + float m_lightDistance; + bool m_hasShadow; }; enum EnumRequestPixelDataUpdateFlags @@ -148,6 +150,8 @@ enum EnumRequestPixelDataUpdateFlags REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=2, REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=4, REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR=8, + REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE=16, + REQUEST_PIXEL_ARGS_SET_SHADOW=32, //don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h }; diff --git a/examples/SharedMemory/SharedMemoryPublic.h b/examples/SharedMemory/SharedMemoryPublic.h index d6a8e246a..c92d30141 100644 --- a/examples/SharedMemory/SharedMemoryPublic.h +++ b/examples/SharedMemory/SharedMemoryPublic.h @@ -40,6 +40,7 @@ enum EnumSharedMemoryClientCommand CMD_REQUEST_VISUAL_SHAPE_INFO, CMD_UPDATE_VISUAL_SHAPE, CMD_LOAD_TEXTURE, + CMD_SET_SHADOW, CMD_USER_DEBUG_DRAW, //don't go beyond this command! diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index a36dc4b1f..dc5d7a561 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -90,7 +90,7 @@ struct TinyRendererVisualShapeConverterInternalData m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB), m_hasLightDirection(false), m_hasLightColor(false), - m_hasShadow(true) + m_hasShadow(false) { m_depthBuffer.resize(m_swWidth*m_swHeight); m_shadowBuffer.resize(m_swWidth*m_swHeight); From b40c9cde96cb0d9e094e176671f0898d9caba5a9 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Tue, 29 Nov 2016 13:50:49 -0800 Subject: [PATCH 29/39] Add torus shadow render example. --- .../RenderingExamples/TinyRendererSetup.cpp | 42 ++++++++++++++++++- examples/TinyRenderer/our_gl.cpp | 36 ---------------- 2 files changed, 41 insertions(+), 37 deletions(-) diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index 21906d787..e8cf9f255 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -154,6 +154,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui) const char* fileName = "textured_sphere_smooth.obj"; fileName = "cube.obj"; + fileName = "torus/torus_with_plane.obj"; { @@ -342,7 +343,44 @@ void TinyRendererSetup::stepSimulation(float deltaTime) render->getActiveCamera()->getCameraViewMatrix(viewMat); render->getActiveCamera()->getCameraProjectionMatrix(projMat); - + for (int o=0;om_internalData->m_renderObjects.size();o++) + { + + const btTransform& tr = m_internalData->m_transforms[o]; + tr.getOpenGLMatrix(modelMat2); + + + for (int i=0;i<4;i++) + { + for (int j=0;j<4;j++) + { + m_internalData->m_renderObjects[o]->m_modelMatrix[i][j] = float(modelMat2[i+4*j]); + m_internalData->m_renderObjects[o]->m_viewMatrix[i][j] = viewMat[i+4*j]; + m_internalData->m_renderObjects[o]->m_projectionMatrix[i][j] = projMat[i+4*j]; + + btVector3 lightDirWorld; + switch (m_app->getUpAxis()) + { + case 1: + lightDirWorld = btVector3(-50.f,100,30); + break; + case 2: + lightDirWorld = btVector3(-50.f,30,100); + break; + default:{} + }; + + m_internalData->m_renderObjects[o]->m_lightDirWorld = lightDirWorld.normalized(); + + btVector3 lightColor(1.0,1.0,1.0); + m_internalData->m_renderObjects[o]->m_lightColor = lightColor; + + m_internalData->m_renderObjects[o]->m_lightDistance = 10.0; + + } + } + TinyRenderer::renderObjectDepth(*m_internalData->m_renderObjects[o]); + } for (int o=0;om_internalData->m_renderObjects.size();o++) { @@ -375,6 +413,8 @@ void TinyRendererSetup::stepSimulation(float deltaTime) btVector3 lightColor(1.0,1.0,1.0); m_internalData->m_renderObjects[o]->m_lightColor = lightColor; + + m_internalData->m_renderObjects[o]->m_lightDistance = 10.0; } } diff --git a/examples/TinyRenderer/our_gl.cpp b/examples/TinyRenderer/our_gl.cpp index cd38a9ab7..04863503b 100644 --- a/examples/TinyRenderer/our_gl.cpp +++ b/examples/TinyRenderer/our_gl.cpp @@ -8,18 +8,6 @@ IShader::~IShader() {} Matrix viewport(int x, int y, int w, int h) { - /* - Matrix Viewport; - Viewport = Matrix::identity(); - Viewport[0][3] = x+w/2.f; - Viewport[1][3] = y+h/2.f; - Viewport[2][3] = 1.f; - Viewport[0][0] = w/2.f; - Viewport[1][1] = h/2.f; - Viewport[2][2] = 0; - return Viewport; - */ - Matrix Viewport; Viewport = Matrix::identity(); Viewport[0][3] = x+w/2.f; @@ -29,7 +17,6 @@ Matrix viewport(int x, int y, int w, int h) Viewport[1][1] = h/2.f; Viewport[2][2] = .5f; return Viewport; - } Matrix projection(float coeff) { @@ -40,23 +27,6 @@ Matrix projection(float coeff) { } Matrix lookat(Vec3f eye, Vec3f center, Vec3f up) { - /* - Vec3f z = (eye-center).normalize(); - Vec3f x = cross(up,z).normalize(); - Vec3f y = cross(z,x).normalize(); - Matrix Minv = Matrix::identity(); - Matrix Tr = Matrix::identity(); - for (int i=0; i<3; i++) { - Minv[0][i] = x[i]; - Minv[1][i] = y[i]; - Minv[2][i] = z[i]; - Tr[i][3] = -center[i]; - } - Matrix ModelView; - ModelView = Minv*Tr; - return ModelView; - */ - Vec3f f = (center - eye).normalize(); Vec3f u = up.normalize(); Vec3f s = cross(f,u).normalize(); @@ -85,7 +55,6 @@ Matrix lookat(Vec3f eye, Vec3f center, Vec3f up) { ModelView[3][3] = 1.f; return ModelView; - } Vec3f barycentric(Vec2f A, Vec2f B, Vec2f C, Vec2f P) { @@ -113,7 +82,6 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb if (pts[0][3]<0 || pts[1][3] <0 || pts[2][3] <0) return; - mat<3,2,float> pts2; for (int i=0; i<3; i++) pts2[i] = proj<2>(pts[i]/pts[i][3]); @@ -128,15 +96,11 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb } } - - Vec2i P; TGAColor color; for (P.x=bboxmin.x; P.x<=bboxmax.x; P.x++) { for (P.y=bboxmin.y; P.y<=bboxmax.y; P.y++) { Vec3f bc_screen = barycentric(pts2[0], pts2[1], pts2[2], P); - - Vec3f bc_clip = Vec3f(bc_screen.x/pts[0][3], bc_screen.y/pts[1][3], bc_screen.z/pts[2][3]); bc_clip = bc_clip/(bc_clip.x+bc_clip.y+bc_clip.z); float frag_depth = -1*(clipc[2]*bc_clip); From 0cb2b21b5fd46bf22a762fd1a3baa0b54760ec8a Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Tue, 29 Nov 2016 14:10:07 -0800 Subject: [PATCH 30/39] Add pybullet API for shadow. --- examples/SharedMemory/PhysicsClientC_API.cpp | 2 +- examples/SharedMemory/PhysicsClientC_API.h | 2 +- examples/SharedMemory/SharedMemoryCommands.h | 2 +- examples/pybullet/pybullet.c | 15 ++++++++++----- 4 files changed, 13 insertions(+), 8 deletions(-) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 5cabfc362..dafe5880e 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -1265,7 +1265,7 @@ void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHan command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE; } -void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, bool hasShadow) +void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; b3Assert(command); diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index a28a6d09f..778e2e5b8 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -99,7 +99,7 @@ void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]); void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]); void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance); -void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, bool hasShadow); +void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow); void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer); void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData); diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index 7f9f4771b..eb91f3156 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -141,7 +141,7 @@ struct RequestPixelDataArgs float m_lightDirection[3]; float m_lightColor[3]; float m_lightDistance; - bool m_hasShadow; + int m_hasShadow; }; enum EnumRequestPixelDataUpdateFlags diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 1e3c10a38..2f36fa669 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -2209,7 +2209,7 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py /// Render an image from the current timestep of the simulation, width, height are required, other args are optional -// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3]) +// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow) static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds) { /// request an image from a simulated camera, using a software renderer. @@ -2221,6 +2221,8 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec float projectionMatrix[16]; float lightDir[3]; float lightColor[3]; + float lightDist = 10.0; + int hasShadow = 0; // inialize cmd b3SharedMemoryCommandHandle command; @@ -2232,10 +2234,10 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec command = b3InitRequestCameraImage(sm); - // set camera resolution, optionally view, projection matrix, light direction - static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", NULL }; + // set camera resolution, optionally view, projection matrix, light direction, light color, light distance, shadow + static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOO", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfi", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow)) { return NULL; } @@ -2257,6 +2259,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec b3RequestCameraImageSetLightColor(command, lightColor); } + b3RequestCameraImageSetLightDistance(command, lightDist); + + b3RequestCameraImageSetShadow(command, hasShadow); if (b3CanSubmitCommand(sm)) { @@ -3339,7 +3344,7 @@ static PyMethodDef SpamMethods[] = { { "getCameraImage",(PyCFunction)pybullet_getCameraImage, METH_VARARGS| METH_KEYWORDS, "Render an image (given the pixel resolution width, height, camera viewMatrix " - ", projectionMatrix and lightDirection), and return the " + ", projectionMatrix, lightDirection, lightColor, lightDistance, and shadow), and return the " "8-8-8bit RGB pixel data and floating point depth values" #ifdef PYBULLET_USE_NUMPY " as NumPy arrays" From 746c4d0d2a7a4525bd54c6315111df556b48c975 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Tue, 29 Nov 2016 17:08:47 -0800 Subject: [PATCH 31/39] add a tray, similar to those ones: https://research.googleblog.com/2016/03/deep-learning-for-robots-learning-from.html tune the VR demo a bit, to make it more user friendly. --- data/tray/tray.jpg | Bin 0 -> 369344 bytes data/tray/tray_textured2.mtl | 13 + data/tray/tray_textured2.obj | 255 ++++++++++++++++++ data/tray/tray_textured2.urdf | 24 ++ .../PhysicsServerCommandProcessor.cpp | 72 +++-- .../PhysicsServerCommandProcessor.h | 3 + .../SharedMemory/PhysicsServerExample.cpp | 11 +- 7 files changed, 351 insertions(+), 27 deletions(-) create mode 100644 data/tray/tray.jpg create mode 100644 data/tray/tray_textured2.mtl create mode 100644 data/tray/tray_textured2.obj create mode 100644 data/tray/tray_textured2.urdf diff --git a/data/tray/tray.jpg b/data/tray/tray.jpg new file mode 100644 index 0000000000000000000000000000000000000000..2ce198fb60344c182f2b991f937195ff6f57e778 GIT binary patch literal 369344 zcmbTdbyQnl6eb!9C6pGZVMSY@c#FG~QnW~s;O-hENC{S;&=x{yfKVh@aWC%DQV8x& zum*Ps7IgT{%$iy2{q^2Exo6#dSI*5k-_4Qz?Qh?kshdT>Lsdl;MF0T-0pR292XM0l zFjDyFXa@kOs{^@f7$Es|i7b1TO%09uW{e zBDnbrV7l$;-PwAN`q{D{4*;% zCpRy@ps=E{s=B7OuD;<<``?aEbXRxJ$mrPk#N^cU%+f#X^2+Mk`o`wLA@1n-IQd{|DIr#We$Xa62&XJR*DqkOiFF z=VTT2CGD>4v0xcIC}8r(4Q}YD5)Jqgo_dlQr(yg;;t81YniT{>gGmpB$~U|@GJ0cD zB)<}FX<>*ZJq|0-?J%R#g+{>r%CnvQfeWQ%Vfdw;|NSsD!oASvN_V-4LUGXP zviX4OTi}wq-aqt*+SvK?5v53n?p1a(k{f``_yvQn<64_MrMdhW)PM4C@V?gGbpOc> z;E!wWpGE^#iNyQS{ioKbinfGw6cSFj=jA41Gl|=-cl#{G?o#GhODPIXwj; z1g}(W*@F=j?c+zF&Bl!TtdI>=AG?l#$;R8f11) zwo*@Gz6Ym`_idcVq&%eOKA1$MDVWwE6U-66`g|$312;=0Qz|=cQu>&oa6!!d#@*$$Ms3#TQLA=9v5mOyr+%}n z3R0ngk~+NlU9@&CqGStCFTRySXxM$(X|6QSKu(dz_jGG^7MieSX4Rm>43Ap3d9(|C zP&HV=k=oZ>4W5pClj$+WLQl_>3%#z^r|KiLQ@(6Pg%T?-M|y41AXdH#svr<3`{PAj z0mWfgX(;v>i`QvtD;K14+3CWDa`{?sicJ@{LnB<=Ase9aEQ2H(i&_`x*brRQ3#{Q! z5qw=OqTKfdyrQ?s2R;6&&u)ydQK?~o8T&{a5BQIrR9c-2%)+mkSf}5 zw&d#dlcgICEAh|~<#d5DgbK5xgiTyrFGbnYDeK2KfXBOTi43Ti>t^2Ob`@@}GVWMH zK03`CfEhCHFvUZEZV(U@->|MF^r&>Se2Vj${<<|RBjlMv+cu~>)tZf7kcF_7*(-|}fb1z8&gN`X5Yi>6al3^F;0kR}uE9IchQ@cLcE zP~2%O^-aV822X93i0^89-6wubPq?8a^r>*kP>CpPUE1-_8}fO>_#?B{==XKT<(!Ib zF7~`A(K5Mn-B-SXTySf^Vls4&kG6A_km%&nv4lDvrm+qFO$5b72H6}Q5w29A_I8z@ zZqQwnPE8Np0Kz$F_{sVNeAcAw=To?aN=}0oSun%y)1mCBOyd=Mu`Rq+f?rcpsHiI- z77FLIa?NtTXjC4Q(+a4dND6YXfjwXxqbTW3Ng`eIWiLBIL*XjpIp_2Tv-^4P-A7(j zzFMq9=gPEH-yOh`Fm-e-!cf6Rl!@mFZLuWAPB(yJ=EZaG{udo55jfT*>I_O_jX8z_ z(-D4#1!hJ~!bn7p<)wl@_FVUvvYNr?I$(=M5KM;RyyV|?VoQB5uX^3Xo;Kr zDR%y6WtDAAt}a7c*hDfDr`1$ZmH-x>&G_Zg$@M^Uv9p%*hz2Px(+NDe9^N87Udt1 z>!)hCUp~>8{TOVg8ONDM^Dp&ogL16kWsl-L<{N+neC|-6ER;G^T5#%`IJ6IuT67o| zhc-$v$nJOtyBgma_PYVROcx{Fs`VvgMf{0%j5<`!Bb&@CGfIEXG4;PiVm ztIDW=>0>!%2)^<%=|9P_v%8pPXQzk2(??PuTtCF^+yrAuus48`$j6k2Novtmabd8X zto$-e8V6zdpWUsnDINPeq8C%M80fh+J_Tztc;HSQwvg;HqWH$D)tmpjIN6?(NW$*JWRD};vnGCg@u zJ5#J%WP{x0*G|BR27BQKSG4XY*nm!Z33hG(lLhm_2n}4XS2wy@F{>rqv@T_j9vgnL zr}sjE#bd4tPC+}^Ec|wF<5_J1kp0pja>Zzou#Tb`fk5X?ZjGe;%EEX#*wg*+p)O!> za!3&S=XlvI+7+~Zbb6B8m7x;1aM5I6X5>;~pZeF0?(4?w*x=5WZc8;xkgx7u41fVu z*%~hB%R75d z9IHg9VL+B$n+yFwX&rD`IJXaJg{^H}KV4(A807s9%;mVV?BjV~gzMUfYk4hhCj|70 z>Ej?x`$N?W-yC`F_9_oL`iH>zEuFw*F+RAjBBcJ?AmlgW81KDJ1^Qy%nzHUX&#L8m z_~?q=Oy4y96Fg2s4(B?1c=P}gc9fUla*WZB^+=zHRo|4+n)mW3TnaM#ym-7O?5r?i z(}Y`bEua0Ph_}J(KK}SYQ#()+q{nkcm%{kjI!C~GIyd^com~VqPk!Et##&6Uxf3)h zKEY5;t-saF14RXDldh0u8p%w?E$i7LYQDcAEW;n?US%&K$2y1MO8J>CGs}B+heH&J zqHm-(&cmy?N~6ikSp34Xs=vDWk>KlTJEa4qouBRf7TJ5H7NolPJ&!eP1F!$yJKyhQ zGhutUo$-D^B99V8x4cEJ)t5C^aCGYf!eoN)<^DT5uw$i(NUXr5vJYVzy6YvJvpsc1O&^*&(zp3GVdwAAdUr>(lo`0>4< zfoO(?+VgIbu5U_gF?CxVvWATp>Ql8fZUO^ic=rSvJM`VIV;B2bVQs&=O=ZvUU%sm_ zc`crvkH|N?DT4{R%cd_4J~e(Hm10cp@NODYkES$Jf5xz_ievGXg)11rMG!xFua>}3 zXtRaM7^mif*_<#Q0cE4b2fb+^iqoL1)`?Fz@r?l4dx#X|@+%4ZGF*YqyH7Dlinny^ zF*g8^If5wUD-#F(^8USR#aPz9sM9)@6^5r;T`A>S>7Lx`k0~F_8zrEb8G)HwI#q9C zQqs*egL_c*aQETGgS6D^)Q$d&vlM%2ImT9bO$6_~HCtJ>;4i^_5<83J)z9O$w+_q1 zm=}++C6DhQE=wBg*;lT(Y*MYiaOI@XmmlZ#X0m;p3w?bdzsgdG8^z^WlZtwlpn&;t}d1HWR}m^;x6+^O#C4{y*%`OjP6mRr zLuDoy_vtQFIy|y^RCx<0`sO3|nOAWzsblvYbTtU1L@2d3mAo#M&S4?4?b{jXm^XgfChW?i6F4Z^tVP-G$Rjl z z@>K!TTZj-81jMG^Uzd+QJ_oJ3>-dZI04dE}Gai?0{JwPhHut@uz+@N804&i9fL}B| z^dBpog{VJQw%$U3Mzxa_BtQT4Z*Aa53{no9&9;jKu?>~-lxDtD5ZeRS9lJ8DkW| zd9oV~AE7~{iRbZrBwg?YUey0SpXl~^IrF20^+Ialqvf|wB_M65v)<$f-xwy&8NVYY z)j!Xzt{I`=z2kzP4TrXv?EFC?Fi^|U(-M)=NPmE{(1TH{a|hf2+8fK{4W0##xjG)E zc4+KO0Uj-sm`1Ev_#9quF@CyQfcmeim-Z*3x}vL7JW<43F(v#4!c%idm%u+13>92t z0!wU3b)EBagKIh_HN6NNKNbK_i_cmmN@*G!@a0N{H7DXC;UJtH-Lz*NUjNtape>lF ztg?pOwHr_#oTMaM>G{@v*f-@Ca6X>7ty+Bla(bpICeN)C`2vJ!*dcr#82ByU%!e*z zbL~=Z>7?P|5$hfaF`oi8T@&CjpUKs9G^AbF+^wZGpUFKle;c9vD69Z5<*PGG4=sa zR+KfSJ?Fk?EU5XALT5wIo0p|)mNky#B;+uEj^)8I3+0{nPak#DyN9u+zfO8SSLIIu zC2$Zqo>8f|uiWU_57QlLPi)zr9kb8FYN<{A^^bBTAR(lo`L_^vDxG(MeX<7;K|2R|8l1~*LU!uWdD|M?`I)1$aj zd$kPqoc(A59lQT^?$@lLk~o$rhtE{}8z|+<9_T8MMk_L?_rvQ+RqkfUPL zXlOXP;wdMVLHFc39v)C*ONR;x83gD;gL_{mqPfIpB>h1-5SF+b0M9|fBE1J%I{)qP z<~xzjD4gXN9)J6hSbN)=IU2h-AHO2HKNaEMnfBMDaP@q?+WjB<3DynQ0Yb>bGDPq=}sT`)ZVQ-mywDF;@Fl>aCP)y+V4J? z`h^>>c6ZT|T~j`Lk_OOYhYOJ1rvrbKczEYIGbCg2XlALV{)_55|&?o5xAc031)ghg$$8Cat%VD!)s^$?rs!}KP1 z!G-zIR+hk>sR2lLjwyyx8dxfrd0~V24K+2 zM@Yy3)!jxHvDBKVH@fvvGcPj@O2u@F z;Hp3-M%xk&s^K#|9be=zxJg_=g7P@_5qed54fVjktJBV?5tNX!FNHu(pwuP@YaIP$))Yl&THYxgsO5B_*E@gL zE#$kO)@6n@z(xc*YNqJMn-qDOm5;ql3+8(5=_1L7TV;ruK!rqXM?@ zu;^ml#YOwf4yuA@9kt*IF+$i4APz(w_#5+(r?{1ml!En`g`uU&NwQRDx#ur|g61xh z$HI$P<;&ceFT2N`_l%5V`zVu=>bA38JDy|IWoBrlI_v8FKU&gu(Pdl4g==YTPEJhL zs#(-t2-hh6pp}FJwKY8hTaen8s|=Y*HW(-za9l*?6vbhUd&M8lT3b#1RAr}%Gi|(d znaRFNX~s4#d~Pg!7Y)n+ZfTASa~lV~-WKU*>5kpwN$1oVa~Bh1tY$*`l_?|e5ar?2 z0!ETYp2P2CI$$R%7i}oO-Y{f&&OD=dUOds!GsNnNU#9Do%<3%+AmPG-VO;s``lZsUDBb< z2luN}YEP_`QR-<{@U?-d{a6WOz^&nS?Y z=UAAvQs{xmRUaHncAV4m!qCvz{dctS-7g2^jz%VL=YkFxBqAgAzON*~S9X=rC5i`r zMAY`$b0<4xfAW$m*)$4<#E9Wlq@4^FL2f^M%@fmFCnFOfPcDh?(z_5v#T81c z0eJ_^1AZDQd-`ArFL{0ed_F=#I{ztCaO6=k`+84Zs(LjYA7{FCQX8 z)8KE2j`!ZAnk>az{fMJ?VX0)XhlnhtrAp`Lx7f;ZAME=5Oy@AU_-VZ&BOfsLTWB(> zFUIqBArU&noBso2BBN~%2Z(pl>dIc5!snFVxz=t?WY&L85EI9;)Nmd3A|I60`(Y`K zT)r>_nITPyw34Ogh{^r(mvxv9o`j4FyGEe#EnrX0ks?z~hM!F%62<&weFj)Kz7T#M zHdZ3YuiktW=!ER($wCg!xp);tY)Zc!Qek@7B~To+!B`zF5{dq+p6_?)=j?Xk0lwX$ z2W|kS3nS5VWZ;*X_N#yO!TZf(o6d`}XB^bq$2R~H{V3y(8SgrEQImMynY_!!IaKP@ zHe7u0G~{}}Y{)JovUUJ11rr76Qy*9_O{5=C{CSoTldse;sr|W~lT;KM!MM2er6F?W zae4d?okRUq7}9DMO(VW3ptN*Nc^iG9c9UsA=YTKG&g}CqSr4u=Go75HqQnKC{#Gp+ zdv_UI>i;m95HV9fWH|Scv}gb_(eU#~U^*fB4X}4(2!5o*V(V+acGnZQ(jn^GGi&TV z_`&IM9~-`+tX3Kdq8uBlbgM*EHvsrAg-i1K?t^D~HwCXf3?4QT6Q%)8jtX3M0}A|H zL^O1Vhtl#i?LB|>u9EeiVHup2&1i|#R(#5td?QMsoqIOZ`1cma>($xkv88`>JY@Mh zwBJrm)y*u2KWOfBDteD({$)Fd3S4>m%cPD&V-B@wU!nvN=~khKY#>0rmVS|aJ>=NN z4BAD;YA%sp*Z%0)I`&Ja7rK0diq|aKjX);vAB2d;63y@6=N*657)}<)91^GDw8nd{ z*+O!cn)+VPfd#LFQ^j3D8F2Mkzd=Bm=Hx+cxH}@U9mmk0_9fy5AT_FUntx|ad^0$T z!SNNL*e(XSmcfu8s^0O#nQxbR&nhIY{c)C{XNH&7eD>oVE6n8;zk2msTw#&GL7Qb* zj0Tb>4%(Lk`r$)ppGR{Y-w<(5_4w@}3)q5xxCQw#paXxcuN4;2Nv8jXN_y+`mW)nr zsD&<8p_ccRq+6e*+`%+j17}Frc*+m^C|Ke;gHRLE-L6~&bOiShkg)4=9OjfM$Cj>} zhc`)E5iTNbMPc4qh=wH9cC9K}{YAy1F~h5(^}PLm`lVpLP}nIYKo3?hclzy4s=Fvt z(}l-(kNJY^d7BW^M0`NRwzOP^!a7a2z^-fY9NG!7ODD^Re{ao9aZq@`E%0jPB1`H) zBt*R$KGHil>IyJmG!AI2+1039v~LM?YKrV`e~pn^JQ1cYH&=>si!u=1DMG#$A zIxp{yUOF40(02B61~Cb8oO|e5BJGgnt#;yTWg{6?zZLEpJh(W}%Zx$b0y69Y;PVfR z@}FS`yRJF$UYlb17IA$k$eG4UoO=;sVRodL$Jm;uznWn2$#vy|43a+PS5e^9c)P{X zV({_$mc4$eNfeumEA(s5nJUt|4eQ)ENUz~7>iw4n8~P3g$Q}n_9(Xb z6DS~iaBLwH=1DEK`m}9Q=_N8=Y+>S}!1p|Ol`p-;O37GmPPC~8+_6x|;EEd5AW@~kt-1cw3S=R( z05M^xIBp9fc!Os3zZm!SS*W{QT;xWqtE*bELg|SyN<1!&f-vhX)%F0U zrr<=c6Z)h4tRGfoy>JMAEG1}|y{|V86EjfwrzQK-J%rCMTh>sh*U3-OtKa6ShJNA< z{8t?H#N(g@g&+-O+SRXij&#m<>Fsiy^b+W4!q*(dSl8H@)^hY?w|YR|$@JlMg3mbz^ zCk(uPzHZhYv4u+8>EnC%nf>O%Q6&jLB%A^rL34j2K92*zcjR^|pU zlK6`7J?s)=p{>}FWrdb(eL!jq!g=4ln7v0sQZIHZJ7{e4oX5QvBnb|OdftZRr5&m( zlXrZ+uGU!rEFulo_V*@_ie_pOXKXf3lCsL-a^EXNHl9LY`Lu(zMiJ(Z?<=@fR)sRl z(ZwXtW6OH4RPv~YB%G83*uC?nn^%7t(R_drX>mV>{01DH9o_Qx8E2=Q5^Eb1&y`wn zhO?bBJ#cxEdhtMo#-YlK0-B5bmL+I#v_W}2ylbyrl%5kv+b>-AQd4S@Y8`Xy%!#wC zKBr5c%p1uF(}=E-*%=@)Ij4ZKpfGc;a|td_>Q2u`)7G9uMEkn7naS+>U017T;9jaw zap#z)(6S(I`5@Tc|5HEATUak5KNJ$=2WDJu zb|7)-W%z4dicIdQw=pe_3BuQGpn;%xgfmrxb!Kg}ZKBPO#H+q@3iE+Nvm%pU3oIPl zPpb7e9@u~_%l*HLoewh!c)c>;nxxiJ4pn^Es%!Q%9e2eoZot&I`dVs)r-(I*Rtskn z`ca&5uF+rDsR&i6Y^n)CFGY@sP@=owXnLDZLGnG=$&IZKpK+x$uC^FSa^<6<0tw^k zt{jo7Gh)r%GHsda2c;!*@Fi5BY{`2Hxrt%LlIo^bR6t3i*a_1_ZtR4^2q$abhjKQ# zrNlrogZ<-ChY9t7o+6>oXct3YR~MVw%r>-4t7=}plYmnke&jvt;V(dCYTrT`;Y>a- zB~E}6)9CBPLUZn+<(C5Xsh#g;t`R@FbmF_#7If|PV(`oD5abvTSv#v2y8(!2y!)XQ zv@iH15j{T_wsk(LXN!+qdW-1f6YR!L3Oj_bJ`nZlyia~_HNTg%tw&?wM{0(6WUfwDC0R(l2^; zrgIv336^>T>+1C4e2i;85?-DZR5kiU-T*vi>oxwhmyM1jfB&{ST!VvA(o@`eS55}` zRS0Ay?v6x|*SDAO(<^F=#e8N)aoObwbo=0g^oM4}BVRk3wCUHfnAFCZC_Z|+J>Gmt zf{&*6gGpf1T1T4A6^61#c&sBaO3N7+b+)3Mf^-x3+yY`;ApSQ;B6v_j_k%7^Mq8=8agtB23r@VX(t!w_?{x8dt@1-K_3L z+RM%p#X?Rj2b{^4mK`s49@b}&9&8qwdpqzug`n<;9rKLx)1w)C+Z%wM{_Q*&8T2cs zl<~IP%n0056z|C{vweAEN!E)Z9=R(C7~xedC($@3Tli z+rjC=@AhxN9V*OW-dGEFaIsZeaS_R(LmD&RMg0p?zYEoR|3PMr)p~Vq z>nPuRC8(}nX2sZNI0SVYp^H~PwD+)G1CY--4~*?>Dz&og@i8qATFsx;AFX4&PD(hbU0~DVma{03F6g5#l{@B> zn9HF@j8T5Y=7(`}d;cK~dIIG?+4zbeVd^b84dj&fNUv)&WHdd8dx^>r^HUTxqg5D0bDhm zBaoJ5JRZ+ob+N#w5JV!iHJf=Z8!qRd@T4tugb&y5AduambI+5*)1-7X4t1r37kU>b zuio?mq{n?)`Tb*wy#MOeTDKPJiW|jcX=gDf@Np}7xT-07i1Sb7sci2-;V;Q;uls)A zSlHcXVfLuVidOxk|@<-M>TaB1~orDMmBwn-N{ciwVTDx=vwfA4_ z_}u+6m+=W9u)JJO!;bh*x-B|5)6wQ-p|b;hrm`|2PdDn1m3yT@!_cT%yQ10uRWw51 zM4*f;>{53;-RAf7uO7Lzkac#DO~;T zXSm|=6lq+n$KdfE9u)DbvgT8zityhai5C`xyAG^*u8yp;9#y5jk2bD_R)5u9aCl>W zd9mK|;?c=-P@T8pqn%Jng%2VJKNx-&`u@-w#0g3bSJdiiHpw!M z3sulr^<-JB(E^!$R#RNGMBc;D~p-b&+o;{GbDlY~ZWuq;=W%e!J*lV?wFjqo7zc{|@s+hSPS81w3w zjqA&UfyFip#?Cy`Zj39Kf9p8k#RgM1FZX+A2sgNOt{W2YsU-w5D9+ewWYX}>FJ`u4 z?jmlqMS8O)#k2NgrO&m|2hcemQSw&m!YW{=#hiu7pB}pbGV_7E&Kr|>QdV}#zDl1+ z?7q)o`CBq#{DT;iQF5Q(lM0VE47r3bRWhivtlmP01)vcKtlu#<3Tn(gvzyL}_+728 zW7+@rhm2{JtOAoD0!^zmz(FYN!ng{=+eKSy#bVunxq=g!5kBvy&d92;x%?qr(uMD% zjkXL^a~qR#zN2i&3bQf*K5aS15mkD&Q>+#r?DHAc3FNzm)ex8Y#)QB)%#|QY=cfWo zfeCrLcs^_0yo9I;9D3zgqhEYj6~@Yr>5>jyzhg-JcdOQo-t(@aND>Pk={`5eu<88S z(e!PE9oRpV!i;MfNj5Z?G_)CvICjw<+NSN69E3-#L1UzX337m1)g)=-AoR!@l>^ zm}adkANrx2)oNnps5Xowz3te^HI`<@E?XtwHvpaFe>yCc%G>97*_ z+!`O@i7tayQ=Ezh4#(|G<^Xa$SF;5AeM+KRJc%LciRrXkYOS)Yy(74KgX9 z&xTz5DG!tL*B#T6$u+DS?WHWKD6l}6Q1A!F2kXNR(@AZLodx~sO>5;lzTBLHN4?C1 z)Xa;&Vr5B7ilkoIN zWo*~YZmL{Yvt>^-DD_k*`FUnrul)7fgRk95DsUoR6&rQx6t{~ezjM1}-2k2yku}7v z+Sc;_316cWq1N6l@RmOQ)9t~cGVa5)$k2iWec7X1_47dt{>>SymEx1aeaNmf(HJh6rJ$AcfVa&5$x6_9VXN7P z23Ut(L)4Tkif}Zi!6echkAS}_OehNa`_VDHGma=Xwb(|H+vUj%L zMXlkU4sxbq*lESsX-@m~Ut5|~yEZuF@bo^{ik0wK=c=jz2dt6SG01XNvqnfV@wVvi zB%B}Ju9T%GCBMKt)8ee;K%>BW7;7a~rTdJNmWZj4y$vlqKR;)EuGgjpr9M2Us_d1e zYaTz0ic7|NHr>tXbI%JHIS9HY#`_NZ%$xqXLBzt67A!6u8vEYYa@4^x*6FeS_9a;F zVv70rG{-Q_k#>(G(-@Chh$E?fA`L^@4DL$)9@Q>D- zv2t|W+%~>q7kMLDX|}V6(FLLWbM>-oB|?POq##h@@!~Cu*Sv0)VJ`2jb!fL|JxFeK zT{14KY&s>gcfPkw3#K%l6kERCzn%II4=KE&TlSgwZ!govgv#n}v zA?nT%F13kSZnRtQ)}B;fX5{qf3VkR#4^OFaw)4gANYUy|_omYAX!!Al&QBoUw3Vyu zO*6X07GqldHYO;6ipAGF&#GOYYb=l^CS ziyPdOSUwEql0th`2}|8yoY=okt=8{LmQMf|FI*RHR~3P;Z`Jz>a?T!6lEoS!n%W|SXKBPhXxSJ_0VDMH_7#_aY{r&qGxpdA_Pa%o zgJ;;|w697mSwFR8)o_Ve_S^7w%r*+_;^Xa!EXF+eLlyMEx;FG{>?2W*$zq95>L}!J zfe>Y5AVe@||8WVNAM|s|D2k__WA^3v2hZ#~h67zPtR_!A24HWc}(DSHw>l z9Ab5t7z{#{nhC&vVaxn&GxZqEaRJNK4CSAz;ZO<|c=awMZQKet94-zmL50j5jM7y`R&zT$j|$bPQb+X-YuatB@PUTrfr7jn`zVbVPLr1RMj zA|tJWqPa?x>E7c%E}HfwB8O0WZ|7Q(`iOvWe9LJGHO1S8UzVpSxm@DRivq1oJ3a-F zvBh1p#QdD#_~X+OK=D@{)*=hWj0wH!pT=8yEub;mpYs)gC)&k%%%Ry2;r4e6*MR zX^APik2)k~Bte9uF{Zz2AIRfq_aM*N%UzkhcA^?*Mo;VzWdj-8i zp#_>Gku9L@mku85?%CA}`7TyCGHG)xXw}lmV1P05j~;o&Z8yl9Xr|`+PZJ?f9tax3g-}hW z`uvZphwE>(Z6ifskAM9wUt`SHe->B7vECjRH(FxmKkR<8Q^nPp=>xxR9f&e~-2ctj zWXC?%tR4^F4pdpYbo0OduY(rs?ZW|MV~w*Y_elGrt4wVfva58q4Nx?t*`0#k9ndlnc}tnAmt zqjRV>j_iI}jdXFzsvDhBji2!2mX){_?yj}TOW6{A!(>2Y&tHDlM;i*5=%V^plPq@O}=8m~$HMpYl20fc=0R&no-NUz|YQ_#`XHo}B zrf-JA^dng37*ISt?)UjUfl^oES6p<156w(Xgqu8zIiDdRq<4v!)V%lb{vcy@nay1g zoXtL|{5JC=WN&BBc>l~zeSbf?nl8&jL{z$@)UYLd;At@bdmm}FuktQ9nkNs%FnN2T zcv;m~UgAyNY<9{m7SXM+Kw#dIv5_x4uc9_~K{H}j6Yf#f^@}I=E_&`&yX;rM#iT5c z=ihC%AAN`xSF{vv@*r<4KLNy3^24)Rxc!B_gL*;Srsm6^rdA(yg`4=)j4v^9UVI&+K+PWlvopH{RSyiXDLfGQxR-uLRYJRVZ)aC z+|e0#*ELHdHfge&4cfU&S`?SJ()@s^DKfI7vgkc`g zBd%mgKlkvyWP1-rYt*0iE3Txmxi#0t>f+)C5A&BDhJ$u@nh#D}NsFpfoFo$v$QGOc zyyKVj7p%IUMxX0!Sm>M6+n9)sMJ?Q~)$ip5h&0UYmC7|TlM?0T`@sF}r0)aOh=9Vd ztr#c$`#-r|WsEO;_=_kNIam2-pP^2rB_P^y*4eN3L>AOq{}5AZ2u?Ojc1Zj<`N^By z(`sA$Ad86u2`7BCGs^gmo42rZb?aAZ*aqjqBp+wdj_h!ZRbquey>nu2Yl7c zlRw6Z=M!^yQ=6~rF3Fnj(nwT+FD$xXDr6-6DxK%kuk>D56r6nGq^Kbeml3H6u8^nA@9f@POzzkHCf zc^07j!>BJ`?s-DjLu(xvI5mrY*`Bg}<}B4KRRvsC>FvzhXvu0Q(nTQ^%BM6btVfoN zJgQJESu;~LOq$L{V2;_Q;^KB4h)T^4(qUCsiaPd7b26ujBM_XDuMc}e^VUT->8FA; zS)VWmhC!p>)5~v*Xv7CJ1F%e39fdrM>4H#@T4dyc0Cp7s>K0O=l7CkCO(MgQ_|37* z(NJ+IXjH3Yy4D-4B(*E+i_1<>w72V(N;NoQ^(|N#-n9l<6n2#)kWRbLHRxDXM}L`l zeYZ_-J*r&|GUV?+BG2S%DZH%qN08nlCRv4;#k|OCu*UIJaLTCoJs77p$BJwNLDs{D zpvf_RpT$p#OdQCJ)tDze*F-)UJvfybVIAuJ*;V*cC0QL~Ps)#$H6oIJ1rylSlY$re zF&X*QTv&>_^giI?tMCmrVcO5XJD30)Rh<3$k8jFkd2uwm8SeNZ_Mf6{+-^9XFO%HH znnxaSda;ii)l6FdT zkJ`QW$>`y6amrTyZZ&gHxOKG8Pr}f;U5`Qba}etbx9872Qu9XXv6GDB!oNhdNw8h^ z^n`6PtFiauRnx2rTl0U za8^Y39_)yc7xUq_Q>%kweO$taFILzbdB+0d4nYlE;;Ktw<>hR!2ER_QJtuavtfFfX;(LY#!A^Q-mDwtT%suM9 zxPdlSf#X4%^Kml%=TsFY%0(~x!sSnsz63x?U5lSMQAe$0X^hy`nPuZpP|}hiFW!wI zMW*dT6Tw}&%kp$&Gv_ufZBr-6Z8w3Caa?EH_t_i6S5gZSdR9+Zpm5^AR#_v|M(&}U zw`igT4D6=A7qS^Rs2bZq{zb!1y?0fm&ZeQPC$-^ZORGr88Rk?v%j1)Ax23iWFvWynZk8R z5H>j)qZ+Cbf+-firbm2|z0!SaWMhZ8^{m_hUB`KKy}rIq2=0oAu3ab;ZVd2R(HV= zE(YT$EJ1<62D-^uLH49o!GiT>D2OJJ4rx!fFRtb-b6ssj;B-&$_3rpwJTbc9eAK-c za@azb=J7qSa_B<^haFybN6bnPU7I7ZqGhN-?YOQoi_*#`JN$eruy%K|;*z72!XlRA z*H}tD)EnYB50`W@h;H9=@kG6dSgMf5Z76itT6O&0at|0x>7$uLYnGKrNFx&L?A8V9 zv6qKV4Pm#h4vEeEK9$8TjHI&ma|Ktl?URdoIy&|6n3(Qp{$n&)^iOVYYK&dql`+6k z=d%Mxs*DuA(WbAerQN&uQ<;Mk<{s%OT3G}bVDsKca~ib?YE)jR-2k{>2mVc)udd}$ zJ;9rB9kWYWfIeCqAhn=`aUmgb^VI>IOZC;M#`gUyYhH=6TqoEq`5_UZCc;Hr>3m6F zd3kj$t77&;`r}Ke@9{~Q=IBwY0HsSH<}TVz6&#%tWo)oCLuoBWLxaZmyBQi`ol2L% zB_SQkh5}-8(bnd#KV{MTo)!&H3!~ZM;Br!sjiXH7=^&R2>jI`P8}e%3J7;U63w;UE z4B=`&)kA(f@)PVUlq15P!9T7w>n4em+p#+xgmjpfHyQSF{}TaRrncSE;H^={>0GOM zL)#!-A41GO_=lkq`fb!@Pf;5U7Iw&KUl;p6!I9R`X9=X#BYjUcn#ICIm_l~K40?x@_*q#c}dEe7__N1t#cvFOvdPn+>c zYH2ekYc?M43$}^>gujuQ`PNLmn=IAJ+6b1F6=V9tnNgQiIeMny*aaomtbyv^+4Y4y zw$uW)-pNW3;oc67ZX%WfcXvop@Osoi_n~9qk=lRnTh>~$gpFhd$z6vQn}kBp!lv23 z!Nm^ju93Kc=o>&3*qx$8zB0&XckXi2vBeTj%{a#;>>~M!TpBV`xcw--aFCvAr%|%? za||vyE7!an8L{H_LySEg*RN7=X7{8(82erj^QcY0J#5-ZGVpmqu!s~_C1mfN9H#a; zt_2)q-6`H(sMFpgz@!E-dVBXPm0R-yiV(#9!G_((yi~4>(plTvp0{+}eN$wTYVx6i z5JYiUwN#)K#@7a43^Pv(uBP~HC_@~eUsoP&eDUIpE?PiuIZ>{20)4=_cmoJ28|!~d z!6!@0pt6^I&^lAO_%4{fg~7z26Omiw)bEj}rVnPj6`W8zmfr*S{Xw024g*T7%YJxc zcCatu?0o#srjL3quZRtfw{HEN{JoM=p}@EQM*fLJIQu=Lwesi#XBQB86FqdS>0jkK zlny$@AD4D;CpCBfdvhSl?!gLX0pQfQqC!sV7wsdZ{uRzf5YodSTN7#IXYo7ugKh@? zqoQ>c58><^z-J$0LbrQ~T`wa8mf|6G{$YC~8FH0evn?M;elO}0GjXqcXeZp4c8n2J zow8#kfY~K{^ZPpWt7)zpQiWQ4eOI=#RNjYtVy?P!QfzRf{=(4c5zcMvyL4+;iKJvq z6}gPt>rmxOG%hQpUfN5f*mkP0A9r_aP{&B`)ERP`?qEB>kJp!_|EG2OD+@+ZVjQ`G zoU9oQebdH{(wg$H%V}|4!_g*+C;}NSMoZ1amViE z7Al*~`qkWup?W+90qx;tElvI-EA08nK~aIh{zN{Utc@vjV-KHTk~g;lo;WtAeu&qZ_*k~PgiY!xjN+fs2>BbrOWj7|T{sS9S ziuO?CO3TDchv~R|h|(-?ik;egZ2ES3=A^gU#>AKPARQX9`fs*-mfn}4hRX8rHlP4) zC+xRFByw5Ag-nzf^f#_zf=oV9^rvB&qIu44YOfI8p z&osqyO=Z9>>mV_f7kTCU37#^CX<}Q~5Y=rG-CIebUP0FD(Z=OfL9B>jt=mlN>;AFv zjgodAn2aSXCjOvbuO4J$o}k_%ttk7dsv$}{xu=^}(W*ag01DB0`%tm}MX8d`)NyV& z3nXAZOPv1dRtKBZ`DqhAKn!Fu%KL>!M$F1J$g%6xio0zYC+LgR%<#Y%HET^d^-S|l zIghUou0hGVfhjB3^kvdr8Sht=kh38ZIZnK!v470m=2ooD8|VtMCt@M|(J{MYclZyn zt=QyhPQw|25evQGBxQ7$bO`>WlxB2y zj;>J(0!oK~G*Y7*#%Lr)BOM#%7?T<>V)Xyr`+48kc%JLN&f`4pOpp+UmL!qK){`xm zgMi$^DZ%ORI*jgZ(Ti26KlbMtQ%{XSzS;18c%c91&Qmz&4R^hAZGd$cs1qmGQ>y(; z^`vw3;?f72=&4}@OypSR8RJ?%`RWcMX^`Cj&u&^a8MpM48JExk!wPe^P&+ff%mv39 zUB6=iNU9~2-U(FhmV9nIj@UWY{3Xu)uhGxQv|+|zJbX4g;p`!sCBLN$hF<%C=sIOB z*_SD$La?JIq9fmx&c+edP$DkZZtlQA&p77Nyqs&dKvdg+nIr zoHEgtsHC=VGjVQ##g8*K`y1Vl6x1CIA)m?Cy1I5)VwH2esoSYNG*zJgBdUZr+ojM2 z2toinHM&d7nf+pAl7Fx%O&wOU$Gh;eqCx%^-p4{_OPzQPKG(K*GNOia1x%MwqF=Nh z!3CgE_@r8-JUH0SuWa|#qrf=6Z(|e;%0!$@EgJ6gkv=#K06=I`j;bR=&wq(m1u27i7`h*(PajFoT=V_h+Do;zN;a!tl!*9#N0;U>|^p zxZ03(%AJ^ZLSpCKhpi3+p-L1_1#g@X?TNNzRsmSBE0!^YJayzjcJ^xsk8u1MCi**#dh40!{gP}jUXGXJ%hs5+wHyY zG+?`OHUgTw`-@`2zk)P4?ZS*nWzN5JiwwLZ`Vypcw&izT!^M&PP#mc&KK#o+?$kxP^3&syR?Y4jQ$F^PxXBiSZ=84n@ z!Fl9f6%1VK>jr+Qd4mJ|k?yb87;ss0}N6}pcK<1w8F*05K z-N`jo{Zq&OO@aILCa~sX9xDde8tc3j{U{JuDG^1IM3@bw`!cmt9f-@aGHG=W+X})7 zkco^IEOpV-z=J>0nBo*Q%NQfp()OBp`TSh9g8h{EJmT3~5$2P`GrAltXqH{#!rz_Z z$&cNG@adpiSA}t0n1NdW6Kdy{$29A1%C-5X+i`04O+$W9!49yTKY)Gy?a;h{p_^y5 z@Z*%v`kw#t+2Cv?T>=&?J4o6=U4g}O^prmCInJ2a!5X%YQ870EX~vWIyyW$ zzYn71pnL)^W}wcT`ECvLSbIr+A@4GiZm`y8IQCfVCpmf~o~fUJ6!MIuO}H)tJpRI2 zLXp%pyh1O@*FCFEZMY}*Zx2n{*Gx=>fh^HOqVWd7kc?oEBnnosD)FJ^ClN#L)>bP| zq*uzwmOR=l9z%PmgB)l|w>+e@S0rZ)s(8U$J8#<(G&02;rQ+jjk8G%tc%O^YcsfVX zWD#U33tm*qA89hkgT3tCX-1T zG=^!rnZLlN+AH+0B7=tq2(IJ`0t*Fn+JqlkQ)J$YK-5D4t9KC@{ zUClRN(hiU1dlFYYDQfvF!es+vJ0E;UoyC=6iPjFBGLiaj`cE~rou|Sht6p(0UoN!b z=p${~cnT2F24G<}o0kailysomicKd@_FmT}d`zz7ko6zt>7^BOdW?LRi;99n^QE13 zO@wlgOPu#`UcG0f-=e#z%GvEQw@mxXCxVYE5T27 z$ZTQWOH(e5=ljM@xsJ8eXzfOUpx!BnONo|F3Crau`c?@iGp7L^WAxO*JCBD=&4;f=)=vJs&f^3+vXAix!y5!zZomLBAAB9^ z(i4dlJd_1E3RJnC^Q+rE(;~aQ(+e=WYw`SSa2Nir+Y&u-iQk5e>x_ z6P?y9H*la5b8}C!D}t%B3l6FB=OR|8BK}9T@hhAtyuKyrLZf-iANQ8bs7369jBVx@ zhNV-lDBC|mmWPJpJm^b%1qn~d8`m?RztoX#H_n@g363k8wubI+ePaKCMhUs4b`aB7 z63eU}hA>+5n^zYJp@nN=sU-?>r6Wns?NA$kRdPm^Q5Af8OsSu4Mzm-gZ2Y~DX!`1j zAX|QcdivI7*zUn3@#KT^K|=?F%PGA%LcN(>HwN@~E8-!8ZSGc>*#dINrdUK%!V9-y z+alT6vv$WJ$6Y!^o;dt_A)=Hq>l@B zV%^67sCLMQwr!j<{*NeK+*tUHb?-m&8vYS+K98v0bH>2F2`4^r9BV~N`_sh2{KBNW zo*ExZcO_V`F-((coT7KjwzL%#<8Ce{r@eGT+?Gb@D*BU#8vekI{s8Wz~soodfD> z)=b#94_OsKe7JX0k(maV5P{>Wwon1@ckTkq=M0~5o{*idw2cO*>6$7JP6`ud?|W6> zP1L?!)-NL~6{YUgypzom>405#$LuLX>1^-A#|s6(=jB*PD(y=eqfzXdcaQKXyuR!^ z9T`0{ug69N`JT2~00!$U(TY_QJluIl{c(BWgO0#DU;bw=gZ;WSF(7g33e zY&t!qmC}|J#Chp|HUFJI$45Oel9OF^D~yrrWn^iyh>YOR(E;qR*d~<~g-+Kb_-b|@ z^qNvq60Z~!=q#2?Xq|`7l=}VJ{lt$^2|j3Ocen-5T8=w|p@IlcHH?2sC!f$~ z^mUGp9TKS=VEUSNO2fX(Up6nitZ+%1{mI&s#IZ zCv};`m?hHAg*#M#?xC}R-Et3&d4qSwxv*~~j8IAbM5HLRMKR}5+47F}r>f34zo^c7 zv!f;KedD%cn$x42PM>hc<==>i-yH#Gz5F9?R}M{Oovt-N3c(rWy^&&1{*U()T2LyO zx2JLV;+5$k$ll@+VM(GwADm!=)|CwT36yy7!!1FDQy!CeGbaJ9#*O#z*~m7eyu0!a z&W;X_&bY7lCPhn%G*TbEblMp~65US0+gs0Q`=jA1gBRRFu`X|ZNQ;;vu%&4~4* zq5l5-;5odZL1Sg5(sAWcpWW$}KcuE_S6|STlybxctMO?bwUi>qS4Ywo6K6*NW+^7XSIV1IFB;1EFmyIElwBekHB<-xX+VtaI zT$bJPw%`b^^2%|h*(PG!$Ut&APWon9MrkWR4pwn*=vUBd#a5Q%-&1V|GSHM^{tKVj zV*b7yXPHnkX@W-QV=HMRnHpOVAw9i`yTA{sxI!+6XH^l_dd)(zxnOED)JbLQ*Q@8I zc3QLkYpR?Ol%D2@sQCOdug^vYB*&Hh&{!y2kShb92nj=mMj zy>@~w9VgJ+SXmhuL@vj}TW+c&!go(a6+Ye(W~D$i=l25iHO{DwkWwX4B8&)rDyoaK zO0AHoDD5ir&1c7qvk5Jxg3w?G;G0y*UN?q)EBWTVJTiBY3A>EHQvw5*O6IswRR%wN zQ9op<%!W;0Gi;5@}0d0ZiAJre9)>R@A7+ zmx;WonFkZSZk`J3R_uOupyDv1ok(ua~?8%<#I>JONCU0hP)vv02Jua?U zUQsT~79+V&AAjCk8>};reM?u8`d4F7*DfC+y2w17RB3$esgU;y{we-Y!x5sb>VFute zuhWK9wlK%^m&kZ#lQ*}s%9F-9Qd`Ftv(euExfsq}=iOIxzF!|^>ASNyl2kD(nosrj z#Pm5Np5tZ3bri2#(h2A9-!rbSjwcbXX&>5X9Y4LJyXBof-J|(nQMi#@d=VX<$HG4Q z7dPjDsi(yp)$r2G4VD;$R))pp29zHh+%4@_vH|0_GElL90>3#V7?rP3Q6CZ5$2<cwdcg$V7@K;%|Pf?~9%0fI!tLl3KVGcX- z;`jOc2-8kSVDD6m{HEdL@F`ju?4#Kkm8#KYcvY}6#5}O}2U>Hd|5e*G>Dhfo!fwpaN$B{S3AB2qyJSA=8!&9`!=mjY9 zi<4Y36jGoe%M5-8pHdHbg2T5QN6l33EY^on@^a8Ikf1|eP44C$#-p@h*lr^M&m6Z%h z)|-xD@U5wmKv42ZJPWc7BuTiqY&ghn5D8hAs8OEwxP-}3xhlmrmW||)CVC~gMCii* z2y%Wgz-SQMO1s@%yUhjS)X=bqh>&gW)d-6)EZ)x0w)5-$oU$+U2f^(mrc+bL=@%e5)KeyQk3H&_A5uJ*(&sLm zrz%G8k+#zcTIHrWIiK9+a{U~6n?wKi@aqr+(h=_N)S!O8+Ys&Ae7!9KKDQySz}FQY z)`-i8=}r0^8n?G(Wo|!8n{~SKuZ(Nr&{1HW7Rvb}zNSWtse{xJG>9cYN-bpzSRcZo z@7nrCta-4@A1>qXGku5%H-X$IUJ;{d|$%5-gDsWa1M{!(dT9LUb}6iu3IR| zJ*02jAfj5&l)TelS{EM#cH8f(s5`s=spnBgC99BCOR!Nx`Jv9Va^P5)b)dckJJeHh zPyf$l(v8b{fZR@l<~XovGVI^M&V_FKW6g|**{a`>6p6*;bQQ9?P&9)59Ki4lL1wrs0g`=-p4X77+)z_vpR1Y;SXe4LbFP*pjy02hTSs514Pkn3o<+ zL%@LOy^Nj9`3c$sjn$?Ok6O9i)VWZqIAE3s*-{@e&_s&P14~3QWo; zU-B<))d5;m?Ti-Dw%fL;a9oA@pf4bim>#>DTFj?V0jVx=M=Taf9UN*u!j&9e7K427 z4U0G2(+Iu*22rbfq7)OURzE^zjZ(D*I(7}Gn%vbi#&p@XWyAqX& z8&Z(=bt%272PqR34b;Rb0khq{{*wX_-SwEHw2&&U2UwYw>QIhxdt5r0lAaRH3=sjU zxQAuEdlF<=6D+0KzI%S;hLawJwY**(bPwurRqZl*N$@LHmJ5X*!s*yzYp4p@>}?vw z?CiuPT};!)-N*jgK1A}l(KJ$Q^CRzpbLYGQXM)y+`K#UQQzK~13o$8oG#QR5C483t z$V6q8%?X}#L&jpP3MZ~mAV2zRm`IP6#Q2)EdAa_5lA{+Vbov68McZHdma@@$-ccoMv{@&^=s^%EDA@T z*9r?fFgi$=R5Jo4!GVguKlD6L!K;}c$qTH$puqoUaf z5mgIie^6M6A6&0M-KY-zi7x@8N~M$r*OaO}vAFDe; zqdZfjWhDw|CiouFrRChd?vj$W8#v4er=h9Ia#rdr=tv0g4urRuYPhTgzUD$1{hB0` zca%?mk7G;QFC$@1;`Ol|XE-^9Ae_q14??mwohhJeqpiYy80cFAhv>jf9kJN9Rp{8H zX?aQPl}c!NAc<3Gj@ApmXD9s3k2(!DgiZQ1^RYd?{|{crASnC0*S^3QUFXIuK*y0w0NK>kw z`C32O+oBJsUz0)Q?rctvp7hOo%Hu8Mc*Ft>SCdB#%PR_fwujb*b>Fct%?l12vbX5H z{q45Omf9*0oD>OUF!b>t{|0Eh=Fb&x-HlA>3y`6b5PgmePgx)oQ02F|2s#K`#pwq` zp`q9MUTYJw4lJS1^8W$S&qvi^OrG?!d6(NGm+t$Y3`ueB+{*3vlIYH?am5w_ z2W&ZS@DOu#XmBC$5^CMB*e$G+6Sa)b%KA2hRTaa3FNy(ep9mR$+n8I|W@d++Yxe;y zGo8$Cdci0tO1otl8gJFQEu)|Nbfk(&CATB1sf~zOinVgg)r%kJ{<{cD2wu)B?RGzX zM~i#gIUMe22viYV8l$T(e5+Ewp$yD-XSk-!fON*TnRGTw0LeXF)KYCEh~tDv>ULZ8 zy3i*(Yrvb7P*DmA&u^jNmDgOD3}E~Y4 z`)KKGLi{aHWG#9tN!@6BDYhdveJ@ekzvSmE8>}^v-Jp+!NZCc^t9xZ%j(6S?qxk8~ zu4&AP>HQqETw8DXe5@$<^Pr`$LYCH@C*3oqX`phR1v1M}`)!Jeo>T%NDJQm9Zgmg7! z2NB9(U8~W?dz4W@+YgqkE!@v~`mOOo0ObBihW2KVu}nZwad3tq_TZ+)TYKRiR2nI;>`}u8fVwc>f*ApIJbj;^-DSfN}%O#O?4Hci`cb zkJ{NY*8$T}abiv}P-~4?Wv(TUzdXMhvY8mhS5lelnW|dH5>#;e&P*i(%T7BUnk)TDgLq^a20mgkjsD|W+gs;5N_VgX7b@x;`Ek3C{z zAY7i1_=jkSOme%FcmIw2%#cD>FoxyGx%NL5w)+h6vA(H1G`6|^!~_x6*YCNYeyT0^ z9c)cXfpkbCXNKJ>T|G{-<%8qI^tAYSsI}v$}Q9|rs#*iW5R}%RDW(HOK zdwa_iVBq69Vm-0%Pwe=r4T%K6eg}7NEj&bw(t)iNbZ$(la`%OQ*@6ZN(xsodK#``b z!A%&Y>CKd%?(A9<7hqlEK87cul9B{xQMp5okQMo5`;(vv{^kUZKM(22Nr-Gp-YGrk zy=;>`S;^z$c_H#^FPRETY6#8J^p^5Ey!bC$x7&w5TYU;Z+|S;n zwQl%-R!40!oTwpX#}b5|wo>!r-^pIj`}Y{L(ii`3pj(lA(eFE*P}5-Q@J>6Z%w$!~ zy*Z(LVi+ZP!)^L*n@=qiEwG8h$?J{1uAc>cmJvt$U8?Q|o>m&2BoAMk<|`iRg%;AW z8UU@SM=Qx80Kz<|S2oVdK8XBUzXATTzNa(D5Ze~PbR&E}`?kwZ7ByvE(|5iPy} zL&1jD)$88v8g=|EomGylj{RkX`o-8I-BhN*-~)22@B58{&?pUY3)C^j=bOc4DBOBX zmWU+1g$mM+Hqfpvisf%CyO;y}g)|z<2@bQ?hNtO&-HkW& z!i|iazvbc;vxj;ZOmTkp+EX%*fxW@mndMgEXiwtj>Y)4kZ=7iw@JXKn4zA`OH7>X_ zk8vIZKUMq`lXTG zuP7#l9SA=JR$hSGNyze$7Vnq*{M_m7S1{gPiu$NT{@jE6*_9TfP134}9-lvsbv0_| z0(ACi_(y-3H}R+nDTsMdA4Tn)cAx=yGNJ2b*41mDHc$wYlOm1*+xI$iPNEUWDEdU6 zcj5(ygj|h5Un0Qmxff#FpLT=d#~E>^dTUb4H^lFVZpcEd>29ez>SMGef1nxBWDK-h z`uMm#6D?Z)1;^_A6E0HfDq3%AVh+eE;il z(jBx#e-*Yo4{i0DvekVx*C3VvI31eps59HnW1L=^$VekSn9>2-*orctSmJ$ec+}AJ zS~8*S4po|^K1P`b&O99*H2Y-aZ)ql`G7u5ajb43`x)rKTyo#pJptKAljyGhKHsJ6= ze{4A4wV`sR>Sd;nXsV*kgByjbv(n;$mChXxP?54nNAuZU+J!z(1KbG!m}NVY&%)P^ zZAPWNdlzNvTqb1;#}+f#1rx9%fuYsJ;@t)jd z;qK!Dqtuae8@eq8p{5uVP zEnforZ+I=_P*m{ZI*6x#T2T*`z-2`PRumxuy#UUPjsVappuQERR7WJq+TQA+&yw$+j#$TPczajiRyN~Nbq&n491b3w3DI6O z!IqYpnU1*1)h@Fjy#@ZVkgyiKTjyr{Mo28R<)fS6umF;L40+GRffrQF2`(2Ie zqYpuq_pdGJ(Rn|fRIA|6kF%FP*vWadw1a1TIztdX9dcain{yC<(l{u-Ktk%RrUB3R zbloa>q>169ZGipH)Zo)SpoP$kd*3CDZMxy*zj2trOWw~3xMAd%{1%4I|1|K?v$Kme zOuRE?T@9-)6O40qB0_XK^ID6g27l_po15peB6%IH&nQLVEsSmq<;9gNVy#fh>cK2( z(tyFBg{&j&l*V!O%I@!xAh`|`WFcS#rVDO79hQ4or+jQsd>dJ0zV^VxgM%Yk8InbN z@7)d9pmfi_(&dj}&vlgXdHtDcMj3TGy=U@927p;#nc8?B z^8DhLWJ~miKWCpo)jzo(KAp5+uEYRtGnmr1h1-~e(Ua1Y8~D0E)N#_xG5;fSNs69v zYK7+13T_0i3S3&t7#QWk=RPYw#xIhJa`Fnf?cDBc$=U0Tb`}+^DUG-f@<>DCf(VfyR7B(>Je9KBdo>8Vdn| zfvb_HH3xGszqlO}45fy5CZr&vThRnP5ku@(RnYTs2DM~$2{Z7_FME%iI=t3N>70el zzN4Ao=qj;AI8QvsfcapzUW6AxnWjweK-g&RyAQ(^qNEK(r9fShlft^}-oYaFRznJD zoRp@-NghLWrmOThx$bX#5|%f@-X@QZzMwJl@2mI)v-2!%t;~(T!q)({Un-wUaBw36 zGW;VW<3Y@rnQFG(*q~*OzsRJHoeKkv^vx4fDH%mKl9}e07R2;0I=TbpyoX}@pn8QM zT)mX!zwXPbdX~0?tdOqt-|&I{lHfw)n`oE&W6(>gkw}{}HJ(TVtgqafqIn zI!m-J?E-6uIz)<=F{~M(Y9O*^%UHGER>4TK1*ELt*lh8cC1k^MIE2+Hz*)h6^c6m6 zSX&dVV3IFo1_*&~>pql&U*4CtLUQDEM?E+ZX#9$A z4MXtQ$%s7i zOFM^tqJMsOdNJg~3m@K~9AiT-i(iR>B`@jOVP--Odh_*z->WE6U#|A}qY@wsd3=Wt zJa}!OZ20m~zQ&+gp@etvwyW?2de*q7qa!c3^EFaxiAUZDBaX|*$9yD4wndeRWG;r! zr(6=b@8+U<0uerF)^Z+l@1P3)?Zj2v6F@@d{Z@uA7uhff)mpA1?YO^KjFiiMbGETBp#1aumszxv86smHy9*Gy$O=~CwFY1 zndAe`6&&laC70~mS*sj={=K&Ww!jhIss^e6kjHsvwo)D!sq-dn1%gEuedjyu<0g} zHXI`BTn1+>zLj26q>-T2&Lg$!^(ehqEq1~yo*-L>q9z`Rd<~&`m6A_%rDv!(Zlv}% zz2uUTubNmPI0>WK8T%?L_7kGrTlxy<#ahHIX%%|+<9|eN)##0(R#Xa8FZ|}%MnG&L z9Me(eu#vmh5HY?gY=2~ai-1C)C@iZzc2gwqnbdoVkiYU^kz1AE%*PN92AqGkHR`zr7EooG5J@FJhOZN;}O$W$x~%ZqN2 zk!S_Mz5Ev0zW-ctGe>{A%tWRv2{WNFN<8X!3gZevR^hgU2cqi(vNk4BbiL z!B8$?NCLX_c@Cm?yH_h+JvEVzPp=9V(uilxe==tB09A+s0ejlj34YjKtB~Sy!os_w zV`|lM?P+|f&;YZg%YPxt4Oq)8Z#6kl%@y+Ul5+kIK7IQy|3ae-)k6LPy-PKv&#&gU zVF@~3wxn_Klvw(%_PLbZ^9&KO@a5ztnqEo_8dJj`W0PGKBoidaIqsA6!~ewx%Gg+= z;iyDghOM(L+ib@yHfV%{@MVnDiYF1%y!Y(D$NmdUU4IoNcrkovmfIvIRxbPJv12eb*Omr@Ujgdi&?2v!J1KiZHWWyZp$C zJvhyNKKao^PxSsv+MWfjfyTx&d3aletc)|o&cZYTQPb7=5%;+S#BejQtLdt;e{Jb~ zNGHkW%hYz`rF(yA!zkL6{-E%dk-B%AcqD z?)7%ygy;PhoFdh{U5GJebLGq0U`M%QS10g<;zRF{B!Ka;OG%xNL+im^nJ_L9!**7= z;5hyjq&vn52(UI}NdOR9yl4i>lY@80B1+4C`sP)yk6Xe^UVd}$fQCTixSP(HgF+uN2-ivO|4Fg* z_UTB>IwU|Bh6Pz|Y$rN}4@!iuY`Z886uR!fe^jNh3JY22?<6i)mWv(~ z^AMvgus!ia?I^6^IifUS#X1`#o&sN^q-SH2_OUo$7s1G1R-)-AM0h2%a`Kz6c3;~0 z+#Y6P3GuwmMNEHOl`GgBH@*Os4ncg4g^4IDQa@E#m3>C;$?GEZw=-!x`a=paOM9zl zIQ7_`&bWB)Rs5gypGMKa2{?&g|5RL}wWpt~$H*>N)SyBETF1b|NUu;z>DrQ{w>2Fh zHQp8Y*5`eITInNK<3CY|$v>VCwsS3tmZF28>AGEnqiY>F$LLH7MPp;sIeP+<&x=x4 zUgV!tNS7NJ^{I|Iv?D{2H6|3s==(6|G5rnTSWizRT0H8R8sJHA%qnaFjce1h z+7B#2S%nndDqZzs9eIWIA(Et&W-dLE## z+6#DF#Gx|P)3_c_7{n|B=TGVD_}w~Hyz@=B3L23p7n*|x+zb4$-Y{)t0ko&TDpX;> za;1I=E_ZgGkKTs!Oec2+{8KU64R`(@(Q=Uov5D!P1zlTvTSLS<3n?MTdM`X1;m@Z6 z)7yQ_39kWrFy6=>fhsDcm)CZ)LsG?p{j0{sqfwQSP(b}^;^)^hGRP#+%|JRk{x-(t zy`9M63X2UD=3}06S`=iVqvu%&i@{u3_RI&U8f_XwR&V$x0-1X{=(Um*ec0Tlk2D!U ze;QDEW0|2OI?E{8*SAfu__GvmH-s)>7>NJz*yT+5Z6?W5+7h_^D1!0m(kOH~9~|qV z1}JK!_m>dhIy!$CQhBAgpWb=d*TSc3J1<46Dbm)m9GOfB@sysx4+y;Pyc z`kdZ@TPJ$nA`see_|=?pSjae*(mQZFH?@Ipba_%lG~2bk)3#eQ!ii2yfb`Dle!3yK z^JSIySm?glOM4(2R&qt^0BI=UGRAP7nGP-ivCGA>M}!JQ<(@_3XORN0!^iiVFxM&8Yv7(9bnfWcrNMfRz)o+0CgIVQr= zxw6(&YU!6T)UnR5y8Z<(C5*%jzrHosZI#NQQL4xgB`3Uo2H_2IzTF@TJh;*c1~IBvQK#HUA|>IvK{Z+z zDgtkgs=-5p*L;f!R#KPHug{pIpOAp@G|Hw47|_tCd^+%174-EuT&raU-?*|o##ix_ zbLguYxeX0HkRwjd_w;7tluAB#PJ*~G(@TG8U*z+*Gd zy5)A|^NT{KDaIWE_MaxQVb;Ku#*M;}E2jP(9X37>dY_lJBNn~!__I6x%z&rg-;d64 z8<0ximBZ6{g+imd1_v@ys?^@7Qt549L*{fkTtq)jh%yl?{0=6l(4*&Py|D&J;!9PT zFE7$qPDC17Uy))ZF)LMe4Al{2##!pc9u^{96@Rh-DaHYyDcRGjxu|=^+?QEjmQ&X9 zT;0!e8}IPWbeel|;SNN)zhrCZPWJ<3A~m(h;7 zJ)<6%3$`s)(Ek2uj5Yt_QiT_;clJw&dnoJ^6vBX!KcgozCZAZ}9$8TxRC^MiVPH?$ zpOllPJLR@8iKwR|!*;&@Rr6o_Q!ev1gQ0oCu0BYNZtlO1HhbFDz5i+`Rv>F9;qlN_ z!rdxeDk9z&3hM!f|x&1q(1oR ztGl$3>jm_sPjJvqXv13cQn!b8Rh|vAuB>W}MQxA(QLRge9D1*R;O!!Rt6kd7ET?T^ zTv}e2(xw*>D?rzcAFVl9#8v5H6Qpk@5|+2Zm~Q5!Y;id}rU9DLI)7@IqQ2R^hq^Y| za=sP1WVO*;@c40GAz+=gYK3vEpriRqZ!cNyqKts}!7xek>g|q?lc4U?HnRis@#j!X z_TwD$by0Zw@CYMwekeFFS;xx8k{7MuwL69%HAw7h6Jly!U#Bg2nuf{QV={9sh2# zDErj+-6)bR&PK;ShN4FUYGjahNt}bE^S!)=^1}jeuh=t2anfi(z5~RGxQarlLHvKy zzo*k>S}_@LqT@ul&ws0p%;>Yuf6gz%h@+LYpfr@v;;PU_i{m=UM&Z=q7!!kqz;@yv zAmC_{-b$%i)j9urxBo_g#sTrq$XDUulFY|6TR$D>OZsetFYe@93LTOKdJ%yyfP-rL?&&`{mx>(csR;t$d?toYbN+q1 z&kQFk-8Ddw3ScP5SE;D!12?{`iya9=U7)j!3MR4QxHdYy1KpzPVm|r9iaxmtH{z|E zvE~B4v>|Cd$0YvQL!a0bHde+Sp}jT~Q&+e;K^=wX-<^x}rVoz#R^{%F2%-!IHoH%Y zdi_%@;}W^4)IQ!>D2euW->nVPiG*90^8fD7a6-GUcP6x-Ozjx(vlugP+blCYk)Bu0 zioL~Nk{+k*8QKQ1ez3-StIDYpe1IQ+kmY!Ay16H>dV;CJsT}rqteVnkzi+uKLMBti zQ5;xL6+Jb!2w_-kh0ZXcLZ_yxyCD;lg@n*Di&B4@=gpaS?a6sGj3B7RWgD^r64tqg zhzSjMSNV=MzQu zUpQkE9Bn{axi@t*C-Siww6%3Q7zASr+_0LrhhsD{RSxujyErVYIg51?QfSpoxQ0EA%0K?Kb<0VVmEGX0IIVmZ3I@! z?PVj>XN+Q+UAD6JY~vK>izhpdf5M}cLjM34ZfM*rQ1Hiw?ED>|L#Eir#fI$hr$zkDk(GJCU3o2;IpelfdXJ*cw)7k)&m5_Ac@^v@!ha}Gyczcw;B zBQ?xuo;S9<(artE#jS#^C#iKA%_!L;@yoDW*X_($=I-{StK;w7_1Z9hZ0OL%W1lPP(X z`My)ikihidf~UPv{i?nk{{X_x_${kh#SD{b76^446pUq_Siw6$?pOl9QVk2pXK1$Z z+9KOVzD!UcNYQ_VQ~*COf2~uCah11{t-BwEa9^@qz95_6ZISUe+S>X%i6gZ)E4EW= z0{MCFaCZPtH~?}h&}1cfC6xC*zl|5TfqF9i;5yVZD!&c8q31reBCsvc{M~)(Ii?{# zVm7Y_1N5rDVRD`u`%YeJUM0}3^xqE4J9vjpl_!eL2H9pnLY7i^U^fHbBy_JE{h~Zw zd9L_#z<=7Fa_Z}+%=gi}dp1eDD-yn>r%sp^^(LpGMS0>_Z$EP-)v8K~^8Ddn8;8FD zanM)KKejG`HQ$W%@f;FOJ+7W)V1p#a(*5)F!*uu0O42NY!n{eO-gu`*)ntzF!*Lu2 zP|eTX1OVCUJ7d!o<5ylW)wK)34f7;3*-TH8u=!}D3?4h=ewf93Mg6wRff}%7ljg@x z!-9IB{3nok;uG;4m2D9X^%1eF?FdJXXFhx4dh6S?zTTIDE$u zp!+#cGFh9AoPK2DxotOGhUA2en5!=%1nu zker7*fj{TctIgq~J-c0fqwH|SDn%-7&fv!ZhkSc<_p0bgOvizqRQ2_xgsLZ9!B26< zYoUkX&DH&y&1ZF|-YkH+VqqJV{{VHl{=bD$)ciSlq^o_R-bl|IkMOAU$j)f68FH&3 z?elcvrnB1@>nGf$>I!hCRRf_scNF(zCfKGUBqOL96bE$2Ip4h^gnK5#gY+5;h+qIiK?e?uW zhnEn_uGJ?a9E!sGRA_fA6>jPdG1nDt-&BniOpL*T?j?^W=}tOoJ9adSdDE(mpktm! z2WnP>&s7-aKbNL>_WuA1WET*+vowwObF>ZH$v(AVE>>4&+`9q$sJm2t9cgOW8Vx#n zsK!}NK*69i0ORj^8ZIFSHzAXD2pKgs zlX-^AXB|+vIGdpWY*_O&yP$W9KY^aKUoiXTEV#+)ALP5Du*WXM3?74yzpXYK8(VnydGcIH$952HSkJjVf6p}g zy**2_ZgaSB2k`Z%?GiP0-lk<rl0{jd!*^sugq38>o69dk(Xf7m&QZV@(=-fcI|IB$901 zyNR})#~*P20QKp%vaN)^XWnG!ed*;AX(W;4SCP3ObkF!vrsS>cRG!hcv5)0!V+SB+ zp;+VvgYEeT&9}8&o#YU=-z=VhXZh4WWWt}9_nUG_7{STo@c#e`q3lVg6FuJ0+_nOo zaDKk@Pb)~=ZTU}QobqZol1UM+8Cu)+M$?Z<~YVE*bv={rygbkoW=~dOU zD}2Q6Y#yCI`qeGth<;UV#ZN*vW`?#Pu3K*Jn+JkF`qZNyp>i9I8tP>(v8;>RYYsk{ z_oV*Dod?Yvio?H9bKH^q>9-K^v=$`r276P*+WC8MV`bs8F@sjFKT#yI+ZHynx8306 z9(^gTrOd3n6;s=8a4IG(EUL|z&>Vw~PtvXa_C-|v;;CS)u`@di096gRGh0GIR60aRJPij#%%eYyIyvc!ESiw zn5?gYVMLu2H|)IoKOqM-!go^kXoMSSDsg6=1H97oMR*0(?7H(n0&?90oE|`Rh-*(qpiVq_~h3{{WV7p#_}h@*IDj^%S~;%M*Okwt2%7 z+c^G|EKPV7pL21;W`U%Zr8m@CSsUcr<)4*%{xolr>Di9tEBA0Z)vJqWL$qgiqcbi) zAM^hJ>T9OS0>-6PM^nH&p7l0;2d7fGmPe2(E3}*p1?k2!Rxe`mUotu_-U^e~+LP@q z3!Ez}ND80f-Z9T2sz|7(AwFK@1I1b-w{0b@xoKp$X}I}PG{Ix;PeJchueDQtyJLtgH8%u>Sx)lqQ%EhutEd=hT{>B7l9>Y=3)< zAMmMdEpZ}XZTgOx_dRO8?4DGNtB}|npW*bSuxv*$Vt!oi$Q&MPO3vHKG;*}4fuL*5MB-2 zzRs`v#=&lR!hL;c(5xiabvP{J`FzZ?NPg;|`^W2n#d@cO^mVd=IAPqj@UAk;jo$P< z>=G^L8bWD0TyVR$mySUhQh&M!xAdpn-g!l%U*2xYk=mVia=vP=SB|*t#aD(2Cd#fD z;~}%t){BwMYG`6f)LX1=xOHN4j^{P6FPCgrW6Sc7m5Ty>`Ri0H;EKZ0RyUEPU;{t* z&N@}gHxY$p-GkQyC%+Xp=s4k3b5%Qn&_|tA;+DvWcVDrK2PHB$P$`|D) zHa@jV>-m6E%*Blz5f8fRXJTm{IfGE z9DDc0Sh2QgBWVLN1|M|unorDn^({wxHOO7XkyLG8lr2eZ6o^A^<#W{YQ3-IHakGpP z4}YawvLS(O+r4r)rOG((s60McJ9jq(@OspUh0jJ9!*vJZg^-C47 zwvIxmyW|If){_{;fuH5w<~K|nWPgo5*2~MeRbl1-01zyA{5`4mS8Hy;%IrmjYTBQ zovL%V{J-8GUuvP-LgZH-Or@A8Y;N11z4fNZ?IfAVQ|x-w5e?rd+}>F`Ljp}rCgcp? zd3$@BOf;}sMdm=x-e=5lfl-v$>Nf6X$>*W}06D7`(l%9i+DB!^DkqO=+RT1#21iO< z!-(W%iI^NW)3NVGMulU_l2@LD(MK?kxms1v`%Tx1NlOIJKaYAYSwR@xQJam*>-AL5RwJiqLZ!=QT zqFJt^+y1FrfI;unaa-*c)!n$V^}yr+$i)PTzTzMmCQ@(<9oC zQ8sA#<2+{{N*R9{IYIbo{n%{W5EZhgDWTENj6G4^xXflia)?}!!_Hum#c>d~ET66fVuCjbeV z4hd7WcMtZs?rYY(SK=E#0_Ylst#ZvBos2JWI|SYGsL8IYN!e_Dnx z!Z21tjAUhMmf_6LJ@Fiu79J+Myxv)JwkXwi6+W5o{VT#hXitdRpNIT)Z!9v)9l*BO zJk-mgw&9LO8BTLv=i{r%hO;8YB$2Ug#d0v-r#{2dzH$Agp6xt!958{YEH`A55~PC$36%D0EEj(`!3e|Pu_^*p#wjk^sYz4KM$@n`BFQmOFc_p6Xr=xzjHj_iXUF+#fvWJ?W`jW?Zaga?TfW;{xD#>p# z3j4<48uByr`c;wPtA~xIRBh3wP22P z6;@-F{RJB#7Nw1lXS;I1A5PUYaViB@<8FE2=QN-!kiw{|!rbfcK0 zhOD33Pzb_>Wyt_9Us0NhSXws6?=q(uBd@r}<@i>Glxu7`-TTA105kqYTk@6R+Q%C* zcJ%8@m^zp;*#7Ixkg_K1WYLRVYi&0;y%?hsHR3x7Byjz2Y>QG;+_Uv z?ZDbPXZg|09)(Hm+VL5i%qJOa9uHsfHBxXIU7#u${!z4J@vSRBeCBMTukeLEKD7v( zHP7zXa2e!|N3ZjsuQoz05;>P>UBiY4?+^a9Ni~#m25&d+pW&%WE6L_FH%+61_!_Bs zYvxAA9y*i7R*hJGLsrP8uHx~YiZRX!^{AA24g0XgM^lW9)z~dDwk3@>Y#G{kJa(rg zoPKL(<^W}Q&Oa(Fwld{+D9LuxChQbV*y-2t#}v~zbrJQD{m?q%v?7QZ$}( z%~pzajluc120ZrzH7LH0H(kY;`v5=vR0~!t4AI*&NH==1ZkVX9Em}152G!g1aB$T- zU&H4~{{Sr2xWi=R`e)vm1focW;k$1Pyq&bbs$ppm61dz30PRx<6fc=3)&a0b9e$N8 zvH5>4#Z9?9E&`0xeAtNlpy%ZzpRFwm=vI~h6t@e>BO;}L>PPdgy7iXQEJVZiV~|(^ zefsqFsPAs0(qSPN4aQjWgUx3yq4wr67TnvhjoIAZpRGN25fry==I&+lJjNJd)A9NW z(6QYEZdEuS_3!w1rz8T{lHpcN5O)LXQd>_1w_8^{HUY;3`%%!Ih3zsQH|LW(o0TW{ z2fw{vQ|E=+zbf^>;;KtN099SRkFlpFp&*(yDmJ@vqdXt;npP`hXsnB0|4NDAI^=PkY3_NWBa|%epWnV_-ad+ zTa{H+D6#Mke(~>4Z7O{_%YDa}^W+7{;;N`Ht0KCqV1^xY@79Sjl!>K(Dcc)cZ$CFc zanJLoCGxZFjkhsS+f{kz-`1l`VdRDRagE2GxvO@tpiQB%mEdv3OOSdEh{<&#tc}-! zft=&l{{XF8Hnsv4Rb?w7JP>(5T6MmLv3~c=e6Z=9>^}7@vdIie%+c=148-JM`})+! zR#Nj4J5Z~TcIASB>rJ}1XPr|K{J8^=4M%aS!o)(Gor~lRxgXAkxo10qu{}ra&iglxsF$_l6Xrrj@wro zK;!YGCOY00borVh-ATp)!wz$illjxPWMJ+YUZa7Ef#cdgc4S#GwBwb> zdR9TDi?Ga!g_T%gfKc7|^s2g*+>%eViB(3=OmqGe==VZ^<7n%WbCE`*o95rqlmJfN znCnU+Aca__<=QuM%@p`1L{FJzZop^m;)j#uzL*Pdk<>XX}sp-kFH6;3e6iS+TUM#rPzVHw{2z4>~-|01#FXA7K9vSeT zi(~NZ_OWkks!E97M47-0NK#wwjNtV>tERSkTaO=(@$*$*Ae}ax+`$&gr#@QcgkP%YS=4Ff-`i8N6dR!@q@k z{=07zO*WHe_c6z}A(#v<;5%fD*G$We+qZg?+}E7^R9$Oa@YjsAIrO!>(r+}GUdHAo z-6J_t3=bI~mfQhW9C8IsyOL)3+v0_viGO4}&1(5$vAFRTg)olV;!Uj6JWjq^=aa}J z0g`cF7A3UML2qq)56v8Fz8Mgq0D!|F^V0^ts`1Cdgz-O$z8v^}#2Td9euHD8MJJHN zMzh{TFv-6lB!w6Ndw|0k#dZEM{hoB68+=jKwf#YD<%3Ytg@W5OUo=u+r=AJpa9z0W zNFJ41BrQ*rejNN@@mGLuW{1O?h4epeJlX|URwE%>57E1JCj!2J_*eT++-iO@webG{ zj5OcuU1IIl8%7F5b2$fx4042=V4RGQD~I^+`!?yn3NO4nsCahj>+KWX+Ueh6k%JqF z*zNOCo7CWy=rf%5uc1CB{4DVI#r3q0TGE-N(|NU!xsGdJRSc)0I3ykk9VorUq0mgZ z5^l>gWDrjvWb;^8dfmN-v2SHF80NbT43D};1;2^9kO9Ve;8yEc$1F=PmQb(`s~{VYl#{m0ur(B(>_nAgd&o3 z+HUPyR&|U>ynseo2e)eZZ}yLl89pY-D#kXfQHem#On?w_54H~#_BOX?9nGALpCymV zvPpr|;B%kyYvRw3){Uh6ThybHIiZlqFtUTV@VO({kZ^in`&B|(ibpj)vfOD(Bf^49 za%&gL6Ora;BN-rPrEV!^Wn8w*^vBkqn@U)xUBTKs{{Ro&&!IK1T}XS07T2CNjg)SW z3f=R_IsX7XDr;{DzNKW>R>~EvGG$d>LXJuI9dq=e$v(w!ld6dPnS%h>!ydW)Yq
6efVS+(maH1Mk+lIwIa&dxHJKIa3I&OJD)^aJG? z{1d8bDH~bLj?8wH3A#ojwmr{b?@`(OAn^shsTy5rI-R@2AbEV~imLi|^!zLA?QiyF z)cjd@bN>JceTJ7bS_y%!OfThmuIL!KZiHb-!038st#dyUb!|v^K5Ki+cCl;dg{+LM zG8pGSLNUX;idif2?jm z=N$)pdsU`ncuZdcuTuIrW{OraDRAg=tLih;J@M&VS|{w|Hl$oI2G&1!|^VgXMH5HLpRzyp$egG`*Rty|4H z$7^*yQCc>RFWtF4KtA7xTF|upp1egXvZbp>8pau=oa|6>lDX<|c+W#$Oy23y$*9S1 zV!vm%jTTS~7Rfo!C*Pb_ou7x8#pTA)vjLIMdRKQS`PWDNn>FhTRQqbSnKewS zpy@sx)vx7~PS8Y>SR|1KlGSB7Dy{dnWq49>xi}t>X{+S4(*Xh17-=o=av6xOGr_kUGMY)3B zMR9R6V`@bC13mpdnf*Dd7T*RhCe~(wwF@h6B@4REnEBijYTzBmoc7|rx?MIgW##fig^qHrc93}b{sz9j)V>*M*MDe{w0nD-nOQ`JU>S+e1ZUr= z>s9W47unpzqHQL{n%*`Mf`K+M?8I~F*WRF9x77KMPWVl!UupjUXp&1vVDnlAZ!>lz zAH$Bm`Kd?2d(W{;a4(@$w@}#%a5K;ojAxFX-&*=k-{Cfr5O24Lp&{Kszyu6oPI5Et zMYqCDCNp;nS(}S{fV+}Oj=}-l6!V@4s?~;w`DRat*N%mfMOFKX{{X^IIc1DgTfl4>Eh@6KIx%~ zPbud}$%$C<6u1}!mOQiS*O0~6y;tMNLBIHJ5gawS} zu*N|iz3QSH9}QgiOICm{nPS}ZIPKW`5B{}QeJ1;IsJ5CzliQy4_a?LOiqlYz7^j-) zR56f<_JTnjITa1Z!aWyC@Y6?crrt?;HNchbLn8>_QTI?0oyEDx?V6sXbv_-E+UnBZ z%#s^~kGW<2DbcK!%zWsk`G!dg)1ObmzSf)IE|sXw8sGlr)l^7|k*hl&LNEv7YeT}H z1@w;&>u~Cp_8MlZExp3tEH@Da!zs^P?NT$4IU9h^de<&0x3Z-ww!M|?x}CT>5UE-; z>dTcktL%@AbzcGagGbSqP`c4|D?1lJ@!ecnNgOPs;1J|(=YS4z&176z%=X)sJB18C zx-D{?nfUyeq4GP*;v0BL4E+ zTwK9yffCdy05;x$$&=F`b3ErY@|hPG!yk(Jq@d$FT>I`O;F@?05B7!{r!;h5@WGlb3dKJi%V-weR_eOej>}%~*nfboQ$2Sqks<~MeSD(4i^UX9e z$u2^&h3VTP>tA4N-vF)bzRI?GU5N6zmT8mB^Bazyx#!cpV%h%88g1OI_NI}NKbfMo zQGyA`T#=AH`uo%7wxMI?*Sll#?vu>GC*;lsIHY;qK25Uuj5i}Pp1z*qzNgebW?epM z?h+e0nnsfg7*G~2e(3Mh-}0z*zuA6o?e&J~rnhT#X``Il?h4%o(~-xuM>e+|y0hj+ z((a~U5;@y;7XmT~JkuJ^dsP1bNRDx|{K1LHuc+CqEpuEqU(H%!dZ!B@R;+eZUn73h!SJSe7$y$HeB!z4wl@&=YBw#`4 zFi%089{8;H{gL#GrrFRk^Kae%_h4<{^rRmd216lc!BmDC$ zr)0P|$Q_p=x&Hw8SDHPRrqJ8k%>Gy+Cujgye4a4h!VWs~PU7V}GRDs8^6$#Gj!A_N`Is){9=v9a$771{?u{Les|()<$}Sct)bD9uu>335ZQ*SO2AbkM z*HayYr~I?)h5RaqguE+nrq646v0Cy#S)IOOpyZ4kamL;&OI(*SGcx_w+yMEp?~c@o zFtvNo)5({1&&+f8zJnC~4&Q0r^D7K7U_VN&c>$K`epdV0JG$*TAXbi>Z0uuIA1*#_ zdRDj4m$7D74a;HJ5^d81aq(_2QfvN*oD1#T&j} z{B);qy^F_s+q9Y5&5ju7oN{V=RbW;3NLz!I;GR8drM%3K^DC;32pr&c&%J3Ic3-=L z+>!hs=ZboSdy=)RN{lwS0Pc*R%;!A!sIBbxTr&Ksq=U)nQW&O`BW~KNeqoM%JJ7I6 zyK;s3Te<7jrbxb9nihI0x_OO_o}(DWSSYLamNB(X)3=Vbo9DD61dubGr>W<#{-&KJ z)x@#4nfsV`U@q^Nj(XN(j*OYLV4u5%0?5Y&K-xbVju@nI`@-Kh7zgAB+uDnAwziva zz+>hZ$z$qjdp2opnA|dT$VD8J+K)1?b~4sHF7KOg>9~*SQfd=zP0XWn9jXBSbdtZ> zQJe1`fqg2q#;H7u@~P^24wL~nWVcmk=*K;K)eDP_@-J36=no^4P|Fm`e|@=2{{RX6 zd)13%Q4)}&a3tqG^Z@8v&4_MQ$8|L%5XT?O^92C(=Q*P4<`FabamW`SamIacKDA;m zE=WFE8Ax8IuhyrO2_u1CJ*wMr$UVp5P|W^a&KR&f^&NZWg-HhG-MT(bZJIR4b% zyx!XmR0F}srB#-|JVwt6T!!7(jxkV5m^(@6K3sR~YTVL!VOMA@*x_UL;`hYSu&7VVKik(EANdJ|2OJ+ZI9YL9l-Y_vBWd{AYcsr0H;YKc}=%= zmiF)OP+T35=kNpCh=-{W zX7ayyyT6@tUlY7vAH&}S>Kg0Y&3PW5ADHn*erE-MC!b7{_*YFHa=W-w&(fp5NaZaY zin6SVRI9G#aC(A052Y?)UsICQ-$MAG;4vk{miM|Ys*0eqfUHgkO!Zj-#~BO{rxjb_ zUxeiF#kIo2u3T!KAC(vTJ~`#{n#>GvlK%i2kVjwck9zqxs$?1v(G_1gNi5{foXl*xBe7J_Xf}*=Ad(8f@E6#}XEQEsi)lzV3SN z#a}`?o8Pu|+}0Xzf#Fr1ZRhbdyZOkUb8bimLCj?Hf;!;xF<$Gcru(_L`I(66*OUJM z>&#bWSUv^o5$6na0n+e^P+B%x^58AKCTGxVp9>%^MR&8rkoIwCo z^BOczUReVF02UN>>74eZA=u3QqkcBrd?N6j)b=($cBLYuR?@AmJFx}=S?e90SNbSjDu*RjvFRCQ#uar%Y2tE`d9x;9;lAU}DBP)AT| zM3I+j%^NZ($RoeuQ0dm{@Z7-5AD5mOH*jg%UE00Jl`@^n@}m*koM)QY%#!ulVA!k5 zf&(5g$*Wd+E%W$y$h5jJ$*$jhl*Ec&NthujFgaD@pTe6Bvq;5xW1f3teQVf$7|CyC zr)j^tKWvyvvB*;hJ7XuKcJ=2SC<7wIAOiGN$~MyV|?d$Z{Z{R-MJkro7A2%LI}G6OsHK`VPLH z^=jKy(`M6RgU{O{N9Df(NcV4l=|;UxIvIX2_;D0Ep1pmg#%nJ3|j{aDD5-{y14jbK&VU+sL8cajf~1%FDV)kRf0c`Y{9(iuNe=tz%BOHsalG zn&Mx)ueDt9&>S2NI^w)v_L}kZgX3n2;n_5p?Ie;N=4iJ|4tp!VKzSr*f^sP@h*EkS z!p9xtki!cRY>E*dJ6Ttt$A8ECi@CX3ztl)zjNoMQeuMHgVRZG6P`7N7$(B$uLoql2 zF6rvk)q5sIHYS< zmN?_YgK0Z@9mDYJ^rGXjOG>hnQF!By6CAP-q;4BWZndXBhglUlWpWJhO~&JAR+mw8oDtOQ)=D<~7t$E*1W0ijoLEoimSm z^iPRj4VOmO;gd^On#oSWKJbBtN!)qouj5=@yfRs9&eKBH_Xp->Zj|Y&o0T5By*(=a zmGJXX)NC&$x3!*m?YVf>cMYc;{WG3=3hyp-i8V_|7Co`eZa!CB7)a}nP}$F1@rsVo z^=}PF`{+N=<;*5*apkuRH!nE))8-#8haF|$D~K=ro1|#ujQp&hF&+3F4OY~AEq!Vv zyo6102`!mbaKU?%+v|>*uJY4sRT*d>sMv)2BWFl zG?LlO()q#6xckg=*SBBmUXiWo8eXI>CXzWUS~!Q9ED`dpjO26kV~#zkmUg!Kv@DjI zjF)z*s@sGP#4sZzkOIf2Cm80Zm|U#j7vSclKBz73WVN@P?95(zvmBlP1HaSpsP(S| z%PzAa*%){UR#K}PlD&8bf%LB1T8cEdmr|STO!of(=I81y{WibGK_th@m{ziVciC?u2jk-%7d-!>1>073c+c=&gzExgjl zZmn-@o1}iby7P{>J$);(i@=(NmyRxDxLbH`w6u5o;~CBlGv6PN(z7sM`vs<-0KmD_J)nJ%mK#UznM53d(_%z zgWYZ#;^||JRfH2TQW-(X&ea_`=~%Y<46s}IjAUQkf;TV9zmEdF+ry^MPPV%HEaUALxl34Yp$~5?xGLB@ zjE={FoL6J7>H2Sk+8aGbMYEFX>e4w{QwqXu3CJ;R84?}YJF)4-XDZgw580-Cv3cR> zZOyw!CB@8>NBhr{YR16h3+g&^>z>u2rfF9YPV;@2cat8)*b6jdo}><+jeS)Y!=DcL zn`Wb|eVWz$sP?*sMvu!AGrFMcl{$jgpEfUrB zi`bd|ZJT0}QWUu-0H8b*jGP}sQTU6%fi$GKZA#YaM{?`2@gif4FzxisYZ)b?CQ-hJ zA8#JBpd^}xfeSp#g!?y|$qmP0xN*3zUOB4zpM$R~<}+&-GF@NXk#gkCyUubk&=5$# zz)`}0IL9^F#b)rB%QCDx0__9kQbEZ2gH~)U;E@?^q%C#k?NHYFkyQQSy>L1GGHcJH zm0@XDc&boJa^0PkGaOY)5yMVx!aF06xP)BT#~jwI!A{i%MfMQTd?{LIW?^phVHcc>zF3E zhT=E?^JPP|IOBnwpRPLOax1vuYfTPjKLjQ8yCb-YHf;HDNcba;grCdtrcL3c(JjBx z{!7Mx-US#eKln9xGiIneMzp8(ry<+v%txX3fAKXidX%3~t+%9Zz=YO8Sq< z9DT*2SQWTv+GqQmFUmhEj@tfdW|`xU%aTSsgOD-&tK2>_>Rt!&&Aq&S4e%Z3h1T9O z_Zzi$ycY+efULX$*E#1s1_f}sSB7MR_sp=vBO^Eu&h9-wr7mIe_Bd@SRk}&xm8Q<( zUnDSQ>%}a(4gJG?vvko%5m388ZNt|cyVqr=cx=9!Be=9#oUz>`F__V^cpqNBrB0TA zVh*Wge%7}5QIuv?AHqrJJ^uhIUWA@)KB=nDG|L>S*4&qf{H%LzJ-Gd9CAXgD)5u$O zRmO72KO9%1OW=X1k$ob^Zwp{ZF}0h}W4Zd(cJNG+KHGIujI!l^QT6ruRal-@dE|Z+ zjvG~PFKm)!wy5Nvf5MX6!xMbbv@$zK9`KN^82j^{JN_82Rfoe;s9!lzw;!F9fVuDZ z{W?~Y={h}zq>@{S+iwocbIv(9^c?l0sA_n$pAPj6RI4;gV;p}wJd84+vR zh4%V($nDe<&H?-dP#-Y(!@-vx6Vm0nxKp-ImMBiw`AN<(&H)(6>x%QubKw=o zjqP7hv4vJVHycI10LuN)G5OcjUOdoryUSaNe7UDH45}Ur9)yrOisCg3RI%{o!IR_= z#O|pP>%$xmtyR*|1dpCHe-BTk=>GsV-?YfZNX|lm*CcnQ%cs0+xMz1&SLu&x+-Vl- z(ixj_d7m~3>ztFHaaHdIBUJ>KXZyJ2M^Jy23vy0Y;?ZN&RyN^^ee7Tlr|Vl9DTYHL zd1G*3a!(`MAFgVQ_7Ww_G=*dxN2Wb-R;(?2nA~oVD|TFFsdCCUcTJZp^o0xCX}yoFaa6#6<0y(Xh2m;?vgci7{iW9 zq`uYPc2!5-=)BXY@1V_?Z!R?}6jW9X zv^H2{Bc6Vh92!*5Bx>%;MoGsc=AWjWfE+tYG)$5$ zB~&5ZvG(VAIsEE5Lp+Lz$~K%Fj)VUIuU4+@{?ZQJ-!DO&3Zo^?*-DY~bR>4qOj1MY zOE3C8xLygA@}s}4ESoJd-*?k@@cPs*5lHtVGOD&g&mybNzG`mC-II*}06IZy51V!L z>cev{UwW3@c_G^z4!m?VR?x_YYUQ^c=cQbP2&F8+nTq_UKdGTat;C+rJH}>a+S&P= zvii{4PQ_E^ZEWYK-5%9Fv$47_@6WedN1bJtY;4Wtj@^2mv@HT9JB3wt+m`4QZO1gW zmn|BQa8*x#e!qnmDrbL}Zd;s_kHVu_e|D|4fCrP0)~3UIm+qHz4=Sm|crAm^O#ULF zTeBLHIu1@d(zU^8mpJ)7y88Z=99@69dm17Z(&U#pnR2A@$*M0iLd@TLupX6f%`$!B z-1j4=;ZR)Lc`$j3-*=OboAamU8<4`@YUdc|xT2zNzcIrey{M(AkG@&9#-tA1eQK;L zAf8R?zF+X1{KWUoT9o2Xm+s?{?NG|+-_pGPhg62UVU!-deqMr_!*g`t@yB{(g}l#B zdgHA=H&;BdW@DdYM&tA&Roqzer1c}Hry%m2FSq^mOrGtccJk5We(IyAzG(<;``G;7 z#G;Kw*36Je<|+0S0~QkPZM%KyUI`4K55k!@THKv+P zE@5h8j`zxMA)R+Bz7E~Maz=5*UX%BjZ@b3?b*$U1I`OsWWm|~<0JHq2^CH>vnKSZ` zbBuK#g&K(X?#tlS*TwG*Yuf#_>^B}Phfuh<)O4j^EzD)Pc-OWGag305<2mBGuh@^_ zj)&sA{YzN9NiMZ567Dy*Ne0!2AeDS$JAnt-U>eu>!=URn{{R!U9T&p7PNQe3_=0tl z`$E}7a5c2B?VTC=0Aw4FaBzC!y>H>s(Kc{uvJ${6O&T zu_T5y(M7`TS1BR$6K>=q?y{bJFimxueytX-3rh>Mkt@7q_TXh(2k-}qqvE|*eFHKi+Y=_69n!5JQ8hoBtrKc!BWBVEjo4QR)}NvNWEkm&HDyifuPrqEhPPzG|uf_+FQ zy;JemgLGewUI$BS=w*`5=@RDNKsHSY##NVtgM)%Qj=d^rJ|oyi;XN~2)K=q8wbdRt zm`M@L4CiPJ2RJRpdx8%`T?~Oz;gxocxEN8#ulQ9DeOc$f4L%Rr{3`IJ&XEP=*U(*D zwZxLm7*-&tP^1np0`=m)W&NVGYa4Hg`h<2mfYgzlT5XwMvo_ESWRNqrj(OzQ+f%}< z-!m$%GFbGlgZ?{izWAx)7KitFzHkwHsKDbKbBxu;a%Hj1L2l8;%^MkGB&z|*9M!hc zzSiNFD=7J~>+Sm1ZLCdiC~fYt7RUf_)u^|kZNfdu*gW*X6|7dbGcD;-A2vA3?U`J6 z#&CN5E9f7DUJD1p+CB7sO~fxG*9^BY?$~#g484vRWFFZbmGk^eWHGkgvo6t*?a2bZ ztoTJ`A@EL>438m(OF-~sebp?)r`IH!3XbI;82l~Ot}oljv7YKrE6!!M#F8NX5?49o zbMyx|#d+qr;EhJ#QoOOV6I>vEt04gA2Lxwp0n~9{QRrGV!O|nX60{8kEMtqgA@Vdikd1xt0o6cl`$ZGGdt9z-zP+0D5_M5@H@UOJKY zLC;fKWA>i$M}scbeP_cru-d{^=8iTJVFq_G93DG$uXEJA5vpBF<>`7}n`icPRYM>E zD(9RpKym9@vHr~3MyX(RElH!*Z={e)Ug7>!E0e;Hx-v74LHsGpR0oIY-?vADZmvAFSj)~7QtlHLL>e9xV& zorc})qXE=p{v*=4-78HOEgJbtxrb8QNXg?r%C&E_yImzz!6ONqm*4Wq6L%hkYgeiz z9gd~oi8RTr%*zeLw~_hrTqp_W6Wn0qIXS?q-WHPAMxI-JKua9AM2M~}pLh$-MnBr% z5$#yM5WKgxb%Rm6l50rN%^Rj)b^#;>&m8vP=DObnY1aNG@g1$?Gk>9^dtNDlX#Q2f zDn9T4_dp20ZsVTaO+lg7$E$zBHQ?pY#f`1Tk*p6k_0d8!%s${&9H~_#ob@9jux$K4 zV`pKgG`daQ`puZFUOS>z+<*wl0OvgX*vA;a>sGX{6~m`R_G272&AWZF$}tJc5rR)D z*Z}9XUh%AYm7JSnSmA+}ahlpd>gs-GA<$ug$Q+FI?@O7XdYo*xdbXi`eRU+88sP+U zD}26r0~tL1;s+MM&l zSo!Lvi|@v+7DcY1miWLkoi+5@R!5CvqO1( znC#%Qk>JdLvb5RdGs*h#j2gG8co%G1P?18&(KOPke9;CZ{{XA{fDc}kwc`&4YM0tB zk8KH>-tOK(_J);;3!}6JZsR!M`qz2jj{@o*BbUlpVOz^&LdWi^D(57xLOAW$t|~pI zw<+v!o(t3O(^0y!iWo6*fteV6&@yqJ{+{*F+-i3b_3ct=aV(r#{{vbvSc%zwYOXGDCj zLZ!|adyZ)4xFmEwIc*nS)3nPw6`EU^*+kLB07i~JH+07K><@FAtiKK~t?i+>@ci-J zSwuwhK{5oG6M(^#@Kj)&jN-1?cpbb?tV3qabrQ&hCM|%`5HdMZLw*(9X}%Nw&C}L9 zS+1tHw1lSV8|Jy-oQA;UdU^_%uq1h&rK87oms)&K&1b4`^1&jKu7iw@{P2IRN8xV_ z!=~x0{g*Ra-Cd-X?y!5J&Ye;Vm^tNY6)wbU%;-7`kWVY#&oBtUr#4>$t@ zkF8eK?)05it+fm5S*>TfQpnJ!?jv;js@?fN#D5=JH47Y%jQlSio{{O70axsCd5?7> zoxW>lDV*{^1D?E}TEWnDxO5kj?G}wRk?m_wEN+RPcP%GBE*GYI*REUWwt9btlIvQ6 z;_B&#m{v!4R`+vsBOIQ3gOV{*>Hh!-Ej)MOYpbm+TE`@XmfGGqky%)B%6D}jbjkW= zt6^E*=MiC}+umxebjspc6|Nklf!UPjb8>nA0PEJIo(a%yJWFj2g~ifvtvq*!%4Opu zsXo01dFRs< zLp{2XK4KM-&&;C)at}ECrl9mn?w?V8=Z)^9u~t$AxCe{5(Uo}--CHR25_3kKAp{>s%Y?v`Yc3jDBa!Q9;N!;BAZ;;8FhF_%#| zu+n^)Zk=O--X$c1l1TwTKQZnr(tH{5A5GUaU$JU-w-)p2Wn!AtF=(u?Id7YuSYYFv zj+LJ^wkvZZ!Aqv=ejodGi~ET!&vixYtaiGbI)0SWeXcU8&Fp}jXSfT_Gr;D&=JIV~ z+eepDx6@xxjcyz)v7e!FW%U?`6+R9htG2rliQpn;{Zuv zxP9K;Pdrzh>w4|ol)}m_N+y!#R*2h_F{qqv&pHgx+FyDnuX2jx5fdSd|k_BBkxqg0Wt{FtPPvo)lV5Z2&x zh0aOn*(0YFq-Cj{yPPkGbeoHzb8xdX$Yne2jAaZ1k~?(3{3@q~{9UMMw@)RPmmJ^f znTl@?GEX4!>0On#gZ}`xykRxv!_RMLsYM|IAY_sDWGKg6KVQeVq|??t9`fGvRDwI0@L0nfn9O;> z8SHObc@kb~u&wEK^LS=FV0Ju?f~#T--Au@ugbyTt zXA;MSRU>kzWA*o~O)o{3OQDo+w8}nM+wOtSEsv&u8nvitP}^$BB+40~360qpz#QV7 z`hv%8G?2{OnC;v!3;jFL*ls&t(kx-oOl+~Xv`W14r02_uA;6DrFc|eLet=ZJ@Qmn| zRuFmr0BUJA#(cC=vMJ+n`GCsgoF1f98YZ0u{j*vv&7HN>xRA>;7E%rx%!&W zyAo?U{L{XtZFze!9$Q5#1cgTmhj1MB7|sCZmqF+{H__y=lv>?tu&D&dp(Bsx9Bm9q zJ6e)^hCLh?=Jz`MiCf=1RV3q?c@yL zLec71L&Wtj6w9n%$>dtD=@@|=NO>8?NEyKBKMLt0j_NymdlkB8jwcLaJg1mPrZPwb z^V6EW;hkpN;hgtvYilCjUSc(V`s8m^lquE=K*@-iaGEJiucq5f5J{{X_aJ`C`-ldVZCH*2gzapXX=D>6K7u=$8E z!9gPfKQ~^LlNJ1WosIS{6yBjz{{SB6_v`H4h~tcU)Se)7qiR;xa>;9PHM->r0Cy4r zC5RrFz&`ZW!q~#K{oTKna|0_e4HkG%PdPn4nErKE{{Un+k*Sl(X)+&;#1CQKr_}Fm zbv;Rkml~@4sv=X8dLC)9*teM*PZ60QAb{fwj(8+<`sCt{po_9zLi1cnaFWAu5X62_ zR@gw`6Z&C&Yo63R53K(H!d>=zhGD2+86fB)4b(B|k)C}$g;><}6#HVKg<+U|!57>^ z`JdLCYR@B?q>)*1;m=|ESD$=Q@a5Isk8~t6 z4a(9P9zU91bCP;cqjpW%;}3c!(BimN^7lI^82i3}e}zXX#$pmS8d*3X)u}B10OFjr zkz-azk;x={tU>BO!mD1vi8^qjDsjgZNfPu%HnSFOla}5O%rZbAb*%IrYkusF!=cXu z+O##>e>+d}5BkOBM{!hDwkOQ_$K534igsk(bsasn*)c0@by2|Q0Q9Cr(b~wyHIs8- z6P}$#Jcf>94(+EUcXG$K^Qi=@BDUrElwornv6zb@^qoDW({z>!A0o!IDk0;V=XEsMzEv`FJsJIKoc^Jg5@ttg`088((> zVU9ZUP}*6jEAux@^zZcT^{pt(Hc6M*N8TA7eE_P_>{NS`Nd%Kb*9y$4q_NKhx#^0( zW2i%KZoYD^?WC4P8<_U`3eGx&nxv~7BXTGkyI}jCwQg%OZ)xS6NZrOjC+S)0Qn@wm zvey4SCURMf7e$N?Z5rE?1mU%4MH>=Q*t z=DM%ULfum1pEq<7nv&OfQ9`HEKq@Z+U4W+s~mm6<%A=;{BeFp=vja;rRr2FlqBI znG}JE5<;v&d<=1e^5hP}s5RXB1H`)YJ`mHs*?T9KXe3D4z$H+-1sVSUXD6xPS2^OS z{7K=hYHedqn$uL$yrg#1CH>sMgMwg?a7kWvw^A?MP&aoSmcPUYYvw{c60rwXL4C zwqj%U$s_ZYGuLKupVt&}m(cScg#Q4vUYFzeVbk@Pl`(RXq&)p1*$*-c0exV_%a1DdYyoB#(aI zjeI5X4nY^hO>J3+{C`RnkIHepfsxQ0VB_Atv(P>$Y5K>+ODQc?q)!oP8#+lGjCCHo@{(>+%iUZ{C`T@p*xxy zOk#VeVQtK^5TFj({A=w$3fwCEFVbzGn${WPvw)`I@{x{l+~*`$$M)Jwe}3bY#!5BP6DwG%9nOKWev$m4q;Vo!YXe=3lP>Dn!vmwJ_|NH^J= z9q55F$tXA=A5Ye(c&5`(u+(hiu(h|ISXoTIZ#hh0{y5JSk9YAV>%ltY*09947Zx*S z&_vtBnFnef{PgKvSBkW)Li55iUtFY`JeSsOaVij1t+0T$06F<{?LkHj?escTlC&xI zi;uJt@fpvU;g3O{yz`F36nK-w5!~r_ZKqh?OwolW1ga`>SoHab=RTe5o%mPai?1Ab zBSO@py^w%t??NGnjv}-*+X*T&cPDdDJOr9~^9xKFtH|iGm-xW66`Ekbfk%it)=uYMsBixMO zW~$AZ$fIGaSj?^aiJ4>Mt1xwwammT;gVWNxABs9=lQ`0T&nns4t&%a3RHYY}Rv1zGPQ6;#k6-r3-Qopy)AK z$k6Zf9YaUgtri=rR{K_vO(l(rwxG8;jbTltO2N83Bgn;QMvOcTwEK;TT%uPd0K+rwp>XtB|S~v0qMc zk=CZbW%y@V(`+unU0BUyGeRCoCb!+UKX@Eq5$<{q&brSF=o%)ce|>8!TSpg^SM1Tq zS&)=0n@>(~I6l2=m+{w&tbA+X$gY0Lbn`|4o-pD3l1E-Tq4YoFSicRtVP~UXi(7+m zuq!U-WG++#$DzRK+)>MLy^mwlHOO?GFHE|I#tXYxaSI#S0cFE*Rxp0>IQ1B=lT6ki zw7j>t)+Ck%w{5_nJ3uXfpbky}IUa(zj}|Y6{{XWgZ8KVu;43Uxkw4YS0o}KZ?Z6m4 zIHkGqbdMgFqus<9Zo=H4-Me#SBcDN@4Q0!zerKfko5fN5K7;JC+rfQq+k|jJ!rkr_ zxIa0_=z5XbxZAw~9YRZZbi0o_J8gm$fu9(c;nT!!6kbQ_N* z%GFZpOS_LV?K3C}Wnb>DcO9d)E0^#+t^Mw{Q%UkJf<(>bw4^9(605ZOoOAC^38CDX z{5vGF-r2!Cch}LzC7n`WvPRiCP&m(SoobJU{v_%eCch?)ZE%`{+pnKBjLuc!R>&?# zU*RBRbA#RtOTZo{wZ8t(v$eXN3rTK%bY}DRx z7l(By-|TH`X12FPm$huN1B?QhIXvpnqg$!WHd6hZyIIUe0!Z2W zgySc+bH*?_ss0|>>-L}6z96@}({<|;^C~tAsN-~Jqp9q}(zAC)i$jF)ZjrA=eQT%c z4Qh~SFg&m|<8AT~9OZ%OfyPMb)2A2`>o?MCl0$6{nQLM|*x@U}Y-G~EYP%186xHvPF!QR zJbQ|-P&?>+O%49Ckha)uW(A}$++s_00|iFlHxAoap1c~N@jFA)AkuAZEN)}+94M=(VjAPt7;5b@GU=QQe{bEV`jM$4pjImG>$-5NJOR zWAH$?VR5I~!v-a=o^{(RXFt2=KU^uvJf15W4GT%u{AAjN)XfBt!zA~D5@Zv~GIusl z-N_t|`0Z7GC-}5~9by9?K$2{jHdRAVA;oGfW!dk89vVBtS zMp&m2?uT?F?#livfs}JmE#t7!x1#MxGCamcJcsh|ao?|V%?iM4P2(Siy0zDx za=O-)a8t=s4Yn-Y=Z}#|03N(!9qYUJb?{@wEoozUXQ;=mS=d}}M7FsC6^yG5#YqYZ zkT@fe-n@%S_+_s6$Hn$mml}Mr&3Qh>^R0wYTd4;u%EJnv0(11QSn-anC&G^k$Dnv) zQieOJrYm=>2imttgJ_M0KIUH^g%7eRd7QV!-vwCf`s@~3gmBs4Ex2UV?LJX6?>x$! z^y83o#d6*)_$T5&3tF2!YfPT@Ym1~KQLqMPMaJ#h*YD)^Jm6xz1L5|A-XM(dr&6()4{c>gjy;X|AmyJK=D6cHG!vK3t4& z0O?cA(+*poGP{^&I2oUOk0vPNs%(g^!+X<&G1 zQf$YT%%SlX=50?=`$VuuV;Df9*h{(DM^|rFIPL~LD?3TH(Pns7=4;sIcPf#EUoCQW zfbLJ?PAb*A9cRM-0A)y`^E|@ubffp1eX@97dBE#Y>Anop=8o1&<9Gd=ZvIsA#DYh0 z$IXn4uo>eZ9MBeLJ8^ZR{{U*Y*ysC1aNLj=%=w)`Jmq?13fa;$r;aO!vsL>=#^z9i zCN@1-XTC5x)~|(p1s{kn=KjKl?&af`_cpRZt2D|p^MzJ9BdJvcfzEIZO&x;6t0&qd zSs_OTQxk0ugU=(NJvvkM7gIjbQdnVYsZ5t$9aWi?hpQf>=hLNinis>SIz-yVm)UQI zohlD5L73gh5^W=?+q7g8io?H~PhDlE7IQ?o4IR6GtH)lyc&~idRj+(f)-|gMEv@68 z$L)}LaxJoiS-8PwP&Tp09R7!zQ;XI!L6by$T8M8ke55T-PBi->l#GqGPHM4%+2$%s31Z*{KWnqocmIbnJslT^etyi zj`kJP{5N#hM{!u7yJ6*?+lvFZ4x~0KJH+}vi)7H;JonafT_G~FLFOdSo?bRX(>-{{ zaoVG_Qt`&3X7eT_HVGL%m>sH)t)+-{ADJY|ugbf+4(6|vnIM(Fv$m$6apy;Ho1~o~ zD=MMJa2uSSKRShU%|Y!Xf=MN{w0T3cZ<5cn5Uj%-5D6Uhu8+r_ByR{coxCk>(!~TM zx-ymlw7$$?PQib<0}EB8F7mwn;zQAL3|3Ux5;Tx zmt-5VexIdj&|ZcXp?uSaYk3Q9KzD2_v)d-PuNdo-N8ue#({jls(!ak_-dXq zn?-nLknWSto2KuZ${y9u_?Xyuc6-LYfv+wmP%Oz{s~hJfn12@l@l$tlPYsKD=#j<_ zH%QEQ{Y7Wo$(a1Vn6ne||*l+XKBeNJy=!UVks6T+{fh@3VZ%FUrv~97z(aV0VkmM?^|8lQyo(! zwzQ5+t4V|nj-N5lU!@URi31q^>hve6`qbAjZnsv?-e%pqjkI~{kl{w=kMB4b1pP-` zb*1J$Zh)4OL>1&adfC%ndbA)bAb;+XPu8l-G;t8CBX9f8eJWPg;TGXl zT(q3zpS*s#{#BjZ0ye!^YZe&E;+i%^X&et4dnQ$LE6Z_70U=hY@D_a=tqX@Y9LB<%8 zeN9-jw%r=WTw^)N2Or9;UtUG0{_po^8 zZvl@+HO{5Ui0)hs$0v-{#aXXaS(#mwU;)KemKj#!?>8Xuy^cSf1hcm9y}-^7CZf5L z8+*AUk(fH11@0*p;pJhqSvH(0Va_?JY(&n7?kBm%c&h5V$3{#ZgmP)d+D4OfZ7Vi@ zZZZ$$P8*| zUb|G}gM(GByfrCUW_tF#`UDKt{%1Mb-ubYI@|?Sd*84ig2}vlSMnIvUo{{UzXGf}?P>(2+RFwL}m4;ZKUtG6xJ`BaMI z7x#_4jt>H=c!qYe(XOVBMUF@zc2{ALqyj-c!mgt#o*4Ax4%Hr`X1CgOkn|HHM#PU$ zNA;@dplESlv&Y2Qekyz?vDL2pmee=NZF}U6swGAvr);TK$4no3>|S4$w|;(=%XlBd zmcIo468qOHkIeLas_2gz!>}3;HgvJpgz^^UkbiAY2Gom^7UKm zdmT&d59Oqi1P-j^qN(5<0tcxgl8kQ0P7}wzrbje82XsxNxkboD!g8 zkCYHO9`)(^2Z;3F5?ZCkpLuI^tb$CWfrwMnBdFx#2Bp?KH)XGB?Q5u7Tisi>H%ByK z)x8h@09;p=_>=Zvw--hHJ*ix2JN{MNsc0RSid=Js}?Gk-z!&ucN)FZK#VuZ-$+-IG`JndjdQ~C<;+_J_!0pmS! z+JSGO&s+EhOJ5MjswJyOsc&W%1mNX{8-Q_wJ5-m@+*$dOEyR}$SjZKzn8#cJ?al>k zOyLUcJo=IbYMeL8a}=^$vQ6bXM#MMq4x{Ql`K9JAnjB@PgY?}4UtbXEw$iQD;3+Dm zS$=M;sz=Im!NxeRjWtP?wY^0`yirMeEWud)+_}wt>w7WNtS@B3s+#3bkVd_|9k@_C>tvz%^km?rd%&i&S6ASC^V-bUcMs;vKiVXgLd0M(7+Cn>M?rz>RBuhuie<3V{?m1Das#Bl zx?vFHvgg!vs~^}l_E$Gd*6rlXf>=q&D*pgn@;$1QM`dH1@N8C|5BRpaY>-_ol*pIQ zJZriuS;%EEwmRo({#Ddm*xcGre#33ztgSB9`8KC-e1TY}PixzYe=;SFW@brbQ;px< z&%P@{?^uS~!8gYvT(rJao13DZIsSQ~z>J-H!*(~1XFd78ncW%f)(6@E$?N>9=6@M# ztE+rQ)+V)ut=1Be0>tEyIqU9CeG%gwNheUODk|Pq)|p zENWk2jw@-Vw1#$t*anhNpEy(f;xIy33^mYOQf@?YYm~J6Q*}^R4|i zPyYafiuyarHAvYc1!Wf!e)-q8Z2l&>$u-UTb6b^Vg-+l$jpX{|^PbqQzSF>#b{`AB zw6CPOhUuTow`iqFBb`pr5tI_~$(_gMz#vsv&&<@k(;@KW7Prc+aWql~%+jv|JP^L0 zTG+AH?q-txWxoCT!{)>j2Lt(Z^yk{V*G_v8dAeqj=0+Q42)G04bKBawZwUte*1U`C zme&>+5#i9f{n9cvF(4~|I`*MQT}tM;=vJ`9;e9GgOVx`|wYgND+TmO8{{Rl;&l{IH z+ItGAW#aqoBHHRWuKw3&aTr+|NY$CtAD3x7sTk@zR$b18scBX$uwO%YrR?(q`Kn&o zj{$MX+y@5)gIKX#O&p(RnrnF%0%dgm@#8I?Lk~|%e4)*u+xRQQ7P>^&Qb})ja4+KW zJwSr#*qD?0vm#cGZxZL@D6jw2N*o#t#WhgacFvsmhiN9 zQbwcZB$&e$9Xb>E{st)-5eBJI3} z1X(2V+wY;s$S0xTAEk6Lc+u@{p}S{_O)k~~RzvbQ`AHE2jP>IO*R6R4hl*s$9SI(XlUUB0+^Ej_ zGq=+IDnE{VHE(9Nu<6%UY*i(V!QC6MEL$bA?QG+|js+Ie%Qc?a7=Qt% z@~v$LN{;&O&MCD>?d|Pkjib4FgGUJ*f_VO7up#i=G3xDQKA$h2<$td&v&(L|>xSb8 zjw`9qJQHSC&eq#d({&4-NO_qH`^yreWc$1z|gJ$J4QZVf312Ncym&pPJ>R-H#Ve}Mj40MHmtY+C_R69p8npIoz1sAtoXxF zyS-b~TwHGtPp6_F`zp}H|H3rk}UMHU1G<$@gF+Vm34~*b<0G`6Mz8@vOfUnvG z(&n7cZ#2=)^SF2%A!Nd5Ya@_GaB-T^*V^mCek&UFwxrr_mw6DxS9Z#7L!2~$PYaO1 zj>80kD=A663$e)fpW!}_@dL$ri%FCv;(-iroj}DB^0~WyGkb2|3JHLh= zA@JqD!`9Mu3yoQCV!dfl+=W|(eW6&Mxl@c|CxMF3xYhKF*E-gl{h=+hItXKUjAGtq z`JNUe6)l0iSe{hlgPeMQfwbFwM@zGs8+a}wjt7=|$;u~`%-QnT9^;_F!3R0*P~~-C z<<#fAV4fATkV?%o*Gh(KMZJ<_isKv|pa4dDo}S*AI#^Sv80d!v5}FGJwO=m+v`%LVviBK@rQ{ty-76*mgmcwGxn90)n;{Ia_FRyx2Xr| z#d)5Y@mA{V;tO0zvD%|Lt3>O)1S(I=csVDjBfWibZSbviyLqR)YdQ9=BZRN-3o4wD zO8_%~F^qFq6MoLV8S!40w-?v9S`MigGBlSudil(lA1-l?o4q>XsYp3bI`CiZ4F;uo zsaxvDUeoR_qHA*%tR8Y+KzoA4T@C=}o(~wWK=@I8ZQ+e4b%vyMZOG6irR)MZt&rpd zXF2lQpvK}`A6$9=0K~roUwj<0hg^qGhggzH4YOZKc3EIT2EpaG-3~K?eJQK)C&c!i z6aL)RGVp5K5DQo|*c2X077;t1UBHK4gbfxse`QxSgbmR0Wtglc#Vo--Ft${?Ohg ze->$)dgyxK)Fil!TwZAqU9^$u(wvRVjB>2Y$i_JRe8)7>KM+x@ZR~Xvk)2_=y7OWWJP4qb!jF^y8wGjfl21VI z4PMFPF9=)Ot-X!9G^RLGC*% zs_Rg-lFLigb$>NhS<*NRkgR{)FSLaEvp%TmDBCiAG(Pn<;dgK zx~UDz{vYV}dZ+eov8hRQ z9&9czqI+9eIRw0El4Mc1VTs$&Q<)eIVOhv14A9K{p{o)m<7qnT#@fy zz421##orff^vx>b-$S>LLz5Pk9${P9B4q<)naK-OS zEBgywb~e8AZ|&no-jGf_$ryvQ?jr*Yf=6-Fn%MDnl=?K+Hg~u^gV69C~8AxPBPPqic4t z&bp1(nH+%LY6zR6fjgX_IL}OHIq6)7#M|YMS!80&EaMOjqjMqdoOCOY2?NUt8?#bJYq%S}IuS(NR$TCv#`={{ZXL zE$$R4`My~j8$kNi^wiI(t1Q;`_Hqdm&QjS@-OsPprO70vg_Uc7Kw+$4Vqb{tu`EmT|Ucg+mx>hT+@G!+lz#i1;(Pp{K zd!uab%AWkx5xkRu^Of8F$5HjE#@N1AWoE|UbH{K009_YX)W1^YtWZS)9OqRoL?o=PGOM1}2zw124bRZ|KQPa|EnSt7?8xRQZj`^uxVE3{g97!KxyF37M z`c|Hor?X5O%R5t$O5-Q-so~P?&@7%`lvm~iw&m;Ati!B%ab^{JjobiNQJ*-1*E^dyq#b@T*sslV6n*wg4NI0LI+*HBao&+RENq<+k9K z`H1xA-lSwsKNAV0~_x_bAm81E2Q}v}} zhPSa{AIOiM8>j=0K9u-l^CD(otL|!;pX}Evt-CFq+3Si;PFW;PtM_mUf!NeL0WAA` zqNyZvMtZR6P{PX)=hv~Og>8zg!_3b(?@Fr7;C$H!rg-rydnZ3mDmg)^gF$g+o~ z-1I*5sy8O$xLjhRme0@ot+SkxIn6pR-AA{3FaxU|MM!A(9W(5gaQ-5A1M;8;VyEU9 zCy!ceryG7&IqG_hQ4IL!@ZyecfDZn2dtFu0xM0Jm`d25f{3OwJyI`wo+H}#%ZX&p| z#1cg=FeDpCQRr)|jO|bk@5+W>Er$oMKxhNUd{y92h`tVrH_$vucdf&9@=XoWA(8@k z1To;QI^g6VZfl;_d>eP*UlMo=#5%61min{J6|L`__)v?I4o4>laL1mx&INn>KG`sN z`i_<3f3yU;XT&cbXnq|@H3NNRD>dJd4)3!?B9ENshQZs@pwFnP)ICn?;(v={wD@tY zUqvWr(%r%^ZVzF!@(DTOycgjw?D2Wy%_?ijrISgwXvDU%GH+@6Z$3DDQyJ_DF zVT<8Zei_v6e%T6uB$hB^-UIJkXCwi@!R_9;zm0j*?DSbQ+vzOs>~ABtiU?#1SYsPV z?f}8(j(x=!VW&gB(I9OvNwv0VT4shIg`2C9!9S&2jaEbafvhhK>vx*WnuIr2t!E{i z-cTUrWn5)jKaFf$Zdk_F`TOzOs18>|@Rk09@k3P95@l^8Rf%Mk8M4bT{t!D3bMzI^ zUrx}((jv2MQgAw)cBzRH1N=>c$sFdY>i4nfRxLEmwiw6FBK95gK|M}m;kS?9$36_a zytsv=yR(_mk~ITx>bL{GILBOyFfsW&|IubLrn0uRgko{ulgKy!&On!fCqUS!1}1=ON1s zsBQoOvPeCMsj?2Iac!;1s(d-Wk*E7b<(yN)GdS6aRa-d(a6A1g;%k&;x^Ui9j^8%q z`@ezXk4pO6RMfu1srcs4YixZy-ACl-EW#2B}-*!_={18R)!UPu1`uA#S=V*t_ZU<(d9=l=lLQyAnB?%ca~U>xR_4YCiscVH3^ zaa~4w7yLhQ_C}gQtac+Gl%MdgwLfRS13^EAbQ5PG`&G@V`D8W~4${N`J+aBhB-h2d z6t?LF&Bee~w}lC2Jyhd8JJ;I(00Ff|({#-}jjWzUy}WG;?--C37(SeX#xw6z)TDY2 zk!f*lV;$T#*AvdOm}FU4IZ^C;0yBZ_TH5ee(5~li`GLzDP4nzKNj(RCgMnF|5Y)7r z{{RwSTZNw9JBN0UbM94(1ZnRdBy^5^LQ2EHQ_11aSi+Qhs&g0K~W1#8KSJ7TKlTX%s3w0dtBvM`J z^4;X_jiHq`fI4S6JuBw8qE)}T*x$KX-Gd+Fe28+Otet#v>&gs~6pzXL0G@t!rqKTK$3Aw#K!_Iez; zADeM=cW%tyPzsA9HaZf!fyZj29kr@$Xy%etW-IfjmeKkUJ?gBla&{f2M+;uFUVW-G zP=08ab8f~40qQ@MSkj}7h>kZWYhVM^`=5HyhfTGaeD5`+x*1=yxcN~>M$dfnz~o}8 zrIRBTMpeltXdjP0nDnajA2YSh%`VbOk-l%bFxcszQCeCLh_1Xle;n4cT|&jO%8pl| z>T%ZRSG_Y7 z#6^YAle$RcVtz+C2>FHp?~W^<@K1`h zD?9aT%MT3skxC>_KTeO#oBfO~(7^NWUZ3Hw_(%RF`I>zCGiVdeB$iw22t-g@N}z;q zEsxHgpkV$+v8kq}k?dx8kHmf%@k@VbcxFvwLh%)uGA*2ttd?lRoU%CQ-#q$b9MvBN zc>eoJ)bn+!e`lRZgRR8;>|xZWC!bDx(=;3DJ`-w}T3)fC+v~RMWR@%FTLw+TV3H{S z0H-}W6UfgMr*+}|FT}c8xbXecE}3GvxwpPxw-8Oi+R8=Pt?4KDAb zx$@+POV*&smNhc0a!lRajBeaJE+f&N)Bx(8CceB2R_t}EF*8>lbDl(m^w)*W)hBV0t1Z}L~1NUhX^ z?fBLbcHG)ATbvfX;}~x>Np$}J?705VV>uDdspMQ+$q~l^2ZZyViDr<*Z$f#= zKIXH0Q9Zwg?kwSp%$oXP%)7RL0X#6pFEWk;!2bZVfA%(|t1hQ;s0{}CGYoc3E?Oxw zks$54PTj4JI&{rm)IVnnS!HP?)TEE>@dP{6nC08ZZGeHhI622`ite;;5W{^B+3&4k zNZI(0cM@Yff={>VD`!m8W4?|?nih@Ju!zV$>iv6z*QFbYyB=ZTPk{}j$>v*LG}AF6 zYde`6?3X0vn1R`{M?bB3)vk}McyGq{T6B{(g?S{BJWk*`s+{8_2Ki3j{MWy0FRjCF zKFMcqcWNIY?d8L#9aJ9qrd@b?-&)he`mUdEHN%fCH+j6dAJ7xWKE%)$>dz$9yiutg zDQ$Htp{_KsGTX;%5nr_D<~;r7j{xTY@$FRn52zROpr9!p>e+`twXT$LaZ$iS~i@U5iU^`y(I!Khq$F|mqdkxNLUk_TP* zJptrmx&HtjLGbq9PPhKlo5UJ@uAwiM!Z5yEa&kU*+qm!n#&{l-)RpW@Jip>5mEpS! zJFoafblqb~xZC#Ik$3)(kw(juBoKa91Z{K3;1X-byi?;>@ivhRciN_{G&*?7+U*fW z*&}czNGFb&2EK;VykDqC<9MUe>~#Ctrj-1E2VjMu7o(Ka_*>!)JHr-tm(LE16{-tpmPKf1m3i{m#y(?_ zj!zvce`ub@e646<_( zOD9q{zCDF?+82#HGva>~n6w`fUFcGIa?N)xsbLdZh8Y`G;{mdAG4h;ez6~p}a~z++ zZ-qW4pI-YNw6_*g>QJ-V%>;gUkY_v<&Nx;lX$OjbjlLJ_o*YHfJjT}}S0oEtSwaQ? z>Od90$=$bb8-T&VQghhWx@%S%H;AlT#SqKl9Vbgyk|=aJaMw?Rw0{F3+ya)yK+X?J z#L&Jg>H0JmA7PVNwz`$q$+Nkb_9d7f$lU!Nqnog|?e93gz63HFY9Oaftaof23 z`8DdF5Bym-#2<`SSAHt{Hl=xWlP`d9-`&6%>MW3D&=R8aU12_#}k~BRrGGHPvVdb!Vem$91S`6JA}&Zf;1JtWv~B%B)ufiTR1o zsPwH1Zw+bs{{V+0ZBuQema} z`$9COPRQc`g20fwR~b1x^Z@j!a};6RscZ1Q+DX5(ucMPsT|tMGxAyNftE(Ok_4$yK z!sK!=c;>74o59WDt5|LH`7GkQa6HGixcN)7VN_&foOSFt^fmO&r^IRD@TAvTmF|z^ z+ptMuwuL8gAq1-|nZ^+0ggyA|1$gJhM_cQbi%8V$wW$?LT;1Mj!o=H0fC@*DH#sAd zjsW-KBT=_ux_TZ%;tvn%Ryvi_TxwSmHL@zrHLS$P8U7f-2bK+(5Tr=id-6{=&B#Zsus=wrM2Y8kBr=Lftc*@HsW=TCq#(&CHuZ^jviJ73JR& z^;-=&wF@}j&F-Vv(!#QCF)I_xsNfTWfKF?pl+R-LPZt6YGyk zUZ6}TiEY(fG>mhTQQRWOff}*TIUKO-MXIgTYRuc5@s8v1sVt&rlx0G$IAhP}PeugV za9<&$Z)*zz_Enz;`7U=19?Hg0y2x$r%^QsvO1 z)RM<#XiSb-rCewDhqg^quo7JENF$Mkc#+2k(upos$M0^EX+G#Y^`_fh%>~PC{n|3} z-jx^Btv6=ELc$;4G?MKEZDaC}!@U;qHM_Eg3>aeo_oTDb8t8oNttU=Dj+O)r<(@^x zcx~S>?NUENDV>r=+S^2b#q0k7*QsqoIC&2o{oce;9kX0bpW=@{HZzcF*U1zNk%Fwl z1+&RCJJ@%=g<0*&HB>w=OKRR`Vrr7r@Z|V-?_rD)nhDf$L z^(C+Y&rWD|uohyKgYIvp4}ZddWRU#dbW>6#jr({jUa2j%skINi6N2LKKzunv^0z-}9{k(1Vn zE#)qsF4e~eaLF`O*gi+y&4&4xZ#?j6B#$RK`KcBrdo^#F8HP%eoDtfbv2Jd-EIJzD zw^nuNQ@OXDqs)K1IR`xB8Rm^wP>)E_uJ0t=$!iPB-r+%P55QHa2b90Wex2#Ja7M_{ zwpnCTxk&j)J#$0ui1R$-!GE-uhJ0J$@3&1m>2mq;+sO^mjnT;Y+tZT0er$1roDOTY zwUaVscC>DB@|=%c*PDDr{gt#`dI@f{c-KkQREZR+Zzf~Zt1f4`?s9WV;B*=Ci+^|DwNmjGpC+}V+*-qVKACYc;yajv zmW1`=cORWW;mua^<3_MuYB(%)X`{@r#^IDUe}wnr9B0SVzhio@cTi3gF05Vr@2|}ZPp2=w-`4V;kS;A zRQDLp3FKnDuTz)6%x*iKRP3ZeHHzzHRtJ;jL=x#Cm3@YilsHv%Ny{xWNnaXOB!|6YeYNVLHxQ zMLUs+Amg{zfqE4p)S-@ItlM813V6*y;wy2g=ogWze6m8yGsq_g0~EU6nI5+B`H;sp z%&6XQS3SWLntgk%q1sM6sRUq-Hk$dad8D_wk~UIIZdHiw?f6&R9~=C;UxpqbX%whU zK2lf=x{ai9Uk|c3m;6MKNzd^b+LBnEKM{gJs zIBx5lf-#=eV%9G<IvDmta}h6c&-08Q(Rin7`fu4Z+m(@) zNf-kgWPHkfe_DmE?w;1-OMA(qn)()i6aa+l_-D60E1K~BxvXn?P0ERqON$$U3natm z5nz14`ev%v2XgoZdq!5@IC>)L>g_GdBT3ms#`b~4-B$8UM7 zn`u}>EA3}rH3{Hx$m8o?0;?=DT&&P6axBsYMEQc9=YjP1=DqvkC7e1Yp&yAYZzhiF zbXy3<@fxW)$UQoNjMsqa`n=kluXM<&_Y%B>ZW-l?>Fw)UK#2|11T4dP=PYmsBzot)L@efe6L?~EwN?Fp~ z%(oKBaK(hMw0l+z9x&PYv)7K5p%*O0WVZ?C7FF_a!zZU~VzsQ}5?L(Ue|A1xgTU`t zdS##wS^2pr$=iK{N zW6QebaJ7aj}LVxP&1@vWv=yor;1 z6X5;VUW5>FUYGHI$JU<|yl)Pzr+9YPM{lx4Y?hV;O%jkl*-?{|#~c6$IIl0$bm;`m z9H<7&pgX=?_Bs4BUZe06;+^M!?xwY~x6mS*;nrWYY7p*5F_L_ieEh1%_=g~Y*R4a} zQkBj!(_3v$B(yqwGWo{H1q z=}Y3jjJk)8{B@{mx6KW;#pKRJTX{u4D2sM7co@m+?NOm=Sd+r`GFscT*An@VI;e&s z;zljmKKASOJE{Hnspc&JAwAhP+LxS?Ri^nU3Pi zQ=G*qMlx?zZXY=LP6#>0amwiEiCw-EUuo8m*~4x2dpS3#7Yc3FRe8y7Mh~H`??CYU zI!LpBg?o3 zL!4v`XRjmF@l5eg#aoL%6KU^b6ncHEpMDev?E7*^1d)zTM;s0+Wp`ss+jHE!Cv`Tm ztL8?RA2^L-Cj^d#j(;AtwRPb{k5P@RW|H1E`K4J@NDe)Z^Xp!J@c#hBw;JY~4aLMd zba&S`8Hzh=f=fg*j2@Zir(P@2yfGES%N&ziP2@;eD~SM+NIe-(KBRpsJ%as4_<9&@ zwJVRcO?@Yl;z*>GnoM)he}!#p{vIA9(_xNwvu)4v?;N&04^T(9O3T$e7pYBas7+_9 zNG9tNYzJq2eqU4csA2J4*Mod9J@&8U$s%DR5#(fZ(6>4I(a<;8n?lm(w7r{ctTMx7 z%(mt6<}t^wVcNQ=Y~E-h*>rw(Eh4&x5)SL^E642qE9zRcmD_0c7m@0BPvw1<`SvPx zWsw^gAdHiY^%?119lwjNr_-(Dp6XAwSs*UZF8#y-oSbump419jooY*OpxH@teQ^$& z+x9kP4H|NB$pabp`c{N5B0koJ-MquOO1>0~agcldmC5NhPvY_ZoeHUi1ddwYd1Ic3 z{{V^S6}{sB01DdptHV;+OKP{#vA`aCM#;{2b@_oEN4-+H56sWkyd7ua``NzGw@j@D z*&)a7W?Y;A-807{sH%Stei7(eESDEh*zH+}Q55lj(c>WW_3c|e3)62r9i}a%$-cbb zAt@x2o0dRwa7h4wI&+%S)S-s?TQWVR%Bfi992m|zj^CXey+PD_BbxDsf#uuD7N2cs z%jJXQvoP}jW1L{;KI6S`cB8>@-OX!tpv$JmH_hgq*AO!fLltg+4yU-T&P$*8L3HWv zwM4#Fh?PsrXvD$G5rQLLneGT5hg#6m_5BaV?KPy!XL)f3$DS!+0ES_~+Ii2tWbWB_ z=y>0Zeif=*w!fpt{{RUT+Khf&(b&TrNot@4-Xc;C>;Sl4ay{#!_%Rb{GF!saYLMzT zf4F-qg6lPy>*o1Pt>(m>+kQkNKISe4Xd?M!53HaQ#vRcB%ID;NBE;o~iiwEzE<&nfOJiE^{zC35Su@=BQ@2g*`3lrND5ah%Yb?k+4bx_ z>grudFD{or(fmOr_O+(Hx=B6BZz^cQv~liN`BC=uJo3EbHQ?V7?)8gJ9&62K!A<`P#TaLj6#J6*4?KQlG zL1UDDK3=#D{IOZXQShtWdC8-!H*F^QTE^y8S@V;#WSJ?B2OY@7TvW0q4=7{&M1Q$tKBwOLbf?#+i;^f#(P&x zY_~G9XI0>D6zF=LrNxe|3oYEz<{4wSWS1kNZNbRx#yQ1nYJUfyXc}u7KG_(=7Go87h8moiUGMQ5<(Yf8lV~J{##;h0|!ZZ*Qh)Q{8NI^A~iH`F85S zbQvsI1D?E!;%3zJ-A_-vYpoAQ)14JX!)fm=qRQCDST5m$dhy2qY^pQ!)>T^2@7@xh}Z# z0+Wu_&$GFy;65GG7TPH$@cyl)$r6qd`t?~~CmTO`*z?AC$7+|v9}n##@mxA}#kYoT z?-fuOAi4W2OC$dPdGZ%=C#G@q>s@uuk>L#s$9A?i_wrraLPT?1O{U2dumTC(%dn`% zaslL?)tz|{hdfW>7P!9g6`l5-d6V{3)7~4aCAG}!YL9{#o1Z~d*VD!MkQrA+F?sB?Mg!EqoJ>A8m zm);thMe^;W)-9f0=LZr48nQCykaqihJk#RNt*BW*FEvRm^;HhQU&kg|VZc@;a7N`P z8@)PlUeLNGvEmQy3oi>Tz4noLH_2tJB(T7$eo_~PBoHzI+k#2$UNP~L!x|664;d|# zlWSHn+wpa8G+$}3ow(s!c6JYNTOd}H<*21&hBr3akB6=AEOl?O>dP>3Z*e*ae7*kw zcsLycsm98bFzp&#?J>iQphSwmVk+3{MQ0 zfLn9#}suK zXSrlfq2%4l=YR!F@ukc`T2Cyfz&OqatwTMo*i~X})Bga=L7qPh)R8X5!#B;-IHi3? zt<b(K=^s1=`l_Kt4*Z})v)x^G%-B?D; z^Dy%UeYnLfgOyl{I~IaP5#WYA65NhDk6)!*wa_GsK4rv{w$gSl$iQdYoYXL(iWQlr zk85P@AYgqt{&j0iy=g7q=3kQq2^@e)$@+EuDQfg(s|pv%EH<(Q{{Uo~O+#xWVZQNf z5;_n609{<4S5Xqi2hHdPMt-$QNjJbs{H-QH_WuA1S`Voeqyo}VBT$T|f=?MeO;HFj{H(4qSHom zhkoPJv8Djm4uVI<%-{}(H9n)e*phA6Fz$$s1~+c?|8@fPZ7_eDwhS&Me# zgHZ#yfp6jG9cqOl$SlQ|*RV9g$`i`Yc+Nd|q}~_iJBp4zpZ#iK0sjDqs`5u}Ds%7GSk>s}GKmizltN4{-3{{YJ>L5s|W;A4&J$0O8Yw5>G>lGS6rk~O$h8>CJnbNobl z4ECq!EjpH@hZyu;ew4tB&(o35(xhpbhJIZ4!KShE0rhTkj`V6t&wNAha`>Z1kIHW@ z^2SuUwvdmw=-D5bMUk@&hmr`5l{$Z5I)nsNM{KFjM9jc}Mva^{Z-n*A^QA>TK&!TEgr{6;*ozy>i zITs&8&tItE)mh#)2XQzD9W%6gnl>G~pHX}t(pydVW2DAfHhCfQ11n`+Se6Grh|g{- zd_*HfUAscA2F}%q@Pk%|SNLh9$sCc$VS!n?OT>|8{2fASbUiXCurvb zJbpDq>{qy+J4hv&i+<%xv0>N@n&bWpc)fgY;hW7s@AIa-k))3w>X$#e10U=FbKjF) zwxHpm-5wp2sK!Y8*AL)LJHvh+@kXas>ePR_iX=)f;BON8a}B&2^?d_ycnB z+o-BKwY+!Ma$DTP=EB1at^rma{$SHTECvK{R$>1$8+TENd8uAdi9f)MM$6)$(ZZOwed^S;rl- zEyUaRw=SJ`W8d?wY3yesF)Z5N*bFr=iCKn)t^|wYt2D)ok4(pY2Jt+~H&SfzE%zzP6iI zJ{<63-!AK`Ifu-VFVEAQAM?!%xuM%=dg9+}dfl~@wl`7Q$M%6Lu-zMHAxe5o5o|jFqm^_wot-ZrY%Mt^D zA>?D*{{XHk{Jv$>cOPeDhxcYk*LfQV894Q-5nN4cb!>MJmY?CzeR!R{rVdxD*ws zhw&4`*81;)wF`T+Xzr}`Tr5bSxge6mj{8dvJJ-&3Fh-V3v4|?f?{4EfaqHjLiuxzT zdY+|u6ec)ghGjAt=XWc?$p<~Lo^$J8Jx2u1qNL2;VTMLWboK4+&nB)LnaOHewAEVT z&+PI~D#oYG*iXpEr%vsT0W~JQJ+;N|+h{Irt-^w-EW%bSI-GzwKApb`t9NE}^@W|0 z)uR%rQ=PdT8{BuRP+Bz6v;5LVvF>aP?ZNH*y{l6_8777yw6vdflFclj2;^rf*2g@R z9WqC)b(T8Em!(_V&jGrIH!gYF#2$k_-iEmdE~K9CI~8L9ZBxMdk5YYWYR2WH45!T6 zK^fbeaaA4k1FN#|+T3W~bTCkqgsG}0B(?@j^PU|Fhn?en^+b^zvy2IME{4BRmDl8+%IOeKd z*xpO0+uzL`i*IyYVJjFxAybCO`=_s^ZhSuRWL^x_q`HRJOw?`}e7K~%iJ4+*-W2R;01sUTT`9!MJU=407sEmx3@cjxp01t-Egx$!m8EcQ=-{vRsS;@*RiU zBcbW})+BfF+UwBWPRn_7=a-r%Uy@F8cVpMkcKj<_#9G9jC)7>ExQSN*A&oZ28i9pS zJpk{XYIYjE>}bQTTG-z*%OW%+g?}jzZaDt{XnI!Ccz?sXy{yvdcUp|ske@iiHKQbP z#tuK$4DvWXFaTE*sC}LtJ{y+Q5_#lu9^N#=MUI4?hv+G6ukI(7;jO2d6_ytB<5$O; zgQz@=u0S~NS<2()vpt`~52ERsbT_N0Y8HMVlHgiKcI=JNp$!zhwvqgJBz(VxBHkqM zEz5tT$8mFNzC<4>xh|RHDaKqcUOD8}RkhXTr||yA?e|j6rTKV;WQAMHR3~{xBxjz( z(!Dd_M~n2o0N82&0NPrtI)$y2pKG+Y3ybRz#D+1+z}iPtJP>6iNC zx1ZWp`gfUT@rKj28O%3wGj;N1=K*t{EwVcd;}z&uzZ!3?^(%b?!fe-14bmjyc4%%a zV&EOofrbEdWym(XmBSL#|3c^fLbbj#!YS`3nL z$s?#0la0}7p8VbcvG{SPqiNPR5WyPZp$Z>oIVabt>-4U7!JiOjxYp*qg=U9FB-_u! zJbSkS3mk4-6V&7b?N_`X@ztl&S#?Nnt!^9$(XLf|yM@OkWZ(d~AA1=XaRPwR5dxn8M#-FB1CCrY|Nw!F4Zb<}x7BSO< z=tW7c_+wA;MXu|p{LRaNLmiLrkMe7S@mIx_@P>;A+M$tjrc)Kf*3KED;~|jr#{_;= zz2G@v({xC+Wz}ZCu)I+vvdRj$R_Bq}Mv7I0OJX zV>Qy*>DK1nAh5zC#xPR{{QYa5i{d_;tiaP+P39yr6eNwL5!8@+3b$jgTwcq%6oq4Q zH!&w9{{XYwII4a-DE#HRaH#@E8Wr2y`ZrJkMJm;oC9>i01J#YIRS!K4GOJ!Y; zf##GP@<8N_diqrA^cqW{$!I?kCGl0X7nXL{$49(SEhn=paJz6YSuhHYpoSR)b*`>> z?Q|iwKeNGcd`@NIcCW5|vM@bOXlYVe-dV?SXt1n%0KxwN z+7nyJ1L&8Uc9hev?)=8I^GH?TWr;jwWO16_)`^>y+4Sdzykp@%f;wG>m+)g)(6vo# zLDU4EHSr&b7s-8Tp)QvY%{zeB=$kyys1*V-fsdG}Z18lJE$ zgWkTgVB1{7<^lJD?FRvYNW8vsN%_n6Ed81FO$YXa@N|9~&~LmiZ=uF-HT_cKN0Qlf z3ujWT4*5VES&EEuLwww9u77B{ntMGieu;kFUkUs(;9mkK#IFs*Y}!TT#0jZ=kSa#M zXdorpr|^8tis^xk>cby4d^^LY+V8`YD7ur*^8>{b=Pk(jy#dE+($suY;2#hF0Kq>0 z0BR2tTEiq)*S=nw=KA7RxRUlsK!P-lj=>+C%E_~y8+QO!PwcsOrR%zL^m`;$2lz{@Bj?zRqomFV6f`1#@M{{Rm>+6}*otaUFa*;r2ZyFSc-jLLSBOKtgAo-^xO zA0DrM9O`<7t&WM}eOaM~BGKF3qup5P&z*r;Bsn@1rTFhr)26%APO*8X$jlmhdCZL? z9AwGKW+#F30y@>t2>7<@;_aVR(rooBcvNL&g@l&RRnm+zBkjoUtU6nq6b!?}znGR_glG!uOs9@fG33Gf2PM zOL$z8*?~yfd;Q#FxWKPM@n4NKX0)+=7sL8p#+jz#^gn_Te}x@DEa#*X@)qT*YCa#cooC#eJgfcG`jd_wr&XB#rMiDzk} ze1aWLSkq8zwouz;je_kC8;l&N$Gv%<#O)7A@jce9s!4GqdWEd1W%lzi`y5jcM#2wn z4%}c26N8RCj_7#9!a9AnvuCMZ{esqZv^OzamV!6rgbSPuf=J^86IU4BkttmC4J*Re z);h|`rO9XFiK8EBx;JNc*`fy_m4P5*J;3K34>iaB)jtwu_=)01mr&D|-rm+Ug2qUc z##jXame1Zf&PeZy!@lwMr>0>$KC8O2Xmb9%luLJk!Rx_ zYR(jnXl-=#L;)oYAWnpyzcY2`xbzjYK^OmO*;^_lurDN$I?>$c)vC_P+;ywAk zNZLeb?YBCjk})X@#s{~*rFyrEt|PsUMzv`pEsrcQ0kAj#_UX-e5089d9p<%Xr7HPw z2P|%!^>Q$H^uaxQ^sTiqz0W6{gK;O8yL#vSpYxipce>^^`=PV72{C|AK~)lEa*gT%88UA9PC*=j^r_-T`y5zp+3(m6a4MzU z(ULu?vPpxk0e@=G9D0-PLhdC&gk`c&CmdR%(5$tvwEyLlnG+D~lL=9>eq-P{qk znpC=0lW<%%M^VQV*&`FYdjkhgoUu9JRcJjn9Syr&-KsQ(HC!IQc-8At+I(-gEPplu zJh8`2dsHyZ8W_n6&PD)X(ETYc*Ufd@%)3t^SB3}E)YNE(NS9H_&AqXf!1=TK3Ve5H zWp6M2Q;ZP6#EUo;vf#wHCH3aHeafl16WtcKy&# zzw1!0JM;@%r*~XL;y!?Z&(|HQ!z%@iq>4bG?Z_XlYQ?p*cG0UzkC@>Ujxp+Kqf&I2 zZX{?&03VoA8}b`*sEHwE+alocp5BKQQbbjend6hE%J}uIDD?Q{3jY8x-S>FKMJAYT zq*Yd6_#7VI_{Jy{OzAeNg1KG1ecW+OSp<)j`=_v}HCtDZ}DgEcNG=&l3zf{HY6PnZj|{8Ir)@+0+rV&!MSYkO-L(lEM-JLE*ELfN^{BP zXKqv6cBYencJbfZqmhhA4(+>n+A4`SAB&$2HLr=9t(}Z|q;@_ZkLR5fe)P&S)bL0v z#sR>`AdKT$PlZ-Gf5Pd!Go;Acd{+om&5iC@o>=!F;~4BST`Y1CgulwCklpG#{Z8LY zv1^-&V}=;qF6LkWB;a%IeQ02O`Qm>MXuk`5Jtm*7cyf8QTY&M}-$y-;{at$P>kFQ@6cpTm}G)tl`QxHgX(258)$ zL;M6|I5p<~00Q;seiwM%TUNL7S5UQ75(V5~S0R=|kKrIUPh6TcdlZq?e$}^nT*pm- zx~{DYGbR8eM0g;cy+HkI#L~^R3#C|Dnq!@-*EQ|`0JP76t?qOfHTxVqwxmZpXCg?P z@ZazjBmVlY3)A%(w7aI76_d<{K*+;@9CYWW6(PCS{4DXD-VgD`q=rcqeBl)FxxBu-xM-xcWpq3gmDrL)0z38mYu}}q zJfT~VssQ7PsF}*-caiUnl}^pwz|TIl^QVb!Z+s!~_DhTDJjPqN<&mRZzH%H4fu0E* zcjO+m^mL1mKpVi?zzSoMB3@um1q9tSnn4=W`WYwmHG5V_4ql zpYDYlhC0-fU8CK%mdDFsw=LBAn$hd9M}1DGz_UqbeWl3>VIthDgKC4EA4A8d7_Y3p z4{3Hj9?&9+8|#SfAq66}o%fb!EX~RL&B@~(G1|UO(WFZqPe&#;ky_z);c^t5VEdZ- zzrz}2(_7nJNgQ*3W!*BF9e;bs+FR;*8T20XwGLynj@ms6_BiE|a=L&!$Xu!(Ipfl! zbcyuH@1c`(Jcb5|z{ydNGwGhftayE$=eo7kcFAtcS{Xj>)F1*ryqtY2H&WE>bPaZB zR!HsbZyqsdW^gyj%8$>0ezefh9rm}U>Gmmnvs}0KYXP+sw+Dg_J7cX=*9Eka!Yprm z%XO3OfWlAB-)1{{=i01T$9Q#?-)kdT`D9$inCLmk^`hp^X45P$7R<*3%kvNdmWY$r zjt>~B71`$>A8*?4z_M=l3zU+xgBv{RpF^7m%#RL8>rQn6Btk& zZwrFJ`e663efXWLTIiA7O*=zt9@hIblQ=~ww~>?AkIuYGC~o`+*VZ?7dUf~Otxc;m zspfr|oCaB;U_n;{r*5E(R*>#Q%3<2~8@F+m$m)G+!re$L{#hhcnRdvk_*n*c$o0)Z zq}^rO-S+&WGU)_QQXy=NZK2fZNYa8Wj`*uqa<|%*epM&}Y;n8ZN2y06B+Bprs0Tu)u6?mt+BUT% zhOW0(b4?8J6Shc+R!ro6qpfb}7E#3%lIoZ7!H{KHSND@{Jbquv^5-DVeSn51c_5+D>t|=qsS{e!ZaF_$N(fv6(zg9AZbB z6$x!D3~)Cms9sc#z57=rlYaf>{{U21I63Q@Jw&^beTgT|SCDrA-OsgMu<@p+rubs} zM7MYwP1PM9T*9p*6gdDtRT=6BTCb&QNgkmT!B$0AR%LOOU=KO=BE3`NKaI2>9Qcb( z@h5_O9sd9b)HWw=?9j*ljU>7K*7(L&Gq-k0``N)K6)wW^IDdt!{kh^RT`p_sVqHPJ zi*}UmiV0ls?5Fra>VBraiuh$Z?804ty@&n zp3=`;8jqP{Ap1HhR=RWw z@ahpUEwgyZAx=P3%AEB80V+x0pNW@^uR#v6rRusqZuLz*(nJps7$x9rg6J^Bk%wM# z4_fjo9d}S3Dvn7ehSK8BMR>0fJjlU7FxcmDJQ38K{uSyT9r0I$bPtL#>;C|3)fIHq zNn*H$C6#aGG3|E&uoDE3LuWkWpsZy~-AdG-k%Q*F2cSmhkPx9kvHO9DUZUU2( zcJkLNg1^QwRy#?io@s^AW+uG7n6Oy{~xV!~Q(*J)=B1!o!!$5lOM`9Y zlNo6VAKhT2WDE@S^v9L4?j6`ZDcH51~=`DMECA@NpBeOQXPcFmvK?@Ov$8TEtgI)2)pC^Fk zipc)}W?x17gKI2%UN^@~cjF{un)!d={{V)h@mIthI!!ynMkcW$Xs?zM63S7@E`47- z0uLj%TJ3yg@w>u57&Of)8MRiinQ!Kcb?vl)Vb}_Xk<)>kour%$ka3F2QPicW-FP#^ zwlirE+{NN6dpm0jhlb)waH}yVCu@`IzyuITJpiv%w^&-rJBvAkM=F*{5rb#0aq2(M z74qhZulzsOb)@iXTwPyJ9IY6<2;NMxMb2_EI_~ATJLNKt#vD;z5f76i~B)t0F@FvEP+SyZO>2VTe@Uc@?1x8 z401!~e(#-nb#ZWX|UZ%9-|eQjh#6ThT<+6qjE91ae@zA@vZJeV6J^#@bATT{xa~y zcb58&pQ=Z=#%^rbG;YHg&Itj%Mo;TpH|;TFZR78T8l}CCn!4trrnx_5UM^!G0{&W( z36RH)x|!wNd>VaGV*n&a)i zYQ%jpH2r#Myh*8OGriQecC!7O$`Or`#}wm|{$@_&k+-2VOFWD`u?hG;;hAOeN%y|J9dFXO*2q0H0@b5;xm&6h3nk*KQ+uF{dqrZ_7 zIUfazvoN<7c;8fQBFptODV(1!PgRNg`Qe4e_B3V0JTwV@X0-$8uN$T9(fL0GoMT#BS@Kn}Sr4(473W`&jrhTCvnTH}M0(lTUBr?+Dz-djySx8cPX2 zSK!FfBMe~VSI{0H@z$Z@%l2(r>Pj{{RVpYrhBCcw@!BAYX@mKGP%eWwO4x7B6ow zJ9b4Zza+>`89`v!Bw!K8p?=dc_yfXM8ZN)$kB^#GpP|~`#V)aBtlh=-eQ!%<%iG5s z3}lsv%7p;rNxLA5_y^*b><8fQkDAZef3oBIZPD2oNAjGu3I70CG21_TIL}(z}xoQ21{csIdXevzlz ztdQR=or;L0F(?Yd82LeN4}U@5imKnTg@^3(;jK4a(runk3+w9t0N6KIK@#d)R6K8q zapmVA;0zIupu6CY2gBoyQb_MSNvG(lsw6>hva`w8c09CholbGUuBDxe3=$8@5Ra>4500+HxnjgbyuY5zL&2g)1x|P1@=Z+?{hV5A~ z$yuXz`9}b@Gsk1aW9T2V?uV*>XWYlA_=Cie-9B0?D;S`T_E!h~ zelS5&dhHnlj(XNF#7`eu+*xW07f83dkE8;|w zYm3hq>Kd?!N9Nt65P?jANx^{66q+ z_CATJc#ii?y1t5gLYi#y-T5%tGiUuHXbfatuWP`rih z(kWSHn&e0Vw!|a&vI407A`WmXIYk4LXMN(!I~4dYB%T$#y1Iuk-D@^7K&vgJgf
c_G!Zw^Bj!sQ-D7aUVG!qFAI3PM_IInk3iHN1h*P(+cQFv zWQOu)3PT3Y?X7^EjFF687_0di$+mf~igk$(lN>E9k>HPzbO4_J0Oy*94~F*^o)weC zhRR4`ySefnZa;Y_L9jP|K^XQ1tK3E9OS^E~80Q2!wmtjPb=^wwfQD=Zf8V9LOZ%m5 zyF(sG-HttRU8*R~Rxx#%Hz3MxWlg(Wai0GGTJZf>!tvPnzShP@&BTwp$(BOiQw~8R z+n^n@Ug@prs`^odnol{wK44y>9GrI*<^CkSv$Ob>3u;j9wzalqjnO}OB!{mb-o|<9 ziaAL)pcmE&55TX|R&2daQLgvH^0or5 z0Qcmdr)rYw=*GLFZ;?kQ9e$kDGF`A$>(3bjhWgUcYAD*|(Wjksk?&?!8_D&>Xj^pq z+m{$4xHVr%vxtXctgfrP=Rc>lO{UpNa>`SPYXZd-8qfBkhVA~=vdl5Uw>n1bLZ<4HB|pVYIqFcn8iiAAyQCC$XvFr<(xa>h1t zaHEd6?@`&=O{r~Z6bTUdt}Zie9_$=5o-%r53VGA_K^kRKKYIi2 z)x9@MIzefHK4Ir0AZNV*uenA@CW=qqWt*sOpne|I5=sCjLD{~O%O2p>`7Qw&`GbGE z!S|?ICXvA(#nX;6>6)DxI+c<=+ly`wpkbNpS1~R{U z=qarWxYa98lgebTY=NwYLqv zhl(kYDDwXRL!L5dprh}%i+ipew(-FfAKj}Dy|<^Zrz@3T;uRY>JfBMP&aKC8>AU!8 zvSL6Nam!H?tg3R@ZlKe?SmFNwX|vX;0%d!4VHgdaz-BZZJZFm*3Msjf9r+Vx@B>XvV6zR}hX>vnht5~ks9meR&5rZ3g zt_D7})@oX;I$fg8G;(ce6#!IcJn%9HIQQr(hmSm44}iQSajDM}JaFS`0r#1X066Ca zS%i_67-7iw=NwmIrC<1dPk`FJlosl`m9nI> z$#TbRvXVe$$3u^l4{k>_i}2UOOYt|ycg?9IJ+$I$%aI!p6^=@(wmo`#3g)f#>x+FZ z`$>+g)5EmN?(?x66b1aY{&f9@p^4;g#jD!aIvOO4;6OOl~5TWZ&h27i)3o2dS?^ zwU6w!5yJB{%^E717<|o+r2hb)T7$#Zjih*b!q;=+*4{XV>~Zq*(w%#6CGD)xt9dd= zr9+S52fyLgk|%OV@1b}3OKm4%+y4Nw zRg%enXYa7d;ByVMaryDMH)X!^&Cd)yhf3?TZ4S>vp7MKm!pVOqnsyA$y}D!$zz)^n zwtpVv@YcI=s#|FP0K2?}R_-&H<1;T(J8#Dx_3qkUs}8fETIv?(_gAp2$gTjuBb=X6 z?TRc9Q^vn;8~*?^;f<6c-Q-y{D8XU;7+1l^u^*_fmeDr4sc)D*IR5}WE9>9dpGp4S z_aTQS-xy%KE9NT7uh9Y zjIy3H$E{5T%Xzy#RaWVY4ZNP7wLQ9d=HvZgXohzVLw5S-HKmEr?0z3FpW;m>M#}k9 z0-5Q#LC4`=TG*8uL@~#7!|idbuH=k9IT`+S@}I+dc5fBv@NJ4lGXMj8pqvw5R%qT1 zxYP8nvzu8XxWIK_GP^xMG?mJUr+28m>=v>#k;x-4fH@i2&N9GOCy172)RxBm+2qsZ zW(?>XvBPJn?OK{6OQ+nj&u*}*zwVCG%3GX+PVt&)_cB^sTupHu(vP|T`NygHdiqh+ zI+JKxz2ZXFO?z&lL-vT|kw|yJA1?1tZ)&foc%xU2_`@o#(bS|-<;DbS2*JxQsP?SC z_(&qvpUe>5NhD`t1p#=;=bqoGt5dudPc+6UCXxUe4eD~u-}0tcL(9Kvtvz-B00hV* zypB)o_zdqJz*$uoa;n@ObMMl;=S$Tl)SxWU=0pI zdwa!HyDcz;$MY#-I3b4smE$~)!o0%Bt*})swnSWG``E2%>|-SDskFA>+Zi_Y0vK&7>KhA0~bM{-QHxkVok-d6IGwbxN zR;2kI55(UD$MECgey5{Ba%P6r(V}8Qd6B$m;O7|UcW&6N4FxUaiJe)NKz>!**w;y? zd|%M~UGV1L!+PeEaT?i2whc|0OyL2#a z@LsTN=F~K;M<}zb`h4POq(>PTVS~7L1aXR+P0|c{IK7fWo@0>;0rN;ka&hPfQ|rYo ziL*K#99wD{?VNhG+|6fkaIwue$C>4`e9SYzARPV`XUD$}Ch$Ls^&K7WEN{NTOACuf z`DKszNdEw6jB)SAdY*PRYk}pqKC|)D#g~@4MwJcrsc{?L%p;Lt`EoZl7=RRR91fYQKN7!ZZx#F=wYR+S29(w| zcUK0{W>;Ah$%4U2T#iDq9RC0bsr3$qUxIa}hVJeu71|bzxsfB?v$$Og&x%P_4%uBvsXS{NqN?Ta2@4qH zm&Y6qaqU+JkFPX+UOhuiy19bgLExys;PFYu<;AnJ)P6Pj7uGAK>3VA$ z8AE-cqVplTmz53Wu;E`kq0UZvV~Ko2`#|`D?i;HeYSPx|urY*q@NF2WP^vSKiW!Jb znZzIEs#UbNz4KBVh%V%9rNm)&BMbrv0OOxrXa3NCvL3zg zSHrftrN*tI>X7-YlA*f`cF(jn-K~!>_4~Ozb{!!_7GU@z!CE-*ebv?Xi8Q@0RwNi~ zCW-v(=v6^qE>#2q?YTfae7x6HW$`yt_+<@-p<@q+8s7Qs zxT+r%{ufK8{59}DiY+wTFZf4qtri{Dw=zj^w^()&%Nuf-`I{+~JC8g8USV}6ovGPF z95JjiTca7}^GkW|Ncn&x_(nm;Tu|Yq%DXj>k~bWSq@? zraNbB_Hro(R6MCy8Q-$9k)4i7!=mW+@^h1#RAg zob%egUifS9W5tc)YgV<>Z!K@3k~`aWRU&4KaQ)&h-Z;oS0fEWKTKh5|jW)g{Me#dn zx^|c1-6XQLoyv(0qJg%%rZ5@z0iJgNNcwQqioKDoH*?ap{W8Nu)Gammd@p5gu-it= zEp*`>#1NbY-Hr<=Cm?p?p4qi=PY3vun~^Ogx**BFT9k2oou8gdPI$ z2^ko{2ipGtV_%7Kd~oolrQ$78!$#BZW|+n0*}LXQ&|pa-IXiLC5O8pMR|)%KdIoG80A=kb4m@4sbDV^h>M z&+Uy4ZEEHp3uveZonTm&Up07eK+AB!6cN{TeB_@MX3}nNq|kodZw{df!6%zJ^PK~R z13ku6V;w7McV<$3&fh})o$ch*?)05|#F{^a{6!8L+AUGqD>+n9e_$6TJ3 zkK=Cxf5Ma0rnCP5go8o4yu7wB$pwwUyi5(OH7L*M2;#GnO(VqqHn_S-W6*6Ko_k0onWhl@#gZf-43WUg zU|o59)DVJl0U^5Zk*)XLTu!?w!%odXPVNw;_OXH)D=6Mn8!D4*09# z_LjH$mX9^Pkc>J`C5}kuQgM_j$9FwQ$R4%Pcw5Jw1@IM{Y8M_A)O=H|JE(|9`5!?RgmFYm7|t?i|`k)*o&4ZJA1 zQyTya$nHo0D*$(MTuf_cAa%I9k_A=FY!I+k9XDg3^*A`Hw^ox&9{&LKk*QG5sz`(r z!6Xa-PZ=kZRnVi=J|p~d)xIKlmOWJIdVQ(WL~z?jra;igXo#Ct0m&d09ZAW@puqKS zg1;3s{eMunk6K8yMtfBdJo<@??Gpvbj75#E&RYstWO7fS@>zZ<>0TNAnKXX|>Ap>_ zxvOed8iu=gQ~h8}t+X5POMI>Ef`oCL)<%KjO>5z%u8X7VcUpY<)taT`v7(1a*q@Ve zT#R5GjCJZOA7^w|HIGTvyh-3M5O{X+tu5r!^@t=gAez)K+E<(a=t_g0PUT*so+_7y z{s;JD#CFMX;tv%^p!tz8iFdANml+6-6vSBd!65d)CypU}L8^Q%(WbGpjnhx@Et-p= zsaZoYl!AYGZv5~%t0~Ai$jBAN&w4DI?DmN73X*)eN!lAZ&e6tw>Z4CVb0gpMAKBvn z0OPleg};Jd!@3=u{{XpIE%kGAC9S#utt`Qhnpn2uw66yPr!`kpw{L)6C-F9=tm%7v zZKsGWbPHyPNoioajDKl6fXsmtD8yirPC4VrFFr5p7kX3?x04ObIApuFL2okc;ZF3y z$X@+VTJ$YX_NH%)I(?m|jP(5$>h?59+f$C-STAmZ?iqKC;A1@H4o_jor7CPrN19mN zYW7n7qCG@ljIi!hSK=HLJ^ed1I2|-r`{-2*(VCoDID&$_dACIpM`?p)N<3>Y7c)gK>Ff zac1xX-O=YY5g?O&pgINhSk+>GuWC zBLs2nSvSr0Qq7lXo8~-cIqpYu&2%otZbj{0=0s+Z+23kqGJ50N(!5VnSv9YU(j~ld zd6C6{t&@VPOG(d8fG=un%&5unOURA+Df0kKe|VyX?WJvt+m^T zRc#{U2^ z=W_1*r2hboQk~egU+%FzKT%TJNw;p^{k^I3?8%E|fg}0DaAw?oQhCYeHFd8S3d*}t zc==e8J?f+pnB_pbwn@VO0JH5Xs%A_-WrXCyE|a5k%c=LwU8 z$r;Dtny`-W#1=M_*CW@r)~MTPmsfF@^7h7!ktBy|sP*UhR;I|)Xp%#8?T#V^S3mDy z9zPGQ7FX1wqA8jDy{*R?3;LSTI%`L4th=OUI9TIunC@x@x|pj(m{n7qi~K&s_xhSs zs7VYCs{2)k%yZM%ng%cS#>L#nw%jiYzvKATVBc+@bZW7zd=|*XS4M_QSsEsG=r*#I z4U&C&(i@peC|JM%V50GgPq-IOL$A%xQWS7M!lAgi`&HT8+Y5Et+k^G|ML>&nb7{4u zRE@fTyph~ypA<`LHaBs%BXH?UQQJ~$I6l%@O0<|c3VLVhS1jx!vOnuNJdvNf_*5|~ zK?gDwJwf}q_WuCuQpEAj`RLtuejO@zFJnx|2+E|4plu&FAB9)__U~Qa!Rd;xZK

z1XgBtI0}PtBk5P+GThxNN4hp{R5#uRrtAt+%2~pn?{&{kDT^6(;1bKu+Ocbv) zk{E6hBCPKia$`I)uelifs%_YNZg>ZTuXT$pGfVuu5;$R#$2dHb)84SY3Vb%V z@wSI~B+Dhe#hu(!K{#K&6db3fGt_nIMcDk#=iz_G3x68u(#L+WY1g_^B3y2iZEm2j z>5iQaYg5A?611-wYm?d8HN>Lbw*8?~{T@Tt0kfQsd}g_?i9fT=uZb??)U?J+TkP+W z0&#D2K{*5ux=*O@&mC*9@Rx*a{2!%9Z)0xO%Ex;~&$)p;i(@T}<0sml=62Mx;!Oe_ zYfkbcl0;Q?ba!F_ABnq4+ev&dYJ-s3B~(~=3}is~7*^22e) zK^?iS2f{xHrSPwfbv;r&Qb8T#NMf~(LZYiNVUwQ6+lp#72^&5t(6oJ9M{PFt-rhKG zrQI5wCz&YZ9x!(fxb)($+S={5RA9-ld3YZvDmrmq5&J;uJ|WXQac^~W8WC>0?B%!1 zM;;G6^vLas^#1^WULv2w9}cbLy}fJ8voyYINiO*m?jQsBV;SQWT}9CI{{Y)R zSZ@sJ8XPgZZMvFG*lcA&fw$?C(!OCs=3NrmG3O_o?XRJ~Z_9>TUk<9esw+$e;qwx9 z^!xy?pLTBzF?=pD>z~53i5m?YQgFcT3fT&Jd(@FiK`fxI(Yqt3N^!7~IMP;Ku(!w< zp1n>f?E^dnM#|jhZyhsQ^d$5jg*MNt_~S)^Mir0D%y?gv_w8S7SZUHn;Y}-1YsH3U zLu%1T-#4-Ra8Ko58~h^Dt}b=`J#9bNE?6rK`Ct#X^RKOki0-uw9?of?wl?o>V7E~o z2$6CLYrd!6-L%PO%@P1}E>BrZ-bKWMkxw^le)uj{Hhcj@(~ z${LmYJ)z!cHuJQ~w-&!7;PN@|p1#!$&xK*u z>~Hk=+WHga39X}9Sz@_i$t{DEj!q8)6x)3!Yg-F7yJ;??xQ}G5BVl)e(Xq!FpmRgg>9*bm zXTGufE~j+yt+-~%n5&HAwgBY&V!VRRLo8qIDdj;OJAeACSiKD1`kKpV;e5r~+j(U) z)2GQjuHpBi?~bS1mrk9aMMd1v`nsH<^r>xHXmaZyD9wORY}TSxeNps?_=WGniHPJMyW7)%aaK<^aseAGY(_};J-sSREy*vLAI!MP_Bf~7 z+WF9y+{_n~js`vIIOJ^z`qnbclDhoNuOP;K1#K<7K2&~OjUzIG+rS%7JP%>(LVAZWem$_s5Z)BA%8yEt z3t2CG{mcIV9_ksf&ehH{@7JfjLvG$<1G^i60P*jUQz*^2SlFBl;ClPhCsM**8CPji z9yY+oLVZ8arF#dDG!KXRkL<N}qfNV*J~t-O}=TSss$UvsQ?3fSQJMD8ow zBOrRx<+)2msoVTK@CS*k{1d8p_d~spO^3t(04vHT+a#IBR1Kw1QNwU}9jYB;_Jr{l z#8!^q#Meu$TU*C3*`b+4Fvly539y*UuTW1NM?!0z@ZGa&`fQeVcKWsUpuTOy_VAzG z7$ZRBmCr1=C-5EW9cSV0y}@U@C}1gR7nKnapin^m5PFa}&(Kk1IJ+NP zYCo}Of_@zS&04kYz2bXG=9<}Oi&cu`c~(-WEfh%^8{cs|PCzZ50I!v$_=Vyx9ck9u zeg3U|safezm$kRKkVsG4U%ww37O1QfO}kQVEttBs3yK!$pCN z^aSTUs~^C>8N4&#>Epez(RDi=V&3}VXMkJ_i))Bw8-8-!tcsxEs`7axbgqSeVDE^( z6SQf(QyXcI{jn*(w-a7w=He+qak@oahC#q8037gmAWXH=Ll;!m^gTny(b)JuSk*0K zhT&UBzqP$+&6I9JyWDP2>{J1k-d6+rwU6V^3+o>Pek4JuYg)9Lq?d5Ze_=aYrObEo ztb}FbVii@1-VZz+jMtp_J`FFx{xa4y?;1nm4L(a4rnhCZkz=0T;Xx%NUPFSz7{~{% zaZ>m%#Fm%#&1rFOsZDmWD_cmi`MXFtNJMA-usIpvbgZRMsZo`Wy!;&ZUOD(7<1I_X zTFsA%w42rPw7aOFTQnah1xOpW@5+;$WDo~Xd~f!t{iZw@ap7MF-*`UG-~JM9CixDa zR?|CSNQ!KCD~Ur822OZv)hx01#>s z_-|D3z04O=X}XLeIVE?>V2rNC+NDDPLC78RUUTD{-7@#ZQcI@k_O_a2%(ELyX(VW4 z&NnJE!ro#tGL(I$yHIDfOsD> zU=z<2Tl^>0ynW#x5w3|fiuiNG_cu3o_t!H=9MVRgBR5gI5$t1ugS(3Jzlf6FYkJh0 zjody%UmgBi41Acvj@iHfXQ>?buTK4&yj`dGYUz9vX$>Ci-F=2HyD1OMFFD6A|K^-#K zAxjQH#YOPP!cB3jrlot~ooB@Q2A+3c+t@oJ9pRQRWKc@{z&6p6LY{!;x^IvF023_y zHLq)44)}HAtxogdoZd?dIc}OrB$NR11TF(@5@R5qPpHLo-?5+VIpELP=U&t=H7!5I zS67!-am2DmBvMD_0@)G9HsMHbyyTi5!F^9Z_`Tz;FUNlnu66A{LSGJvj7pkz5DQ@v z2*VwrM(5eMji6^ede=K);V%$;Quv8$Wou(~scPEn$|8~|i)VWU+{AQI-M9;bn)I*R zN8|P9$FCmg+SEEEx-Nqyt0tHB%TFq8N-*ENn2<8cY08!nJZhR{Js5NhZUjc4x zZM4f@?M-0K{g0~K-=npwND9bh3fqImxG|;x%!Q6f0;)SJ6E4Sw>$*DV`h@VTjVzJK z$j5d{6=J8Seh=wX?yhz!temfIq@m`UCbcBf-9skq$_!G1K4Lrb>+U-9Q_XLt+}^`) zr+=ZsuqNcXoG}ss^PKa+Y>+s{Kb5_m?wV&alS}Nz~=KvB*%PB$L3dn@RB`-X8Gf#qWdd zuA#9yTvmP|mikDfTbbl$1)zzJKm+Ac0cFb`Gn%2Md2BETla5V& zLHku{{t5U!taumx72__Yqw0?O#l$Ui*LJ#;i0Bm=iQc3kb!8iHt~kzdmD7_Zgl9p@%^oJ_HVSOIT7%8GUK7aKK$dAxzIH|BTBQrxUjvlOT8`BS&}=eT+GTw z0(p!wI4juk`BtW%@n2f-?0;ohpt-eDg)MI4^Wuo7O}mL8daic#;<`_SUmmQ!7OmEw?n*T(=bDtd9&yz9iq*5h22wD{(Z#%CfSJMWbfaM}qN z4A|hDb?s5tP~}C9L&XL;{?%=1XQ$lfhKWgDhoEf#0Q$Y_n!UQXx}FxAeagHNarz3; z)FWXSjbc?;+YKWFy^o>if$Tl29`PiaMOHo#d0>#dcB|HN3z(K0h}6f|?)1%0 zg7pJ;_MoChPb{2_j-6|2<5`M3*?z-i3~Hb%%Hw;cI-fzGrDNT}_GoyGTjszkou@z6 zg_d}i=H0c1Lh;B4jz7tu(kz%{J3Pm8Hp#W)A^~{{TOQTD`Z1$<@AAldb{urtM;xPT|r; z+!kph$iXl25%k4aQr|A;Ra|Zu!kiC!rt-*Ge4-JKgOgUQ?IW~RJh4&1ep;Xv$DKq- zz+1x4v-sF__x}Lv(#H&wM$XeohU$tiDr<7moz9zN1mip_dQ^(vy-=HvVV;@w{3(x{ zp<_qVqtmQem6|q@c+cyftt(tKXLeibpUR&yq=Om5=RDMSD!W%KxgSAOVD$#SZzyh6 zX5?UZscNpWn3_Qi! zd0q(zr8u7c-TGBo;<&na)fpm-f zc+XCU#1ZJ`>045`Lo9at56*)*=NKI+fN5Si()FEU_QKZfZZCBF3E~{>_2<40LC3vt zzaMoOHR!az4%))k7ut-*OfkWQP<`$`r#`}={hs_YE8S~a_2T00^72S_=a|4^#1MVR z=g<#Y&-lxzP2k^&QR`P0QQTU|WNfVDMmv$*9Ot+^Ld>pm4`#j&;J|*5+*Z?COWHA2#aPf+Z!CnjTEsT0Dt)kxPu_eLsU|3#);PmoBUoHi5O+e;_L4vUAk?@zS%r31xeu_+>41 z0T0@vcO=F404z`A*YvGz#E$%P?NzZiASI9nZ z=bx`pS{jx7dQF6v7ZNNGpvy|<0e#Q4d9R8-7HM~$HPi2;mRqmwIUV|fnFDYjkEU_b zj%%WAbG+0n*7C+hxK)}t5Q44Bka|~-`~vZfj+NqH5L(=bbkjVn@IuN{U_x?(C$Q%S zuiz`%6h$&HjC{&RPBD!C0QIZN{vmuR9xV8ocO;QX9CBGlEO!y`zG@N*pK>rg1yn_* z%=4ey-&(i6{{Vz$HS=Cc43k9Z_ck)9IXyGL_53U6{oX>yy?*x@&RF`_zJAs>XG^;9 z*lS5Ao9r*OCn_2S$Su1Ze7GNXy?BP(^E4!8hA&Lt}Q}*&O1lU`ofUd=$KsP4UK)6feGQ z_&+zzw{8i?ezo-ni8P=1My=xVu9j$Rf70Ov$snGp-h`U@m*9kP%kgT_riK<-Aasd~ za)kZTqdc7d0FTq@>wgbP;@=M$Ww?zk<2!E4$UMg6?HhBtliZ>o6J9{pa(Ts|H-t!= zbF~|eGt=6r*m#rsOT`M(YLiIUQHyPgL5?y310W3U9Q8da{obOQW{Wr9y0)^P0t<%R zlH-8K>FZfXNQTnt<-S%1?l<%^t3diUgWkHVT@Ykz2ljyLl>$n@Dt3#izA;z-H$ z9eAwWYR*kdOPULLK4m^}Vt5Ol!#zJLy{AX#ShbJtV~+6#VgqYN-FkXt1NhW8_wl}* z*AA$yGMi>ZY;0bIx$JRNE{BJH(*6tA?erZ#Sh={izS6w-(i99$F5fK!kD!Ey+JI?m8aWsU?me ztL3zxXaMA%0}u9UPZxNy9~Vlk7K^25_V(a{mWWp%_9T*99lbfK5!~*#eav@6FoAjz z+O=AvGfTtT&-QnSEN-tM{?dxpMUkx~Z<2He?*28<-*}qi#9H*X(ze-dn|GEJ1&i1y z;3xwExqT_4xU@1v+h&P|(pwIv+t#(M7D-q$w1PlLB>w;xu4%_q4IMhp&2RFy&BF|! zXLsXJ2Ui(l+e+>ARX*O|N=fbh&8B(s%F)lccERPJop4U|Ju${T^Pbfhm97dhp1dgS z_54gumb)DK5Ly`-EG9zaTk`;1f9{c zkVjsJf_Lh4LfX z2hLAD0%QF2sjoE%Z*1dNgsjTPbfvp-fCu$8CBKKSzqU@7CZBZ{s|<$O?Af{? z)2TH&TFGq;kd@mc4$(@k-5edPIQJipDhn&gv|IRZt!9!7s9VjBM174EgP{kuD#ov= zwxf9@-)gwOp5grIr<@TZ%G|MHNzWwn-lod>4$Qx2;+xGMO}w?WxQ$`d0vm*N1=&+1 z4abqrI(6?|Z@|CXKg53nb>;rfxw^cvmM6EDPLfv^uaI!SauJoe1Y;l(-n`seG_%U( zyv7G1Iuq;1x2Jmc-`MZq7sJ1fn)T+B;+V6@9#Cos8UxV5nm!R&~^}8G6d@rD}UD2wN z!X-?G^8DUQ5=a=&7{+|jdUrLm-0Q#KqW=K2fbeg`?JrF5t<-Wi_E23?XeVZlGRGm=II0uVLAc7aW7h+Z3r#pM2N#IWyzlVHXr&zA7rRoeXMfBcw6AH=@ zslxoYZNTyzWD4|8i2fUI+XqpL##b6(@UMmRg`U~a0n~<0l!-DMIT)v}YhMmu%5ntlwtehG4nL9gnAeI@P<&XzkxK zd6UN+VUf0ttPlCdJAM_t;;#_uUODi@9!8CCZ>8wFklbndX^sRgcM~jwA()Z;M~}w3 z&xBqLv-r{ANxU-$gEg&V#vUJbzc<#JkCzq2h-PNCbzy{VTVoBxxdW#Z_E#s=;Pp?4 zw_Y>SCb!fWY7CxQ#dUH#%bR%PU7{%4_){Blqpla;x%9V^=rcm9-b#SPsN5H(bJH2) z*R^+EGS{?U7|9fRJXg&Pow`R5k}cN^v9CsC0Z3dNumg^{?dR8#T&A5R=E)MoOXM`8 zD-$;)DLevk&+F-1Q?-Q4sA5!*UKyFAMhf<>kB7(0mgkJ%9`)CFU&WDX9}na3ZLXi9 zT3uh?d9!M=+NatiE>s1QcKeZ`$18)3=ZfR}A)ws&j_%$VVbm^dcZZ+su@_~DerI5D zfI2j@FBC%4S&e@`ow{mc}wygHBRg3ODL|Uxz5C_)0r(f_j{{Vz_H?`I*E_B(X z$=f)6 zha{8S`}@~P;m`O%EPfnbTx!#J$^2>N6|l9kh7au485>$z9Pi|3A$b@W>%}Owu%cn6 zxL}G%WV41wk#;LKeos~$<0q#)R1h_-+_A%a_ep0X1fR$&<^()8-P{(zIL{fVH5s0H z3^wpG$a;))&uVU)B3Z%ntebQIn3O3f%Cogk+P&pKR8&(!L+?{nQDqHlHLqP)$sNYr`DRqd-(C(o6V%ezsPsA8jY{ck*(027XWrN# zoc(=xto@B|D?akFE)Lb`p!dk{S_|QWduG>5ac>xf3y9dVw7l}5;{}IY3eIR_n%-$u ze8x}?N$7LZoNsb^jktDqV$btqk^$rTit>*iTk1BRHA{$4D#ruw41VGa9G^<{DPw6P z-NNyVDeGJ<#+wGW;vIV8`uaFOvh0v8zx=e2%EbUt*NhTRwLda1)bL$m>1MfI%y(}s zlaY`)sHT~3ZlievZ5u;3Q`h|Uqgx7>(xBbJAUQp%y}Jk`R@=EZXE@~JG|A>B*5--l zm2K8vBX`Oq9S2OF)di%hJ<_i`PI+2VhDaEL^DoRvZ{5G$9ufEUhPBlN(2_dUMi?d63P{;}!rVM(WGAd8C=xfV;lxo^U?3 zdIsKGmR1Hm8C2m+UpDmacz*G9v(G^8)!@f#(Z(6Y=Ycct8 z@5cmos9N1i{KsnhcQqC%T^6mUGo7ooVNsKloYjLWc^|^eKfHQ` z)(J+;$jr;Y_ovI)d$RNrwcMXJHsoc!D%HvRJl`vJ$jQw|41Pj3;kCJ7#O3;Ssi(JV zaU6yBagEAzfPbw+b{+MxT?)-0ATADYGy0lC7ns{rlD)wk14x(z{oJ|fj%rBd@{Tuq zl7E#hVwe-DH{7l~tqLv^RWIZd5Q)_nVWE+nSx&5J-$u z3ZV7J9eJkAA7EYF2JSjk&_gA~!Y~_D4x6|%>ErY6b}I(j3uQq3F;A$uuEmDIypgq( zE>9=D6q&+>UG2t51MbmMK4g8wW?2(z?qTjaQ)DH3Gb;4=rl-vo=G<9$6!th?KAiTh zEzX+_SzIQ<#2&cE6q3!cFc*_i$oRskJ!#MLFAU9&!+;G{#bl7jyvbGD#&P)bQmJHY z{{RnOzj~mV1322ZL$?RPC6WMUPI%JdP@th4fw+5 zH;!#C;jDE+h&OCG2a&)X!2bYi^7WuqPInNvu6I-L!)hAdr)za*6#6cy0&mOUiALbr zUvZ8{_iDETdIpY5XxI}? zFg^2Kmy7i6NxUH}IwYTEy^U31&q0IJ>F#TpSZ=-O; z_m>=w0Ud#(puI|ewK;%z9?m%L4w zZKsd}9tqA50luP*$+u%#$HVenctTA#RG0ft%~nZ^{{YKnB#;lMTCaJdi1p1Zi&$FA zPleVz9jyZqh40X*Bk-+FKK9>Iw~pf0Ww^JPWnCZTZ_Cs4s~0v7>y}nsqaZd%;%Gs# zD#y953gtiRo=*G$4y18~Q+JB!TubN1YI zZ-_cfB1YV{JIbEw&fNZ(#d!Huf=!IyHb0-I73-h2jOjncTOTiQk_|ipNZ^Ab93SV8 zOjnSJmT;u!%;)CE6}(o4WKSmD-^I=jdwbTdiqc$PS?w}0<2dR5d)8{=K-}~Ln%3}q za>=g4$NICD!R=M8#*yoP18zRq@p8kMSNk>zE)0@dZ;4iV_y~ti#==#OHpJlk1+TAok zq9^VXfu6(;xuV4*u)k@b3p7m(kk6P=MmcfU+pqGjLU{G-4N5y%9^cE3U!3my!14w< z_4KXSEqsNZI9=5(8|_OIeA^3uI>@~(f2mygh|;a_-?w-AyaD+0QylH zPks;9n_+PnkIarnSu99w1>5HO8qopg-?XKR+xRa_-7Amu&!p(hWY^ahQfpd_7qP=CXUjxK8-dOjk_Q|fwdDmGI5z#+ zBw|OmrEN`^$@dLQZpHH1N`>A}zo7N2R#P;w7FGjl0(luGs#~VW8Dw0r$>Y6Pw?z>7 zi?`(mIQ|;bnHhD|)6@LLeC}0M134Wlqq1h1K4bF%&--5Wg`khOH6bzgJlZ+3}q@7Y}%I*M+@;i^^ z-|J9YU$l%B6`5Or#N%nH+V5?t4GQfqoxuIxybrB7#cm~H=9l6d%{JlM%6TD@TV}PC zp#aGfj57WrtyxaCx1=z0-F^Q65AdwJEjl}?6e~CHIp?C*t+WcVDz4^LI0l}mJq>6r zqnSL-%b&>O@vHhKmbcn{<su7tdbDS!VP7X=n4_=jPRq=d&B=GKwr^lq} zdT7z$WNGc9#QK9V$$6NQxw-%c0A~WI&c0~>09fhAEUUmB@$c5T}4zuK*4~@xB4ku9Y{m(?e?vDrOtdv&zbNPMl|& zqp96Ps_Ifm+oAK0NJJUu(zBFYv;`!3PsZAHrIBSReVLv%M6 zLI=*R(UFdDMtXtN8ua}Z*TO#?emZz%v>g{y(^pfRjZaRUfm-$&7=6*>gP_AP@Wdku0t$P{sR6Z#9M@7&+Gx(ED z(b{W$FG;_6U;vhQ_8bzfPs~FCLu3QN71@5;o)7TPhrDB^>V6xGOtZGttc2#)$pWNl z(Pr2N0CAC@RW;=v64SNIjXPA;EOg1Qw4E9Oaj8hF@}vd8AU9B3IOCDmfGVS}yk_)g z)pkGdP+tvvEYURUe++nMQkwE)i~CpY*QJ!Q;aG_YVLBfDYs286y#JH%h2*&gYgKj)R;Ga{ey6)Adba;`>R{F0@?^;!?IS zT+Q}|i{%@Tx%=2TIr>z-0=B-g@pg?Kk8cj4ug$7Jbkvxu+Q~lf5;+mRR$awO$rMI0 zj;5Emmp&o0)uFe6tya!Ec-wT){L@av{{R-_js`|6L&TH#Uhl-xTlj7rYFMr=V~Wa4 z>0|Q*ZGg=vz#GZrDEUCnO@&}{W2kH!;63bm%Ln;+I__SFSVWs z^vz32w2dN(q;=Y?8HwDbT>OEuF`QQk@K51PGWMbUnE}I4P z&%NFmCg4W9PC_Xx=L)`+g|)jhmexG$O86h+ZEwM`>y{oF*R?GqtGe7-+Zm(UxebuH zVT^Yb5A5sWzYX|%;*Fixh@{l5^swc;`w35s~pd5_wM_zNEjPkC?2mD04ZA$UNt8%JuEX;(n973qEKF;W$;U_gWBAM9uk9cGpMBwP5ksT+ z%E7+Q*H?N?)wEaf=Yczjf}CK5V}tW@a4Pwo?9rQDi{G|i?aAT)02F*9o5B7Sw~l7k zN-guPx0P*Y0+8DyJa2a@fSe2r_v!Or!+(#yCHO&cadF|k4+;2+&%&+Yy$;egkNalS8*zIk*<7!dFodaJysQQ~4l67E z3Gw?%Xj*57Cir9Gud&+cclQ2ej;SgbC!XN^&lK#WfS4y^5-_WVJc{D~0N|i{CxYxe zVWDbX54iC8hVtHMZllsCj&D7c^0zWFXXb6ic{%w#E1p+%IU2GZl8N5S`(OAk!QMXc zRgZ*z9sRSzJ|J%{c-K;EGo;)@{ zKQ`cf3HkcU=1Ar!reIiRNj5W;^gk#k91m)Ca@CX6>pm)LULJoL>XLXqJwiPO>gco) z-GSzLK=2qTJu}8~ag3bTH>%t%;b@dH#^-Ti-yHE(=WCRiRneIwC2NLr=Q3()H96 z*xm+Kj`(%?SxM*)NZ^d~T-+CvS7FQ?PlobHM261J z{M;^_ta%v5)nkmEydJqV$lp)p-j6N5)Va=cf_UlDw2QjXmvX~PXEHAJk{0{LmHz;y zYDQ~O{j^m z5>9it^vN8WQEzJu;dGk|J%7bIMVwPLkiNN!)_JFuM0V=Uw8^=#@{fFCy|dyU{1eB- z-U0Y{d_yL`q3aRJ15Pa#8DV0pll!?F<#tsB?K^XV7dRE+zAn%$G~l-D4fHysIXBHT zsPRdVFk?WVs`7a(+2aO}5PWa(R-@tT4IfnT7O|^ob|Y=AjpfsrZ2%irY90q1eJGbR z*qdGIXTAGjn6pW_NgeU@{J9lO+nX^eeeW=HfPccEzSMTY^DCZIR13~Lqs}jhFLIkf<9hxyPwj$*T6L%BP%xMaskK7iezK= zp-0}x;;-sqZDsjXZ9gvM`=r)*+LsFL^v_dTZ@4QUc>(A)_QCEk)~(vVlM8Lf&CvI% z*O719(XJUkixpzt*E(r=8+UWG;H?`AO^Yg};mZzW@A}fN-Ho|fvb|gQ4{E9AmW*vJ zx1i&$IH{odI!K|hlB8r2-lujhQSOOwHWm^3Wc}0rd(?PjE7#?~=ke)Dc{0m6MaWhl z4l$l7oBsfG6@Q5CCp{0P5?3h_OCVAdt}=6gdhzX6qKka-$iFg-i~-WBTENmstNybr z0MDI4dk`f$!AvU$G2LQ;w0m*s{z;2fb<$=lkF-S=8d|aPi~a$qjv4gXpe4s<&^Cp_ok2m zJ+OH`lv!A$PV%g-zjxG!ne#RB@A}9?{ogm zGC!66yk@w$PJzoF7v?8Em0J69qj@K6jCjc7{3^+Bmv-;H&jOms`@D7I98!t`I2-pM ze-=8Q;-)ihZtISxJQ|TASom$(etwkYkN1tYJoEyM*a)z(lXg`>9VNco##z@W!XDSxoXxWA=}<*}I-q9AvNH+;c~b{vKF(*(07t zxv~$TC94moek7y_jd>!fIm!qbNN>LB!9~>{7L@LUrh9_4*vkhULgIRWsgd{Ydv<(>O(!f!xFOW$lkk2 zI3qk0$2HV=1LD<>#E%@^e&%Z!65S!SN#z@+Z2Z_??{wqSG@hcdlkqcH(sg|!!nay_ zu!e0-4ZMpUz=22%ti4ya0Cit_#rTWhX)pf(XbV`@Mt|)A48zPBD$AVUasAQ7RsEtZ zE%YB6+P$vW8I#VCMJDV`yQv?-!~jnm+SYG|cM;x0B(pTp{hY5@q}`DGbJMqehP>8q+1FaryeDs|M=TdN zOgz`MC_^d{o)1IEB!4>ePm3^W=f#=}SP3sI=DYJGw|*lIoT%S|R31;EBDh~AE3)Z32+SN5Byf-Nvueo-%0aM?c924p* z(zM&xyRt@_39aOiVdG*ClzHHh{XJ_FHjD`(aMc@zYY;-@A$!S7_{Z zbDzZ5p1{PE?pL5aNUfu`hGTAX8-DG8Zga(KcpY|lgtIe^;|!#Mj-$U?%TJ!^Tk&j; zm9ya@vg=FcFWni>r{mV1r7t7ae`mWnb#I7zqeRm(`2kiSpsA2HcY9+DKNDX-4K7CU z9-6URC>rBOWe1X*yxWF2RX^<>0Qaw+KW2?A$?=M9O|Dr4aSMH$zE<;3Qakdak<&Hq z9x7{}4C@fsnWSdXb*S|i-X_Fk#KezqGHAO9-JOoJrd@bXT>j0wvXs)@N;#*xB^71WJ zzjk4HVPtKEWIuN&(|24|bsOCBABehT-J9u?`Pzlnn>@D$DW`m+ux@aA^aFwhM?STm zG(KFBG>d^EnGmtYLF4)g()gdONd}3a={Hca%y-;KV}CREj5@Y31_1nbRecvqyzza! zHg@o}?x6~|lm{;|46$5isKFq8MQ8H!#U~APpfFNX`&}GTh6m6kaOT=%6WPhD$Zk?aaL4z@ZXb6ipKfcH(`0WW=G@WneTc4~LzQjj zjiLp7+B!|o^gz7KwV`c?StTIxj$=6Q>drB^$@0m=L+CMfP}#>)|1thoSS_s)OMO0x{; zuoBz+z)k|LcYYPGJx;B?1+wI{;g6hq-3 z7iqes=9ap&I!uOtB^)C&j#Y`q4$=YVjw$(}-%A(16L?=i)qE4;onuyAL4UGs_gcJR zKFHI*%CX6xn{i?Y1A+r}#w(4Dt|cuF<=9sWdw)9gZ;O8vJSXGLI_0#V2HbdmS-PDr zZYN9K@Jz&$BS{$Ho0Eb%X1KjiK$A_g)9xd>vAO=xMwG!E+orZqahD&%xaR=#@}AUg z!FDOCv`_OL*uwnhtt`sdD#9!YA0=|UElU)Oa|X}dvnkKb*1BtN4R|k4@Tc3gZxLVK zUtOt++fC9V3w3KZUouyad45>I45KHJgONv&Y;smwOcBI)TtAr^-II@)pXNQQu=s27 zyIuG_t4(pDUbUNCe6nFxImjp6+tT)gqc z)`#OwURmxeE+k}YbP!4ef=L{P5)gNF0}Y%JkzY8;70un8(|Ix&VcM?Dr0w1JNhh(# z8L9O@4ojivnr-Bd43X+-B%&}s)p>8T4eom5(y^60tqoxTcCG>8@;J^t3-&DithC(|_I#4ZR=c>mywK&GO$>0nlf`6m;Yw$8 zh)H}Af}mrLDyPD4jXwi%>on1qyc7Ed==zWC3E~|$P}1)|;S$h6e#4gh?N@z%Y=;y3Nv;wgSQ z-AQ7;BJlierZujgX?tX@*KW;~dEk&K*u(%Z`JZ zRA;)@t~DR@JLO_k5hHQ7F&~(7v5qo+QJ#aGuXosXN6sG({C@uc4J{anUeZUpuv7@B#rI^fD1KA(DPDTwzM1$#@NZoB$?%5z{t^v+Y_0WU96x8$p3lp- zwtPt;o;cU$k$@->n3ds%Ij*zz#{HK3Iq{b7Rq=<0ZmjGzt2q_#?s-!)vtB`@2(703anrucpZ605v+@W&qPzZ;0`Jw0nS8E!6JWDKegCm%B(O7vgZ#tkm_;$@Atsj6$5I^AO0 z-s4Y#DV-&el>U{SfZ`!4>;o+|yO^{_OTxX|=i$M3aUyC;$i zf-@Qsv@_u685qaqd*Vmz%i>>w{{R%VOMA}`>V7cM{4Xqb7x$vVSnTetn`!x*_;RNQ zYY+%MK(EnH82J0bf3jD?L3wc*()4>-65K~)Y$YODaz-Ok2h4JF!2CLVpK<>H1tq@t zg``Q~Q)8^_a(J6kxzgWKhA6GCA5WZ^;SfMFzJAsPw{gK4=PSz^l_c-bwHTx1pB4Cu zEmK`-ps=#jE#yBfrMO`nc;k%c2iKfuIH|O+6JBXr75$yP)V7v-p4GVWn`>Mu^j1A~ zgOiSg?v$FkyLXmiS`K~W6gb@~+d!HzzWuGSr zkf4Au-v)}2ZCE3@55>JM$M%-^&o-gq-D>Lp09^4PeMPKwB{73LIV-2zyKu%h@B=wT zYyhL6t6F#b6YJuY=YuspYWq*qbW3eDB$QfS-KW~F6*JLOcHEo=1cFbeQ{v;qZF6|n zOXn=cLoPrn5R;w5=yTJj73!1z+`kaD?+DM~y-!?M(_Y)`?9o|7ms1X_zEC$Y$QgX+ zsp@J}XS7EqndSP0?1su164plKg3I?*dS}Cj>9E~3t>iX$ftKFoper5L(}S`@_x7BFjN|K4Pd33Eb4IbsxmPM#jHe`ma&SI^ zrPX!aPgv6}EpN3e?Lya0jK^yf^0bj!M#Pe_u5h5YCml{`u_+9W`&sc6Ho7gR+jUE; zr${X9<3RICA>m_>Jb-_?2o-V2r_l%uR}T`(vC1~Hqhu+^Zk@v=YsZ39Ws5Sh~Hlg4W{VIjw9*mk0=>U@ek2V{z+&lg29=c+f=8^KM{NY{@4c z-jwbdGdBL&q>))!zGW?iZdCni&9%$*)U}C~LoATO{$@G=20px3qh8F62^)si&m)k1 zYlzmhds`11UJ2l7nr$u7HjTbpwti;peX073UC$ZT@-G>)`>uA6?sMsm^&PakVcj9m zTzZ;9vTAoY{n#wn%N?pZ^)#`DvRq+XX~7`z`S+^W&669~eiv+i#0jEH=bT3y7BT+- z5%j3800ZwZ-P0WfS+}xL3bbLEV`}*fE~{{T8hyeR6e46aBdfGS9DT7SKjeDE{VuS$|Dh~v20+k<`Z zjhvr)k=ol4NA|mh`Bh<$g$F-1S+~)Av-8ZSzUEwiI#rcJuGpkyQldoI^1=gy13<6 zYM)L|{{X7Ar1Dx%lr~u7o}=7VD`!NLEgwKQ^~FyhS)X_BH*^5;jbT>P<)YfFpp%Cjzsg)h;IS!&$PQvo)8W6E7;v9}Vs?#c4=087rN{ zk@c!4)WGq_gl#-eZ)+-erS7q^>Q`E>=1n~adek)E4(I8boti+evdA zPOf&e>z$0m4uP}N*in0;d71Pg1;Ky1-E-+#dS{9B?-j#$EKMMW#hMwUkqSq+ec%b; z*B9}_;yv|^l-fRvW2#SgJb0Gs-V#;>Cm93|N$J#Lu6S?5Gie_OE;PMEbX%>a%d#Ae zz?_jn*pl~x{ubEy8(-9KtOu7KprdRj?nBOa_9XrsVy$@Z;th|(oh$8E>mZHa%Z*eG z(wNj_iGwl>f=N7_U=C|5_NcgNJQZTNU*Fz^ zT=qK{4trLf7023sHftNBXylF4dXdQjH3~rYAI`WPzjzGo>wqy`ckM4d z%wHGp7@eXWbs&UmEJ4YKCiw zRTknki*RLSZumX3`2(C+zQw5NdbF`D$s+0ucFT}hx{`UvetMemf7xcvOZ{71k`o`B z3Z$WBkRp{En1X%l+-9G0f^SMtWJvbax#cDXcM);2M8;e$dGFW`o+V~h! zSKr>bJxY8G1PyB zW@(ze)`6=>b!$6Y&2B`oOBv-GvkyaC^WOMNQuxKI#^9jiI5^LxH&ljO9Z92+yt$VRoP4q={x5v`_p8~7?rUD_mmVS3X1bYC z+EN|-xRw+r82h7v#cOD@t)qqvyIgGqjFj}p_}4uRvrpx+?o?tyRT%s$r_(LG`2Nkh zKAYUR7&zwu_03-7c@x}CD-=>Pg+uW6;)-)gh>~$V|+qa!B4^P)Na1^~Fu5 zt;Vq((?HPw0HUsB%k3;XFwZUcQ*A8P?HNy)S2)4rY3G`oN$~q!YKa6as@Dz?NjM)j zeESZ63a#`OhKGebCwbzluP)XJ*_D;0byD6+7RKX_!!<`+(e3{Lwyxo~o9%JKGsc$% zcC5ik0l@bIBkNlp4e@;64t#5Mb)#KfwU9}nPd&t+Xdf_5_y9QFh8zRHtQ5KOGP?tw z<%!@APuHzR!qJx=&d%#kgshV_+LB!wF|;V?!L!#rtKENO-`Qz?KX@y}8l}za$krt3 z_USxNH- zNZa?Z6q9j4>yI%D5I}Ht^%&;4nRMx`qgHsXQZ{Bm<|z@DA9w@m4gnoSd#A_$0EDaY zOZKVpM1C35qqelRn&10L?Vu{Q%0pSlTG+Xr}%?e@tvH$ABOho_e*rWUm-|%b}%9GKJTV$qWzqk!mxZv zx47}75#4CATgu9_t2MjMIZreuTW1Hh2_rmK=f$0ScDby_;X9`A-HZ{f%g3Wc)>iij z%)ctO(IcShcW?+jsw!Bh-1qMv{>@sa?KgcT=Zm$={VTHBS6YYT6oc=JZn^qa_S;hRRjvxU^%E-*x>S%7X8ffy~j7#;WgNBd#;f5o00 z@vnybOAU(Z7wavzf)dWz^$WicmxZ>UApvMzX4(OAnCFqVBaPnnHT68V;kSk~zYTm+ z@UQ$N7T3>jsA)F3Hj^c#+50}LbP0|*9?D`FV+Uv`M%8ha7{zcuw%5Tg4*Uf8k*4Tc zMy;%B`j_@{&8i#VyAonbf`kFX?Q&P0ybSZlp8QVMwTu0JCf0@A8rFkt7MpaJQW1CN z$GDa`do_eLg{@>hm*b zS4_wTsR21gz&J(*)R4ZTQ3Iqvd_hT4<^v{3#)Ij#d9_4Tu*k6q&JtAD-$U>45VeTlf`qt z@J>I3z6kM_y$p96UH<_5CjJ(8yqfLr3tPtJ%BrF(0hL}ewYka9O6&gsY%khZRq?mP z`wxS@3_c?8#u^aop-Q*U+c$Ksb@(of~OkleRDp>;Mi(ua#~tS3kT}!whc6Bc7n= zKhnO9{fjjJ01|vh_}!{}CD-*Q);t@g#dMe24y^3(vOzW%$c(q{;+UIRX_5 z3Of*0a5muJo}VU3to@SQ?LX?qT#@%jPx33QzWDv(txMtbJ{7z19=SJ%)TsLlU9&<$ zoTwn@f!7^49)h=(K5H^LtZR7V_J;Adjy@P$_)7D2=7pk4k~GoUmy$iZytR^1ovOb+ z&`xoY$O9ZsovU4VYge_svAB}YQMF+;wZt;*k{29?L)eeZSI{2?KWM)T_%rr6@qUG> z+eLS)O*D{2ZM_s0*T`o@ zuK3?p*XO^wywtTznKefL08N%lmv_26b0H_^&Ierd6^`MgWKhy%54wAMn$YlMPU92Ry^O|B049$V_ zW3OzUI#n$nkvf_7CMLXPkQR?WAXA1vg-LZAH2Yx^WP(r4Qe35~!)i3YDIgJ?*A4cN^A9pL+}xHUx2|e@ z(Vn{+dQOEM=9M+mTnl(D!sU5sWI4bX9X_WW4;4o0Mcm9z)s1tPYScQVm;57kwy?{Y zmwdM~1OC0qAwdVG)fmA3@$Pu92Ct@RR#Gqac-1ut=3go9CS``nRA+FHq>RUppDMd? zwK{$PwZQ-3tUNX(?hJoaq{gul4x=G1t5=dat9RJzTk5cT*cm1WW92J^AdY@1A$a^2YD_o8DwTwAfYE8hv7_S+h-<1 z1|uGvd(!10?q=#2qFEcv+`lhBPg>(O4NFhCyVvCB%#I~RlkcwpOI?+JKJ{z=O7A% zeB=dRu4?`Asb$-e#1H@v^yM%?t{DhKOJdwJ%9+_PhxoRTO7*mady1~J{_$5Gv5-0nk`yGB1(ZlYKBKJz-#|%L34<|a&t+rt8n}_{ zQ}X3UJn@cdHMK}fvy<}u<^ztr^G}xd%NSPPt;r;C2W)%M%hY~_ttR?wJI0ZgHW>wy zRmzV-J^qzDB3|7yyo!=!F;EFVfU1db&Q?Lm#v3A~j$=9bS8HcEH7#`yA=BDbwfK=wJofEVMWns_U%7{nr*n2%%@mPD+pX41 zGcMuOo`cLjOtgGyy-MhN*&-3O;is*`M)OpfZf#~#1oQbTsJw&^!u^dxbL zdxor@1G+uG!`x%PH6uRJ@{i%@PfDsTep0KJ=L8ebfA#9h+>B)4D*nFJGT5cD5Z#l8 zR?kfLIHg&czF)ijDX{L9M_sIXdQ`<0HQm>@K9taU3{%RVx~=;CYE~PH;lA%9)KWK> zwYLRj#z{PWbrZg13OHP6Ip{s=dX;vI5x~A-{`ap=DY7J+iRE^T;Ga&JsL;q?hhhHV zz%=NjX(nCgBRJf7#TV3R+`VOLtp;UvQ=T*2QB*Fa61OVMtHONU1r)5uc74a@Y;*UC zBZEqA*pr`?lwf<-MdkF-&g#smw=7tWm1wlnTP%u6QaT^vuRqY}XtZNf^Do`o_ekJ+ z)N;mr(%X(3x3xmjO&zh=swQR6CnGg1Y|RRW@6-;I)x)6`!EUssoh$%u=#J6 zM>*i)j-jzf!k#v<@#d1(nq=GKSsFPblLAE}u2-sx^S_4rZl9w3Wbq}ArM6qioLpJU zB4p)`;s*qSh8;NhXw-Z+C&3>U!>wu7^IT|mU%I`86v-vBlal_sM_x11y#D~l9yXK4 zUlzZ$G$y=-f~+==5yZ0X&q0jx82r6)PC?Y~zCLI=#g&b`@R_f4I9$tf93=U+;CCGI zoS&vEf%rw>_`GT3yJfbTTUabg-!}gMottBfuN(}VbDF>LAL3t$tvodjgQ@(tI;3KA zF!^qhE!-mkfHTfVTvWfaI$bZ1T1ahUxrRGtOPM!q@{p0V{d0kjucZlsdYS=sElkENk(7w+JYeuzKJKJ+8VVvjdTKa~YYpF)D+(!hl zvCL7)hTOv^ARhhmSf38HyB#CI+D*OX<-9USZ5lfHfV6B+0FTSJ8LtrW_r$$gKZ~+Y zaWu>Qk$H%1m*qrNZ%_7@KQZbLwNX5`J)_1K8Z0`G*>!uH8+W?3l~7N^7}<8X2izaV zyb?!;;XlNG^a(9>i(6LOtlu&)BPB@#?_;>{SH3!U?@#!T;)`3$2AoIsa13(B6`>@O zS3kvpj(TxYd=Ky*m*b1O>wQzq#k@-_LOHg+cXNTxM;IXb&{eFDH~paIT}R@D^xI5+ zdZX-R+UxRz&$t8+!nm2OeD@oS41^NBn$qJA==Em1A;g;t)WRA+N5DvvghW>$3EOvA%VQ-be{#*d;uWUUI;=6@4Sb2MuTghmB`lbn@h2a-L0mFw2`K3o9M;n9{mijB zC4Rhhs5O?nk4(2VtgUxrKKI)DL#|KCeX;3PAtL4lX(RGkGaTVhNdV*X1XPz2vOyad z{I8Q_gML-VtyYA{@PCRn_t5-CmLDcaH0dHT+q{to=6tc-2Z7-gz@^*#7`G-zo-4^&Y~l5cedz((W3_-L)q+lSpD804O+NX`g2 zJl7``tEw4uxE=t{QU3tety8|_+gqI{gbkV0A~*A0C5ovpPrC~N{MRPUG zpX%Ce>=8<#ZOnPv2;(Q53f|LhBTHL#R7m87%b66ASoZc9z!>YA?LTCX80bC>@vQQA zhT0vs5Rq$fHg?;{Ic_txcL9yvbAS#FWO(btHx@e0#;G0EmEN1;E1QekDXo}>G5Lpr ztOF?-$0Oe+r>OO@Pd6I=rFk{Q_UV=un9X@Hb14|YhHR2g7^F=>q|$tsSv<&OEW8ga z4*vQ5DrNAE^{<15x%Rg#Ked#letBy!LyVqUu1K}5mJ{sxv7n5vX6?Nj@x9V*+^xReWa%Kp7`E7|A%V zM*XGrFNj9x!@7UOE6Z7eTQs_Own4Nf%8c$;lIN#!)DLHJV;xU2xt)BEBX0~r+@s%t zpGwj2mV&-0@gbyhK{W(%CL$6f|adR~R_{{X;NJ`(Vbt9`6oTwHj9;M(0l zK#nVHe3EV>EQJ_`3`q>F&{dy+))u}J{iSrB8&GeyTj@8B@?Bb?*fIboB}+1lsLn76 z&T-8|r=e;Zj?+J2{{R^3o;sgNvy)GIKQUS@LUPf@@f;n+IbcVj#(tIb=C}J2_-odnRd)BQza>gB<#&OZ>jn9r+g;y7Ps*VJp)P6F22>NT+be#YDiXeQq7ITfrUZT;~)cG z)9{=A5{)suYvESZrqg_BHH=nK*xsVRBXChs%gORD$i+t>Fns5LYKMz|X}vGPUlgr% zYfV2}veq<-MDb5MM-+n+67gkKepX&L6zF>Mn)HnuC-$pYE#tPh zk(o6QEXW&Skw!>7k&JE5J*wSC)}xG5XPEfn`acBtlSS5a{XfO}&x&+7R^Dq}droGw zORt$4L{LFR545U`4aG>!eF6JBe$Kuqw$rrTb6*yBekZn$d$|&Ak=;Dfj1}{9wz4Z_xsFx3@>(VYB#hfhQS)Hr4i6RGd`I}hdEuJ~ z?0haOVaMG;t_$T-u}G016K$f_oaD_MG^6 z;=dF8IlI#QFEz*ZlCmlCH6^wCI`u8NhDpXa7$>G`Ij^A9QRB8h1$1B8-{FMbD6{bF zw_09`XVfpF)NSFoo<|r}Wef<6jBpo#2{q?TXpw6%}z zpW1P4DU$3}kz;a86$b$G(AQn2NAYL&eDJ!jh@Vi`{5@YU7&_PCiP>5 z-GIxS_N~v^gW=7Oh<-iZcFZBta#EgXMjwwj(nwqOFs9GKbiY}!v7!8~wkl)ACF zv%`O3e~-Ek?AznnwXH(OQo6U+H0QO7cvVD`5bDYz-N7Z(VdM<;#w)P>vwvtkN5o$k zw7(p9fBQDh^TTSkHuAO1R~OduF!Ox5Vg$v7+(`ho3lMSAzO?Xf?2X|+wTsPD!M+@5 zZRTgwt)#Mzmc<bq@~d8IIXP zZ$-FBzIJBE%_iN8xD4@%(lbt1W-`%ee7|Mlonjvvwz+Gl>Z8PRNiEY~+sx73Z+x_m zxlUI(Y~zeoe-->-@i&gO3t6>~5o?;1wn{=9tJjle;e(8x;{fx{Dmc7GnjV7;mbX`s zYWE&xyy+Q17m&(6P;rvY&QIOPu4WN&Z10a53I|plKM`FY!wYo3@oaF-CB!y+U1qt9 zOgGC8M(uaxr|;Q-7>wjUd}sR9acT2j-YVMK+}zL6BZd}v4l+&@WS#*( zN^P%*=87`V?u}VODL=blImS589=OdHcd-X*z<`$9>i`viYxPcUt0)p!a< zGoM`ZRS{#J;x^(nj1a&K?({jSwci%sc(+}+)U_#1)%D}~lghwl+ZfIO9N-Unu#v;6 zTSk$>mQpGlmXw8+vz(ESl=K+s!S$nX5iMbg2%6kOxBPr|>2QTUrj@ujbbE)B#sx7JF~;?T;B%0X9RTPj994spRX;v3_NU9vj) zm_0LqJ*h^`+)Wxmxjj_UFeY1nrL$BTAvEb9SKNV_8;ScN>*&))}<*ucP5F^bdFblU< z+mDnU25FHaHZ)lNZ=jgV^FR9|Cjg#< zHIs1+k;&xBjq>9-ApU-}DhT6uSmWK!>>hdTPQlIGnQpDp;g)DxNf~jtaki1~7IrW~ zp`?%R0CGU>`PFZl;#F1J8BQ4Bg&g|S)4~;BYwnF#_^=P-PeET@2Q2Z!v?|HxWMmEi zQ@r-h67+N!PB+KS+m<1#b*r0drM>L*h z-z+DX4=uZQKTlexcMq8Ztb{b1es4qi)v09`^8CA(jxs;bt!K^VM{e?YEYY)LcSS>= zUtaY(-s0Tk{8y{Rr)koUE-RAFw8q5zzJ&gDg>9}jr=;uCG;bZ(mW4rIlm!?dj)U^; zTi!9Zf=f@c{HA$6>bKof!O!9CSsF%_Yjg1b0K@^7^!-vA{;Dh>}YHxj5)K4|J zl1FnQsS%>!6$hdIRT}>QsQI0?ws=F$(p<}(sx#Aqdj2%Z zB)MZLa?OmK{S6T#yh>xoBayrGH4oZT+(iq)3oL6d2MgD?`TEng zfLvi|6Z0gGwLmNv<_GCf=gL_5lV;(SBcVC$DhozgrTLX)bU0#otMJ^2pZ8?$=v?*h z(zBF6w|P3UEv%BXs}CCi`FeG#Pa|3lul}r&x6qINwKhdfiWlZ~CD`{q)Wm_BP6DVP z^*w(ITObla4o&9F4uly-Bxp*kB811a$SQqRAt5+RWc5E&j=kAKy`cA2<+t|-9+3%$s z+s_$EBW|aTxE(#~u7dS$q22d@9fuW>;x7hiUMRuTEMdBtIY~XhuG~BRlslJ#xQBKNr=~O-%E5yJ(C}%d1EZf~ zZdLo-WOb>gZRpX;H^$3?G1{Rq=2?VDY zVg5gtseE&=lJDV$t+&hbBa3j}I3O@N`s19QII87W4yVjdF2`0yA1ekMyPr=&I3JaI z55IM18(iTp zKF={S#U!h>WMj((Jq`~Zwby>kI(5FMu4)&OMv_f$5(tBgl-$Ra{5#PY>KxB=$G#%? zmTSKnYVrAN9^2VV0Hc$f9G?9LeI`+<$^MwF3j*G zW7ubaYwceX-Rl1U7Q8QOb!&BKx<}Zdo$mzurdy4pFo@J+X!R#Nbg!6x4)}Ne5)TBd z*pWQ>%u?q%lc!Ziw=f z4cnzB1de$6bgE5zbv!U#KvFoQQY4FS-5~OF*!APutoJaFBU~ReukkU?Sf9t9D!jl+uU<`J=1Hw%nXers%1A_UvZ!8H9OrFE ze>^%w6D_a7z#OMr$g<<+S-CX!mW;%0@n3dYt?A zHPC7rCZ*#oS6|fbrMFl#(;7^Y$RTIRBVrEZV>tFbYX;v)Hrk@cGb|Cyf@CCY3H|bV zbmtz`q)d9Aqwtgd5Dju2TGQek?e>#&(I2o~K@nwvz$Jm($YOr)1x|6mIUJk#K*R;i zb4I!~!?3fvnS7BnYD$?IGD`Eo2~ugHl=YLzTm$u;{O0B z9gp+Xl8q2u$F7+)run(W7MjEa7H@dRp^*Ry?OAu<}Zh< zd7{mCs~hKyj9Pvqg`yF&NYjoCPK*Ew+#i^ZfY%o;yCl&@-de*V#IdxHF4bij#&N;p zuj^fRgFYs=!>DNTwS=+aN!}RFRR-e2U2b0EAcjb5D}{LASiP zTUbra-Kav%Vgm&w4_PA_Q;;$TE$d8H>Ra%CgSBmY!`GMA@>oNq+aD~+d2*0NB%p2x zg^w?{pK--EN|AL*@XRe(sq(`iWCsN8$87Y-^{iXnP~8tMOL*;Lj|2#_8Z)jzeooR) zbI0XfM}Z@;)NT!}<;V7H(+!rAOCIZT-2AeUf`FWS{DIth0#4_B;SY~KA<=vxrub&x zPqDny^r_9jMz<3?<9XUfae&OkV+3G!u0GPuwT*R+yiB4=fFPVK1)pf#-4JBsEI{OR zr$>Kfad8uAYkjB72k!3PYn7FJ&igiiLX2YvCz|OzMe!Qy-s}5LJN-WD<59DdO}x|p z0JFusUuMV!TW<}V1_$o~qa7#+omY+9!`}sD@YUCY^{DPVWueJ3>u!qg8_L5ftGF21 z6-h(4A-5CTk2diai^q!+`%>36On6nB`QHi zY+!(MwfhlX>-#DG*Lp94^c#IM##&5XAGM7xn?u!Lw3U%u${p=DHsdD^fY}(>p|jS$ zXz>)2T+bYK`kLND8nn#I6UQ7I<)U!r#MM7l-a5 zxrTeS42f|rNdJCaM1D#p--&!lGm0E8dGnjOD}?V8(8)6(0?wu0!L zlEt?N=4|d5>PgRBoO50spnM*@*F0t70jBGk#-D3%I9)y>?eVTU~%=Xuf;m1p(K!|hhrKot8ep4Dp6s)b?oL#>jjL+k&l*NbE@+D>uY2O|RQ(*LU6>7J9IR z{hI6Mo)%!gD-Zx>#~c7j0P|a)v(|;;EhFKyI&ICyrE4}GMuiUl0JR|`?pz#&J#p7P zg$_)7wj=TP#an$p#M*tvoh{_oR`H8@ygJrtEzRWYM%EVrODgO;h`{^2*B9e&0(fu5 z9w5{_NvLV#Le!y|Y@`i(@Rp5KhR!X!B1rOzyLbm~epAO`T6S6_mX=Q?#Bkcf7dec8TOf7G#ZC1N zQ;hgq;k{GhRJy_O1(bJImh7o*YHijSdxqYuyJW*CIUEm{n!)%Tpm;yv$HiY5Hk08G z6Hg{7TzDa@wS`c*)JeA7k85GxVqJlsaGiyu6}haNZh-9PfE_e z_(S7O7fjYB@b8H%bqOu+*6FP^%Vm~k!2Q-_BjxhdxEn_7oRP(N_r*^S_?z~J(0oB_ z<4JrwsA?V$i*#D9mgd(`knVFFZw?APXbIy8*vHJo8mP%3N;)1#@Dt#lhyE_>dVhoe z0J3#Q)^#Z+NOds6)&YRbq?X)v>`oV9Id7#)@yEg*1O1#nHQeZ0$AMqOAK57cfvx;f z@ zmQ@6>89l2<;Xb9{9~t~G@xpk^Lb$cnuB&)O6cho2zA*;qDsbbcJz@ZDw43(gthF z{{U#8hdNJy{AYP>qu=TJf~!co?JmvJWhTLC+h|pGQa)50S01(5e#So)tv_e&XI9aC zWu>g13GqNC=0?)~*XH3FP^8Lw?og&Y9ORr1qs;tDnl6#!Epo?4x-;lHle`*Gk&J6> zl1e<2F=hDz1M88D=Zew|sc)eUIvL&z(!5#XuM|UPrRn;vrL3wmSgx9{9ng&w<%1>| zC{o$^ut34iab0X5vZlH|7HPqA^TJpTg}{Mfox5TLu?ogtGDLk0P@3={iA>2q8<Mt<2mIy**45a?^)05a%>Z5Iw%Vcno_<}znu^-B+I2*A=_) z`@#dqI)8}u4Uk|gJ5m6$d(=>bSz7|xdDkPqmD;vtz+V^7kon2yicrJ`PXZ!S~1re1zT7i1jBs$ z0-!)+QWRq(4y4oOb~Dqdg$rou;i;}9n&KT$-AtIGnz1dgFsapbATT8iILj>}YS%+h3FDQ%&B`_-GxP7`MerLUIATR1$vdGFI6 z)l0b%WOk~?NZI$sxZy$FyZ->MOud)PkSL7CyKqY{1M#WuwMd^yf+d98O9&!H2j`TN z!Sv~ll~i6aUD7V{!{!8IfN{ku1&2WzJ1VN8?IZ63cLFNYw*@&hTH-{8Z{9cB7D0kk;|HE8=!qxLd?l`Uy5i|{tuE(OYe-t+c;Qe? z5QBo`XWVcyPZ$-AtlW`c(7c~2sFE%R@@{K7|6#?MPuuC z^7w-MTgMwc<;$#U%McAau>n9lXF0}s{3>19ORjw}RCeA~t-U} zR%qf(l2{%FNk2D3o~NyOUXP};_+whQiEfHU+rn_mkf4%B(29j}Obr$&v=RVbX0ZQ)Z#QT-EDz;A< z;-i~W^R}x-vAUnVj1x(H`-s(3aSg!FQSU~TsvR2UNg62TX(RH=N(ogzYoPhL$Lic+}t+`F@Z z#@wjL1K+nayME0#&ySdK@9#_YHdhL)(sn-FQ{c1mCd|H{chaj?f+295dU~DM>57`h z2HYK23xS_cdPp0|n6S$x?pGY2$NE+H=JO8R0UkEsj!g)m)`g-9qZ_mHanxe1nFA5I zit&&KK~PSzSQy)BZOjfjpU3d^sUx?N;dgm5ahA(382Z%6u23$e_ag1bA+gi(rX|?3 zn6!LK*gKC(e2S4Tm-4GH%j2;2_oz%jqK~{fd!J4!P;!oWOTOa!i{OKt^OOEHYSvxQ z@;99FxyEXk+Z203u6lqtq%wKW@|I>Cj&MGeF2T#K%@K5{>z&Kj4UV5$jc+$f%B}B$ zdet?vXL8I>Y_@p@oc3XU^5dPvlh>M?E`{8(@+@ekM#Ol|0335qTfD}6w>WICKf_3n zLvVgjv9k>A9mmq1EkX^e<+p#ApKg8XZQM5!JEoCTDFAK3095f^3r(!svG;HX9Mw2& z^5t1}mN?HrR~870Zp$2F89n`}`VQTS_Y>w<%Wd5IflEN<@n>8$N$k$@ZCC1xOJ9FgvS zI?KHHaiZNB8~Z&Yll#y!M8`eO(ksm6zNbN}sA*8@b~0PtLmZa!3>eu%D-Qf0Uuxr~ z_*r$~d#0DeI-SOpfle$X%$9O7W0FI1olo5K7_D#kSB(Mx07uq!cmki1M1g`1!=8Uy zCe!>$rAQVHQo{XJN0zrX+gSGHm-OR4^tHGd^ZZhq!mi8W4KCwPT;N{XgK=cUlY(0S zrg~w9bKbh`KT@{Vtrlxrt9zK_8CQxxz>a&4pU$vj)x1dv^6#{3E2M0pHj|C2JLErK zrE=Fk9n)-YTH@Br#2yyZrYCFLN4gnViRFOGVDrugZk1O9)8hF@mUGkds``z$*ysCI zy5}eNsr}{bezoIzN5}0(z(;SYEbHXR{{ZPunDY=Z10WBsNX`J}yQS;B57`%RQ-7VV!m@q@=b2p#$BSo*G+ zCb#kb09euFl1p~hEdqV69PWj7hGCC$cOtjFS1DxJK9ci#~khh7|sF5<)!_NuB@)D?jgA=5^jE2hZ$UVJr8kLJV#}!_*cTZE}f&;#dNmq95->G0y$y}hsY

    &_x&L^UmKh&;Wr9yVVKxmz1`+F=&ruK-Dieidv8iT zW3L>rolNojRS-pzs^mHxW_W~aYr&MzOctR+W(j<#4AIdb6er+gbgqRse15++ga&d; z(BW<%t^DseK~M*88m^_vJ1z>(-5#$<|Cm`QY&U2%v4y;7ZFav^UP8sSfW}dcbUvR;^^I{`@GPsmt z)2cVib@ostOmKkF4y~$2mSTXD$PbM*Sda5+DC@?@dXLrbX281pU8%^KEBtuU_6(Ek z;?>uykCO6$Wy~xtSla23GrRON1C^n7|(Cp$}N`B?bGE?B= zTDu}YbGH#s0Z{T*F7G|Ru=k61YP`?wtzp>G9e49AlQ-M92Dt%sboea|X?|Wih!jIV zARe@RjipP4S$kj@OE9d9%K4dd1-q~2J@%yRR-6kr&sky;x~Be>DuM16%b)~YBJqIU@^?8Mvo|b@zmYh=q#gc>zTJwWb-MWl zz4y_ZqYEj$;!U&3) z)oQa^h5}`wFaXYp+q(%QtA^^!gubkMBAZev;G8VFtJl4hZxu+R>x@1SgYyi^_Suv1 zJ&p^52Wo}fSkiVWi_@=EmA4k@_C2}cZM{jcC{fof6X4t-e5eoQ>WrGFJU(FaWUVEDXC}wkF%8V)eRZ{lQNto z+;XA3x_Ww%d~Bp8_+DqCY**SSL7K;=qY<2Yu z4>b-S<^VkZiT;2KKMWENqn?$-lwEso)6NMAFMV30@YV5SiBx#E1-4S{NPRuLA~oud z34MkOoJSR@J@H2{9B{nIjw12OTab^GDu-D@Uuu1Ex+^PUFPu|ukk@4fOTC%L(L{s~ zp4nS#U`nl0vxX{HwC9a(5y<_?coe3XCOsQ&c}ZJJyWF$VGNKwwc6YzST({lFS=XQ; zLQ1G%VBinG4l+FdGT`3N?IZds%2ao77&-19Way4AXKH7a`s`{;)Zg3_Uy2xgu?sRx zR^?yMGi0)34J`JIx8J21E@F|{V@?Q~$z@XSv|(f*j>LC}=j&c~XhBP_8gx=NeDb)3 zBm4p0;K8=yqg>gdeCznMw~1aqfXrLf+7}DKWBi-f_dyC)a#zkHKRYcOzqCXPkddua zJEdqaH)TpLeoX*%A*Gx@xR#Y}bX%1sjmlNzeA!4hV&Z2Z-GaYETC_~lEEuXpje#1* zkG390hA&&Vriv$_{t!ei*go6_Z64ebk8s|g7bp3Adv*o=<)yPCyz<~Ii5Z@NlVdlU3y%ojcjOKy6adg4> za{GS9`>^jF%gLK{L7g>FiM*yyL7AF+a_}{vu*aZ!mH#Z_zCr-Yc-gm?dol?tI>*_c z@0C#g`}zLDXtuMP!KQbMRpCb8v4h1HPY%bnn5YWLw)P`0W(OY;mX6MJ7 z74iM-{O_%0YcZ}!cv`Amo+L#zzf#pmL$fccK(dF~D`)046#w3KRO#1~Z-EPOSt~;1Z%E+lSDq5j+hQfw|A?OfkVxSx z#zPyzn}*oUY(O!^9dDma3LhfJmaQlwN~ZuWz8axsOW7E+xrAUlmd`jUe-8(>{{Vmb zak8y=ziF~MV`A6dp7`C4?08qhWmC!TW+oJf-=*fmasI3fpDH`q+Ikzlj=ngRh1|JG zFgy>_q$m#8hI1x#sO}Cbe0q|ItyS(Hri}CImvgEUQqg$qEOK!;<`&p=>sQ*!nO`u@ zdbKoFg#$<2lYXuigHJbUZ zK0e8Av6`u1Ef)E_++s2LuerbmfiA66DMHs%gp@VSfpd>Bk?OM5hFnR$7il4KRSC{B zRlXc+75M zh`&5Aivryu>feJ@ig9lCmIdbfP|Va}$wGWx^K39_QnGNQwz%@XokE!JxMKH3Nv`2Y-_0o5-E+MHE>QHLVO;YDC!mXG z*f`X^Ge{7gI{?;n`dBF=$|~Wwe>#DH%cr}iQ=4CCjiUH5lQ%b{H+X^RS0q~P?84CL z>BZ2c)F`=-QaK|oZf|LdQI;t%%jt8WTieRl|45$bdi2|dZo7EI?UJ^x!!^S-!>;}d#89eE8R12tn>11_N&fX9*0_a-L2^sSu~{>juYucLSBif`@nb`R zgxWl5#O?B*0K&EM_ux!_CJMt4Jh#N~JKTn*2KmfY4Iz1?_xeSXntqj6BJO`|g?uBC z9c<6qJATTBj}5F{!o{oHr$GSx=+yly?Fv6k zqVQYonJec&Ee!Nes8vqosSkRV%8>d>sXW!~vmc5mEd}%~vQ$x-orXO;EB^|u zzKTEl^5_uc#iK0U96sT3pf86CuWh7eHQUI&ptxO;Z}*(i};mxVyOp*dXKXt52P@Q@>C64&0{3&-6^MvHVyzESfj)uJTM(Jj9m0lB@+WX63PEdOF56JmP^0 z>}yiGJC3iZ2^>!?C-viN%(3$Y63jIVeRsVCX8$E)&F4B5kS~OXytuDbI&*E^N9GY$ zkAeX7&;gs+ejb)@hANw{R~O$i<&gPA5pzE6>tUn)%*bBqVr8~MdWXy2Ad58eSWY@+ zlsfF)kBS8|x7!L|&c1j)N?51PH=CShHkw(;cCn754j7xGGege}zrp$i*d~X_-J+JJ z(0cF*M5~5!x81(1uzd4ma==zbbMKH^ir8^a$B=|mpo)W`TfZ&l{TUc)X-^0j@EsUO zRo{CPU5M<9ngtIzl&F0@2Va03@l)*xoI3aGw^9nl_6yQOE`$gR2PxJUH-W`)+w6(r z5))TiTCV%Y7bN)`S(zfAUx@8DRE3&FsgMXSMb1?#JaLPzrk7|pO7dLLi-Y#5gmud4 z*i1?+ti=@oDj4@8OlJrm0^U@UnLeyDS~*H87q(Q^rIh{H%Nm+gWRYl`5}rqLetgPU zm21DL@*SL%v3s+o!%6#1t-Y^JTSKzseKSnSh%~<(!;ZOICX)(7kF+U`u|%>gRkSt|GI$vvtUx=#`YfXIrv0x9 zVSB;{v_~TzXmfiKWK{?=r85<2_Yotnw8?D@RXQ|GFu%!i-4x2>5IGEYPf7bFL+uqidsEOlF*czEcx+8Vy;Ypb+*)r~ehCU7A?iv>0$hvyTI8mUB~a_(Vc8!E>&=cJ%IzJD#ff+3QZZ{9vg4Q~5g%nTn&noF2Q;lABryKn`a z(pzJsdagU9iff%%XkUd4-@<8}r|7mPr9JeP@ncPAvZFdWE-|U>8U z&99T_a)Wy};v(}8kXoP*>A-dV;21(y4(P}A-(M#$B&m{XHu&x+oF8rEk2G8{z^81T1H{s+b=C3}t(Rofb}_R_c~h z4Ws@zMTyM)@jV3hu>Yd8l+Kv7-282V!b{)g4WKbL&~`anh?>zfnq+|I@~BiAF)dUx z?ddglylo&|RR{5$uw{y~KKD{)L5L`SDJv360DA#V(PD|a5Fhud8&$Xb%E|usOw28Q z;xbnd@~rSw?6K^UN#_GF+$gJlJwY{yakOOk2)IprIUH$?$KYAee(Que0~ ztFT(gWY%^@b4fC(<4QzeL^iyGQH4nJEiY0b{uT5I)(Yk-WP}cM__u2iy1~iW91lRi zJ0o)mabMp?9S z%0oUISz}3mcYR^z%Xw_`IvA z7jGY$G(OO->+cejh@#lu*AcE#G4~Rpl(+FXqx40}SXk|crKW)yB$<4!LY&1^wR}OQ zX@P4M$0eY6xbHl{9XXx9dIem?U1glU*DSd+sDQXi6tnaio$}4QBIrpNoQLsO8J@0q z^&xXt474yl%}O`7ZklDqA~wB+;Q%LFCxYm)5>Zu`pRc6WzYBTaT12sD3m;l8|JIo= z5cU(pCOqP3hMxMG)C%$>IVpe{YsI6YECk|)t8lF8x15heYnLM1$Pxp%D?W>aM<2yk-j=mPfI^!MJD4 z_34nV_bR?>vn<9bgrR%#B=GZmKFB zh9nIniD*MQ-GXV*b>2u3X7=m7bCPnde=^zjB7uo6W_Q}#UUp;KlQB%FuHRSBJgC1v z<`f=*aIduYYeJd!C`z|X|7li|jC$mS1gut@;$+mzQLPVhtnu?RGL^p3e({~wI_iH& zS(=nuW?LNRn|CW@`laE{jmpVVKk`%89sD}OkYL20*ZG303u_!lbk34-`97iV+C4pW ze@}i;x0`=f-tSp-I8EBas)=-A9W2gFZ8krT&Ds-J=LDqm!Y$Q?Gzb5YNR~}GQC5`t zhGC8h&1r0O`G;c)da2&GVCF7QEB3yCcCCDq6)}XD?|C4gjE60dF0*8Rgb$2j@U|?8 ze3zAT%H33Dkv+iI7=qobTL+1L=yVL|zuLL>C0*PAl zvKhCR=i>XPL1D*bPE0hJom*_Y7@~rvt0HF{&C>b@9T6vW2MBJ2$G!){x~AI9cQw#G zRKx0jYT?jjHN({rJ4BV88e=87MlmOcnJh2`cZH|v%BTZ?^GyFqt*iP9+uFTYy7Lq$ zRqJY!7ESsFvz)?}TC6wEt_NPQ&0`J=gkYb8hp@Wh%-c_on5@B)md44*+8h{$r-o;; z%tL9NSLe}-Qy?sYvIg`rr_D6$B~yIi95HBSiv!HDY5xPCbmf?LGpT;bBXKz`n+Y7f z6_|8*+3c1{w36(D^|23%MuOCOcoIWg;=)9=zJr3%#;j}{$#?$nd#O&Ze=6Cz#qm4| zTgv|7uXoY_zM=q%BVka`wUOJZhI5+8=%q(^ikDxPe47%a*YG1T6VWl2^SZ1s@9tDx zhbb=2QC@ew(&~Ti*=8|d*XG;5pVAUOcl<3TwOZcZ6$t)m&IvQ)O&JU<<6SufLvJ8=qDP$&P;N9%y^%9H9(t5@`@7hMti7 z9}OUxtr&K>qTXlU-H5hGVErSlKLfY7e>tV%!$EFj@r$H`oL}Gc={4GZ^mtJ-U$v^0 zBHLZbvL~A@at;6lZlRAHPoj)0i>NVT$F-KJ&)@dPbuImRfR#_94;{L$E0Wh3RmXQV zNjW&W>5_gRhNLfNix4-mH|=bbg|)yfUXHrH`CB3)C`pjIg`t;OZMsu~Jni}BJYMNbBUNCRgz;&u^yeV&n`gaO2fPFinPbmjigrvH+&ncr% zaH&Ky6~TE*5;D1a(){lqR>db{+dEo*T{-;>E>4dbNe|-p<_hh?HyOI9B&f1|wQ%E+ zBySEbn_bZCH%+fk=x|Ok3HkO0^KFBPB~ol)W6nTilRHa=Z`gm4JaFpy?&`<-HIS-M zh)n*!$`q9oBSQ%MG-i{3rJClqc1ttu9fmzHWH8PfW4om(K3{1vFujY|n^2f3bbobU zl47n?Z8qQGHYx`8YbibNu>yV(>2!kLNO!3?9LjudYbP}Cn&Li>BW<}{4Ys!=lk^YmI_-gM4K6NBrc>LWqqtp=^tL< zxc3>WfQQe<542L1wP3qQ#|BM2w)*#tc6W_8>}67GI8Vwrje;D<28F{TB$&MNVu&*r z+q(7K95CoKw2$R0WB}A$)}yE=bN{yF7&E^LL-F^LHTF_6ro2m=@}Db?p!_m6ItAcl zOFMRjwi&~A>K5D7(eBS?f71&V-j%w-?-75HE!QWRttt(ve%(m;--guKbhjCy-ZdML z?OV>YelaaHN_Le~h-pQMl%w~7o6XEckzK18#SVcMD~-woPKgnC+FjdViTN3aNd|wN z>daXMH%EWt;9D9@Hp>iy*N3^IE&Qm<<3e`*BF=5&^qMO)Lq3~B?W$UX0{tc zn{O`VLURs`yg#F=M=HqOC6BLD=fdqx8C%wF`aVKvJqi92-%tMgEHA_{url^JF8yt? z2_SB$&*!IZ{mXlLgR6yr^=h7KOp43%$25t&HgY_X*yrZ@w3XuttQ_^SDP|4UFe?K$ zqZ={Jk)j-p3lhWR`v&8AN2hTaE!a6g&X@nA@O#(&G@2G`yj;VUp7X=ZL(1LfY@AUS zE#<~MsZ~=|C{Tv@Ot80HST{JkekTz<$f2t5hp$;%X)?ZTbF~~AQuHwA(BSXRq%4O! z2T9rU+@=DnD6O)hr6w?qqQ^wND29N1<-wdPV^D$lQ3t#|E}bLWG{h7{cJ(y|&=h9| z+Hk+%k>p1ae$*elSJU5)4>nt#3MdD+2q-@w`brh_R! zb$~z-p40rRc%c{s*VAqWtLR1l^}uLm8Ltp7E85_k1piUq*b_e8yQ*8Y^-=4#Q!A6X zH+T;j+u~?+I;T&+xYV%reh4dmCh(bnSAc6DJyQ6;0Hq3A^&pO;CoOXW`tp8mG0jHT z5-q>VcMvcS0F3s#2zl5gMq>7DroIDF6lQbHzSPk&*|y!MUxBYNo@v5W1ZV@Iu2`A#j^soO5pL6 z_l`X)F5R~|ELd&e?F4by;bT@*RKuRS^q2ZEO}^K?G!zNqLpJDNe4AzG2+VI_CrFRY{L=4AKQ$F!XA> ze0;UrxtL=lW4B-{IWC%cHm>OS1n$QJ{Qm&@>XRg!XPP&$W^8+4nzn}ow{>ng{JV5D zU4HK6A#=#V`?&uAIH_&p^V!DZ^5g|k*V36<1QLGnTlZ_uGJaJj@cwmoQj_grZn5)9 z2K65@2*vi}=5BgtAB9N`!!56t9hc`M5_%q#n;wO8CfD4+s*%&N_o<;R<}O*V z034A_EAti%+t)cEdC#Esrbi<%+z_cC;P=l?X_D{Ip6*T7EO6VhGEdi!=TS)`7x`NR zWb@jVd6})obIW6HI5iu`^KSW@c*p=}81w??e12>E9IcSMLC&cXsMUHMm)jr!Vyw$Q-puB~YpvNGbDty#_sh z{Z!Js0`lEBIHfVER?h5aJPZ@TC3>+e&j*47jdqy}FyJm)N+=kd>Klz#B>yX6@m_B9xN z@3(I6;pgW3$KygWw3~N(j2^h-KJ>|C>OXh5=jA^s#Y+iRbqZ8&&p7uqKV3|sC^EQ*SLZJAO>%hsvM5{6x?BOLMp_dQK0kQ4Wvw{<0Yb>P#Y zD;h2ra3kr+{&e(3=tU7*eanwcq#k;n59Tpa$9k~=-J3j|Qps$vkWr6391aQO)GUj; z1NgWEo~D-K)Jy9hw8W=-_4!C2bp3s6IWNA)aADi?Dc}~yN3Cr_j8TnQtoWC9{DGXdw#W};GIXq zm!>(U@a)n<_G2iI`%XYX&N*$o`u%94sZLGm#NitqE}x?KS6-e=gQDs%`D?wAbv%aZ zasIE5N|(c*3ACM0;v3rAwxMea@WbsJ@;cyfFesw7yXCork~e-Pe$AFX7`}(>+JyTj z-;mLQc=yk-{Og$?3Y)}n$8h?jh+~mpW%5A`q<}k&5$oQHDpa0^5{kKv2Y{8ecD0i0 z%vCt%KlZWf#bn-TgGnKTjN5~%fHv*gdj2#~TEb0`W~H*p16(lNLY5=@$K3ukK8vTV z`^c=!s-%H|=|vS)B+8b)Sd106z3lQ_zvO zVP=s-DwB-o6#I1%%-gp#Xqnlb_&m`?T(m(J$u!;9HnKO$zEIu3>PCOYn8SZYE4Plm z_@au&GIlGe4aKt0Z@Bg2ADI6D8jn(s$0=DyQj;JIsX9l)zSWuGXDSzHgHE_ z%@k4qp4nR2WWWxfjN`9EP}^B6s%|9bB%h}=QBx2p-pz}+?f&xTa+CZg`qYfxcg){2 zXCGX8(M2h42(uNsTc^su>m|q2Cmd8)7)A6XUrd6CG z#;U5jy-6a9DZYksEVQ0fcAfVlIVY(mqsN&mGW??XHqfJ{Gny!&fmY3Y*Hz1Lf_dxB zShbB^8~fYBW{N6+gHVs`u}dc|+psg(XQ%%FUZC<-r&a90v7(Beph(O{uMaD<1|r8?goYQh8;c_Tlbq7m0|{PdBtVw2ViIJ2V;($(M3LhLl5s9fwXc| z9CYtf#cr|(^&R^46j4v0J&4P0SI_X|f%sHTs*LZV3@Rwtfu`PABzZB57K4aN^{D58jiDqP@Bv9j*@cVzYT zsHFK_f%&%OM?aVIqKZ0{I^PU;HsZ^Hklkv)nU-C@!;%0TV05C2sFMQaACL%`Z!j1-dRLq}gxmNq691mhhqKYI1JNeo%Azm^{ zk=yH4^y!&xnVV~QZMPeGlf%QW&$jvQ?B3mF_5_v;nUWiFakU zHvxgc1E=Feb9q*!zVgUGWj)WXdeKEFjqXSx&6-KV^aKIdHC>6?&F_jRrdZk6YpBWF zoMW~sXp}03U>gMS)7FY9$6|UBvu#&p&)p1ibDD98#-Dh$?*5cfPpINJZdlc~5_l)v znv&I+qWsJ`1CBG3MHF-sB5-ic$9w`hahhK%%#C^5=6tyW?$Jd_K#95b?tEvSdgg(T zGj89M4xX4aQBR>UB#UsuhCjUEns8Q~a$DwHka5ivQ;x*-6=h?!PdkR=pI&KIwoArA z3_&BlIHHOqCGi#;Is47D4C0w{ACqw!t9oGiW{N6JC9tyF2@y*Y-G8U}(`U6=QFEWV z4+j{=Xrh7)eP$tQvCO}DSSbgg<0I*c+|Vu=BNLCj*%&=2qJo*VENaM)v}Qq)F~Is! JMHOhH|Jh~9G`au) literal 0 HcmV?d00001 diff --git a/data/tray/tray_textured2.mtl b/data/tray/tray_textured2.mtl new file mode 100644 index 000000000..4689a463a --- /dev/null +++ b/data/tray/tray_textured2.mtl @@ -0,0 +1,13 @@ +# Blender MTL File: 'tray_textured2.blend' +# Material Count: 1 + +newmtl None +Ns 0.000000 +Ka 0.000000 0.000000 0.000000 +Kd 0.800000 0.800000 0.800000 +Ks 0.800000 0.800000 0.800000 +Ke 0.000000 0.000000 0.000000 +Ni 1.000000 +d 1.000000 +illum 2 +map_Kd tray.jpg diff --git a/data/tray/tray_textured2.obj b/data/tray/tray_textured2.obj new file mode 100644 index 000000000..98a8962c6 --- /dev/null +++ b/data/tray/tray_textured2.obj @@ -0,0 +1,255 @@ +# Blender v2.78 (sub 0) OBJ File: 'tray_textured2.blend' +# www.blender.org +mtllib tray_textured2.mtl +o edge_1_Cube.003 +v 0.580000 0.590083 0.250354 +v -0.419960 0.426691 -0.001860 +v -0.580000 0.590083 0.250354 +v 0.580000 0.573309 0.261247 +v 0.420014 0.426691 -0.001059 +v -0.580000 0.573309 0.261247 +v 0.420014 0.409917 0.009834 +v -0.419960 0.409917 0.009033 +vt 0.8346 0.9187 +vt 0.2203 0.8574 +vt 0.1480 0.9187 +vt 0.8346 0.9129 +vt 0.7623 0.8574 +vt 0.1480 0.9129 +vt 0.7623 0.8511 +vt 0.2203 0.8511 +vn 0.0004 0.8386 -0.5448 +vn 0.0001 0.8391 -0.5439 +vn -0.0000 0.8393 -0.5437 +vn 0.8823 -0.2564 -0.3948 +vn -0.0004 -0.8392 0.5439 +vn -0.0001 -0.8386 0.5447 +vn 0.0000 -0.8385 0.5449 +vn -0.8826 -0.2560 -0.3942 +vn 0.0008 -0.5446 -0.8387 +vn -0.0000 0.5446 0.8387 +vn 0.0005 0.8383 -0.5452 +vn -0.0005 -0.8394 0.5435 +usemtl None +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 5/5/4 1/1/4 +f 6/6/5 7/7/6 4/4/7 +f 3/3/8 8/8/8 6/6/8 +f 5/5/9 8/8/9 2/2/9 +f 4/4/10 3/3/10 6/6/10 +f 1/1/1 5/5/11 2/2/2 +f 4/4/4 7/7/4 5/5/4 +f 6/6/5 8/8/12 7/7/6 +f 3/3/8 2/2/8 8/8/8 +f 5/5/9 7/7/9 8/8/9 +f 4/4/10 1/1/10 3/3/10 +o edge_2_Cube +v 0.590083 0.580000 0.250354 +v 0.409917 0.420060 0.009390 +v 0.573309 0.580000 0.261247 +v 0.590083 -0.580000 0.250354 +v 0.426691 0.420060 -0.001503 +v 0.573309 -0.580000 0.261247 +v 0.426691 -0.419158 -0.002053 +v 0.409917 -0.419158 0.008840 +vt 0.9410 0.8520 +vt 0.7523 0.8566 +vt 0.9234 0.8524 +vt 0.8896 0.1426 +vt 0.7698 0.8562 +vt 0.8721 0.1430 +vt 0.7185 0.1468 +vt 0.7009 0.1472 +vn -0.2561 0.8826 -0.3943 +vn 0.8394 0.0003 -0.5435 +vn 0.8390 0.0001 -0.5441 +vn 0.8389 0.0000 -0.5442 +vn -0.2569 -0.8818 -0.3956 +vn -0.8390 -0.0003 0.5441 +vn -0.8394 -0.0001 0.5436 +vn -0.8395 -0.0000 0.5434 +vn -0.5446 0.0005 -0.8387 +vn 0.5446 -0.0000 0.8387 +vn 0.8396 0.0004 -0.5433 +vn -0.8388 -0.0004 0.5444 +usemtl None +s 1 +f 9/9/13 10/10/13 11/11/13 +f 12/12/14 13/13/15 9/9/16 +f 14/14/17 15/15/17 12/12/17 +f 11/11/18 16/16/19 14/14/20 +f 13/13/21 16/16/21 10/10/21 +f 12/12/22 11/11/22 14/14/22 +f 9/9/13 13/13/13 10/10/13 +f 12/12/14 15/15/23 13/13/15 +f 14/14/17 16/16/17 15/15/17 +f 11/11/18 10/10/24 16/16/19 +f 13/13/21 15/15/21 16/16/21 +f 12/12/22 9/9/22 11/11/22 +o edge_3_Cube.002 +v 0.580000 -0.573309 0.261247 +v -0.419400 -0.409917 0.008678 +v -0.580000 -0.573309 0.261247 +v 0.580000 -0.590083 0.250354 +v 0.419883 -0.409917 0.009162 +v -0.580000 -0.590083 0.250354 +v 0.419883 -0.426691 -0.001731 +v -0.419400 -0.426691 -0.002215 +vt 0.8690 0.1040 +vt 0.1365 0.1739 +vt 0.0188 0.1040 +vt 0.8690 0.0968 +vt 0.7517 0.1739 +vt 0.0188 0.0968 +vt 0.7517 0.1668 +vt 0.1365 0.1668 +vn -0.0002 0.8392 0.5438 +vn -0.0000 0.8395 0.5433 +vn -0.0000 0.8396 0.5432 +vn 0.8825 0.2562 -0.3945 +vn 0.0002 -0.8396 -0.5433 +vn 0.0000 -0.8392 -0.5438 +vn 0.0000 -0.8391 -0.5439 +vn -0.8821 0.2565 -0.3950 +vn 0.0005 0.5446 -0.8387 +vn 0.0000 -0.5446 0.8387 +vn -0.0003 0.8391 0.5440 +vn 0.0003 -0.8397 -0.5430 +usemtl None +s 1 +f 17/17/25 18/18/26 19/19/27 +f 20/20/28 21/21/28 17/17/28 +f 22/22/29 23/23/30 20/20/31 +f 19/19/32 24/24/32 22/22/32 +f 21/21/33 24/24/33 18/18/33 +f 20/20/34 19/19/34 22/22/34 +f 17/17/25 21/21/35 18/18/26 +f 20/20/28 23/23/28 21/21/28 +f 22/22/29 24/24/36 23/23/30 +f 19/19/32 18/18/32 24/24/32 +f 21/21/33 23/23/33 24/24/33 +f 20/20/34 17/17/34 19/19/34 +o edge_5_Cube.005 +v -0.153309 0.580000 0.261247 +v -0.006691 0.419400 -0.002214 +v -0.170083 0.580000 0.250354 +v -0.153309 -0.580000 0.261247 +v 0.010083 0.419400 0.008679 +v -0.170083 -0.580000 0.250354 +v 0.010083 -0.419883 0.009732 +v -0.006691 -0.419883 -0.001161 +vt 0.0506 0.8517 +vt 0.1935 0.8492 +vt 0.0342 0.8520 +vt 0.0164 0.1914 +vt 0.2099 0.8489 +vt 0.0001 0.1917 +vt 0.1757 0.1886 +vt 0.1594 0.1889 +vn 0.2565 0.8821 -0.3950 +vn 0.8387 0.0005 0.5446 +vn 0.8394 0.0001 0.5434 +vn 0.8396 0.0000 0.5432 +vn 0.2565 -0.8822 -0.3950 +vn -0.8395 -0.0005 -0.5434 +vn -0.8388 -0.0001 -0.5445 +vn -0.8386 -0.0000 -0.5448 +vn 0.5446 -0.0011 -0.8387 +vn -0.5446 -0.0000 0.8387 +vn 0.8384 0.0007 0.5451 +vn -0.8398 -0.0007 -0.5429 +usemtl None +s 1 +f 25/25/37 26/26/37 27/27/37 +f 28/28/38 29/29/39 25/25/40 +f 30/30/41 31/31/41 28/28/41 +f 27/27/42 32/32/43 30/30/44 +f 29/29/45 32/32/45 26/26/45 +f 28/28/46 27/27/46 30/30/46 +f 25/25/37 29/29/37 26/26/37 +f 28/28/38 31/31/47 29/29/39 +f 30/30/41 32/32/41 31/31/41 +f 27/27/42 26/26/48 32/32/43 +f 29/29/45 31/31/45 32/32/45 +f 28/28/46 25/25/46 27/27/46 +o edge_4_Cube.001 +v -0.573309 0.580000 0.261247 +v -0.426691 0.419400 -0.002214 +v -0.590083 0.580000 0.250354 +v -0.573309 -0.580000 0.261247 +v -0.409917 0.419400 0.008679 +v -0.590083 -0.580000 0.250354 +v -0.409917 -0.419400 0.009162 +v -0.426691 -0.419400 -0.001731 +vt 0.9046 0.2397 +vt 0.7929 0.2434 +vt 0.9174 0.2393 +vt 0.9537 0.7559 +vt 0.7801 0.2438 +vt 0.9664 0.7554 +vt 0.8291 0.7599 +vt 0.8419 0.7595 +vn 0.2565 0.8821 -0.3950 +vn 0.8392 0.0002 0.5438 +vn 0.8395 0.0000 0.5433 +vn 0.8396 0.0000 0.5432 +vn 0.2568 -0.8819 -0.3954 +vn -0.8396 -0.0002 -0.5433 +vn -0.8392 -0.0000 -0.5438 +vn -0.8391 -0.0000 -0.5439 +vn 0.5446 -0.0005 -0.8387 +vn -0.5446 -0.0000 0.8387 +vn 0.8391 0.0003 0.5440 +vn -0.8397 -0.0003 -0.5430 +usemtl None +s 1 +f 33/33/49 34/34/49 35/35/49 +f 36/36/50 37/37/51 33/33/52 +f 38/38/53 39/39/53 36/36/53 +f 35/35/54 40/40/55 38/38/56 +f 37/37/57 40/40/57 34/34/57 +f 36/36/58 35/35/58 38/38/58 +f 33/33/49 37/37/49 34/34/49 +f 36/36/50 39/39/59 37/37/51 +f 38/38/53 40/40/53 39/39/53 +f 35/35/54 34/34/60 40/40/55 +f 37/37/57 39/39/57 40/40/57 +f 36/36/58 33/33/58 35/35/58 +o base_Cube.004 +v 0.420000 0.420000 0.010000 +v -0.420000 0.420000 -0.010000 +v -0.420000 0.420000 0.010000 +v 0.420000 -0.420000 0.010000 +v 0.420000 0.420000 -0.010000 +v -0.420000 -0.420000 0.010000 +v 0.420000 -0.420000 -0.010000 +v -0.420000 -0.420000 -0.010000 +vt 0.7524 0.8072 +vt -0.3038 0.8371 +vt -0.3038 0.8371 +vt 0.7012 0.1905 +vt 0.7524 0.8072 +vt -0.3550 0.2204 +vt 0.7012 0.1905 +vt -0.3550 0.2204 +vn -0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +usemtl None +s 1 +f 41/41/61 42/42/61 43/43/61 +f 44/44/62 45/45/62 41/41/62 +f 46/46/63 47/47/63 44/44/63 +f 43/43/64 48/48/64 46/46/64 +f 45/45/65 48/48/65 42/42/65 +f 44/44/66 43/43/66 46/46/66 +f 41/41/61 45/45/61 42/42/61 +f 44/44/62 47/47/62 45/45/62 +f 46/46/63 48/48/63 47/47/63 +f 43/43/64 42/42/64 48/48/64 +f 45/45/65 47/47/65 48/48/65 +f 44/44/66 41/41/66 43/43/66 diff --git a/data/tray/tray_textured2.urdf b/data/tray/tray_textured2.urdf new file mode 100644 index 000000000..8b89b015c --- /dev/null +++ b/data/tray/tray_textured2.urdf @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index d0a3dca38..33b178dd7 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -43,11 +43,12 @@ bool gCloseToKuka=false; bool gEnableRealTimeSimVR=false; bool gCreateDefaultRobotAssets = false; int gInternalSimFlags = 0; +bool gResetSimulation = 0; int gHuskyId = -1; btTransform huskyTr = btTransform::getIdentity(); int gCreateObjectSimVR = -1; -int gEnableKukaControl = 0; +int gEnableKukaControl = 1; btScalar simTimeScalingFactor = 1; btScalar gRhsClamp = 1.f; @@ -718,6 +719,19 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() } +void PhysicsServerCommandProcessor::deleteCachedInverseKinematicsBodies() +{ + for (int i = 0; i < m_data->m_inverseKinematicsHelpers.size(); i++) + { + IKTrajectoryHelper** ikHelperPtr = m_data->m_inverseKinematicsHelpers.getAtIndex(i); + if (ikHelperPtr) + { + IKTrajectoryHelper* ikHelper = *ikHelperPtr; + delete ikHelper; + } + } + m_data->m_inverseKinematicsHelpers.clear(); +} void PhysicsServerCommandProcessor::deleteCachedInverseDynamicsBodies() { for (int i = 0; i < m_data->m_inverseDynamicsBodies.size(); i++) @@ -736,7 +750,7 @@ void PhysicsServerCommandProcessor::deleteCachedInverseDynamicsBodies() void PhysicsServerCommandProcessor::deleteDynamicsWorld() { deleteCachedInverseDynamicsBodies(); - + deleteCachedInverseKinematicsBodies(); for (int i=0;im_multiBodyJointFeedbacks.size();i++) { @@ -2429,29 +2443,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm case CMD_RESET_SIMULATION: { - //clean up all data - deleteCachedInverseDynamicsBodies(); - - if (m_data && m_data->m_guiHelper) - { - m_data->m_guiHelper->removeAllGraphicsInstances(); - } - if (m_data) - { - m_data->m_visualConverter.resetAll(); - } - - deleteDynamicsWorld(); - createEmptyDynamicsWorld(); - - m_data->exitHandles(); - m_data->initHandles(); + + resetSimulation(); SharedMemoryStatus& serverCmd =serverStatusOut; serverCmd.m_type = CMD_RESET_SIMULATION_COMPLETED; hasStatus = true; - m_data->m_hasGround = false; - m_data->m_gripperRigidbodyFixed = 0; break; } case CMD_CREATE_RIGID_BODY: @@ -3940,6 +3937,12 @@ double gDtInSec = 0.f; double gSubStep = 0.f; void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec) { + if (gResetSimulation) + { + resetSimulation(); + gResetSimulation = false; + } + if ((gEnableRealTimeSimVR || m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper) { @@ -3997,7 +4000,30 @@ void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId) } } +void PhysicsServerCommandProcessor::resetSimulation() +{ + //clean up all data + deleteCachedInverseDynamicsBodies(); + if (m_data && m_data->m_guiHelper) + { + m_data->m_guiHelper->removeAllGraphicsInstances(); + } + if (m_data) + { + m_data->m_visualConverter.resetAll(); + } + + deleteDynamicsWorld(); + createEmptyDynamicsWorld(); + + m_data->exitHandles(); + m_data->initHandles(); + + m_data->m_hasGround = false; + m_data->m_gripperRigidbodyFixed = 0; + +} //todo: move this to Python/scripting void PhysicsServerCommandProcessor::createDefaultRobotAssets() { @@ -4141,7 +4167,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() btTransform objectLocalTr[] = { btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.0, 0.0, 0.0)), - btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.0, 0.15, 0.64)), + btTransform(btQuaternion(btVector3(0,0,1),-SIMD_HALF_PI), btVector3(0.0, 0.15, 0.64)), btTransform(btQuaternion(0, 0, 0, 1), btVector3(0.1, 0.15, 0.85)), btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.4, 0.05, 0.85)), btTransform(btQuaternion(0, 0, 0, 1), btVector3(-0.3, -0.05, 0.7)), @@ -4168,7 +4194,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() // Table area loadUrdf("table/table.urdf", objectWorldTr[0].getOrigin(), objectWorldTr[0].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); - loadUrdf("tray.urdf", objectWorldTr[1].getOrigin(), objectWorldTr[1].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); + loadUrdf("tray/tray_textured.urdf", objectWorldTr[1].getOrigin(), objectWorldTr[1].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); //loadUrdf("cup_small.urdf", objectWorldTr[2].getOrigin(), objectWorldTr[2].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); //loadUrdf("pitcher_small.urdf", objectWorldTr[3].getOrigin(), objectWorldTr[3].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("teddy_vhacd.urdf", objectWorldTr[4].getOrigin(), objectWorldTr[4].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h index e271cdff6..dc7992980 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.h +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h @@ -23,6 +23,8 @@ class PhysicsServerCommandProcessor : public PhysicsCommandProcessorInterface //todo: move this to physics client side / Python void createDefaultRobotAssets(); + void resetSimulation(); + protected: @@ -37,6 +39,7 @@ protected: int createBodyInfoStream(int bodyUniqueId, char* bufferServerToClient, int bufferSizeInBytes); void deleteCachedInverseDynamicsBodies(); + void deleteCachedInverseKinematicsBodies(); public: PhysicsServerCommandProcessor(); diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index aff18b0f8..e5b4cc3e4 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -39,6 +39,7 @@ extern bool gEnableRealTimeSimVR; extern bool gCreateDefaultRobotAssets; extern int gInternalSimFlags; extern int gCreateObjectSimVR; +extern bool gResetSimulation; extern int gEnableKukaControl; int gGraspingController = -1; extern btScalar simTimeScalingFactor; @@ -273,7 +274,7 @@ void MotionThreadFunc(void* userPtr,void* lsMemory) args->m_physicsServerPtr->removePickingConstraint(); } - if (!gEnableKukaControl) +// if (!gEnableKukaControl) { if (args->m_isVrControllerPicking[c]) { @@ -1670,7 +1671,8 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt { if (button == 1 && state == 0) { -// gVRTeleportPos = gLastPickPos; + gResetSimulation = true; + //gVRTeleportPos1 = gLastPickPos; } } else { @@ -1682,7 +1684,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt } else { gDebugRenderToggle = 0; - +#if 0//it confuses people, make it into a debug option in a VR GUI? if (simTimeScalingFactor==0) { simTimeScalingFactor = 1; @@ -1697,6 +1699,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt simTimeScalingFactor = 0; } } +#endif } } else { @@ -1714,7 +1717,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt } else { - gEnableKukaControl = !gEnableKukaControl; +// gEnableKukaControl = !gEnableKukaControl; } } From 15cda751307424c522a805461f14b31f80b61976 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Wed, 30 Nov 2016 22:24:20 -0800 Subject: [PATCH 32/39] add in settings of URDF/SDF allow 'useMaximalCoordinates' and 'useFixedBase' in pybullet.loadURDF. enable split impulse for btRigidBody, even in btMultiBodyDynamicsWorld. allow initialization of velocity and apply force for btRigidBody in pybullet/shared memory API. process contact parameters in URDF also for btRigidBody (friction, restitution etc) add pybullet.setPhysicsEngineParameter with numSolverIterations, useSplitImpulse etc. --- .../Importers/ImportURDFDemo/URDF2Bullet.cpp | 52 ++++-- .../Importers/ImportURDFDemo/URDFJointTypes.h | 3 + .../Importers/ImportURDFDemo/UrdfParser.cpp | 25 +++ examples/SharedMemory/PhysicsClientC_API.cpp | 20 +++ examples/SharedMemory/PhysicsClientC_API.h | 3 + .../PhysicsServerCommandProcessor.cpp | 122 +++++++++++--- examples/SharedMemory/SharedMemoryCommands.h | 6 +- examples/pybullet/pybullet.c | 157 ++++++++++++++++-- .../Featherstone/btMultiBodyConstraint.cpp | 14 +- .../btMultiBodyConstraintSolver.cpp | 7 +- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 2 +- 11 files changed, 354 insertions(+), 57 deletions(-) diff --git a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp index d9e58ef5a..7c0f2c86a 100644 --- a/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp +++ b/examples/Importers/ImportURDFDemo/URDF2Bullet.cpp @@ -143,6 +143,34 @@ void InitURDF2BulletCache(const URDFImporterInterface& u2b, URDF2BulletCachedDat } +void processContactParameters(const URDFLinkContactInfo& contactInfo, btCollisionObject* col) +{ + if ((contactInfo.m_flags & URDF_CONTACT_HAS_LATERAL_FRICTION) != 0) + { + col->setFriction(contactInfo.m_lateralFriction); + } + if ((contactInfo.m_flags & URDF_CONTACT_HAS_RESTITUTION) != 0) + { + col->setRestitution(contactInfo.m_restitution); + } + + if ((contactInfo.m_flags & URDF_CONTACT_HAS_ROLLING_FRICTION) != 0) + { + col->setRollingFriction(contactInfo.m_rollingFriction); + } + if ((contactInfo.m_flags & URDF_CONTACT_HAS_SPINNING_FRICTION) != 0) + { + col->setSpinningFriction(contactInfo.m_spinningFriction); + } + if ((contactInfo.m_flags & URDF_CONTACT_HAS_STIFFNESS_DAMPING) != 0) + { + col->setContactStiffnessAndDamping(contactInfo.m_contactStiffness, contactInfo.m_contactDamping); + } +} + + + + void ConvertURDF2BulletInternal( const URDFImporterInterface& u2b, MultiBodyCreationInterface& creation, URDF2BulletCachedData& cache, int urdfLinkIndex, @@ -258,11 +286,18 @@ void ConvertURDF2BulletInternal( world1->addRigidBody(body); + compoundShape->setUserIndex(graphicsIndex); + URDFLinkContactInfo contactInfo; + u2b.getLinkContactInfo(urdfLinkIndex, contactInfo); + + processContactParameters(contactInfo, body); creation.createRigidBodyGraphicsInstance(urdfLinkIndex, body, color, graphicsIndex); cache.registerRigidBody(urdfLinkIndex, body, inertialFrameInWorldSpace, mass, localInertiaDiagonal, compoundShape, localInertialFrame); + + //untested: u2b.convertLinkVisualShapes2(urdfLinkIndex,pathPrefix,localInertialFrame,body); } else { @@ -413,22 +448,7 @@ void ConvertURDF2BulletInternal( URDFLinkContactInfo contactInfo; u2b.getLinkContactInfo(urdfLinkIndex,contactInfo); - if ((contactInfo.m_flags & URDF_CONTACT_HAS_LATERAL_FRICTION)!=0) - { - col->setFriction(contactInfo.m_lateralFriction); - } - if ((contactInfo.m_flags & URDF_CONTACT_HAS_ROLLING_FRICTION)!=0) - { - col->setRollingFriction(contactInfo.m_rollingFriction); - } - if ((contactInfo.m_flags & URDF_CONTACT_HAS_SPINNING_FRICTION)!=0) - { - col->setSpinningFriction(contactInfo.m_spinningFriction); - } - if ((contactInfo.m_flags & URDF_CONTACT_HAS_STIFFNESS_DAMPING)!=0) - { - col->setContactStiffnessAndDamping(contactInfo.m_contactStiffness,contactInfo.m_contactDamping); - } + processContactParameters(contactInfo, col); if (mbLinkIndex>=0) //???? double-check +/- 1 { diff --git a/examples/Importers/ImportURDFDemo/URDFJointTypes.h b/examples/Importers/ImportURDFDemo/URDFJointTypes.h index 88912cb1a..2bcb53214 100644 --- a/examples/Importers/ImportURDFDemo/URDFJointTypes.h +++ b/examples/Importers/ImportURDFDemo/URDFJointTypes.h @@ -22,6 +22,7 @@ enum URDF_LinkContactFlags URDF_CONTACT_HAS_STIFFNESS_DAMPING=16, URDF_CONTACT_HAS_ROLLING_FRICTION=32, URDF_CONTACT_HAS_SPINNING_FRICTION=64, + URDF_CONTACT_HAS_RESTITUTION=128, }; @@ -30,6 +31,7 @@ struct URDFLinkContactInfo btScalar m_lateralFriction; btScalar m_rollingFriction; btScalar m_spinningFriction; + btScalar m_restitution; btScalar m_inertiaScaling; btScalar m_contactCfm; btScalar m_contactErp; @@ -42,6 +44,7 @@ struct URDFLinkContactInfo :m_lateralFriction(0.5), m_rollingFriction(0), m_spinningFriction(0), + m_restitution(0), m_inertiaScaling(1), m_contactCfm(0), m_contactErp(0), diff --git a/examples/Importers/ImportURDFDemo/UrdfParser.cpp b/examples/Importers/ImportURDFDemo/UrdfParser.cpp index 817cb0ce5..bcac5eec7 100644 --- a/examples/Importers/ImportURDFDemo/UrdfParser.cpp +++ b/examples/Importers/ImportURDFDemo/UrdfParser.cpp @@ -672,6 +672,31 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi } } } + + { + TiXmlElement *restitution_xml = ci->FirstChildElement("restitution"); + if (restitution_xml) + { + if (m_parseSDF) + { + link.m_contactInfo.m_restitution = urdfLexicalCast(restitution_xml->GetText()); + link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_RESTITUTION; + } + else + { + if (!restitution_xml->Attribute("value")) + { + logger->reportError("Link/contact: restitution element must have value attribute"); + return false; + } + + link.m_contactInfo.m_restitution = urdfLexicalCast(restitution_xml->Attribute("value")); + link.m_contactInfo.m_flags |= URDF_CONTACT_HAS_RESTITUTION; + + } + } + } + { TiXmlElement *spinning_xml = ci->FirstChildElement("spinning_friction"); if (spinning_xml) diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index 6b3e97ae3..12bf1ce90 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -317,6 +317,26 @@ int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle commandHan return 0; } +int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); + + command->m_physSimParamArgs.m_useSplitImpulse = useSplitImpulse; + command->m_updateFlags |= SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE; + return 0; +} + +int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold) +{ + struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; + b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS); + + command->m_physSimParamArgs.m_splitImpulsePenetrationThreshold = splitImpulsePenetrationThreshold; + command->m_updateFlags |= SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD; + return 0; +} + int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations) { struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 4ee0e394d..e32c55b87 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -163,6 +163,9 @@ int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps); int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation); int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations); +int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse); +int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold); + //b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes //Use at own risk: magic things may or my not happen when calling this API diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 5ffc08e1a..2872da72b 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -2338,6 +2338,17 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm { m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations; } + + if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE) + { + m_data->m_dynamicsWorld->getSolverInfo().m_splitImpulse = clientCmd.m_physSimParamArgs.m_useSplitImpulse; + } + if (clientCmd.m_updateFlags &SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD) + { + m_data->m_dynamicsWorld->getSolverInfo().m_splitImpulsePenetrationThreshold = clientCmd.m_physSimParamArgs.m_splitImpulsePenetrationThreshold; + } + + if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS) { m_data->m_numSimulationSubSteps = clientCmd.m_physSimParamArgs.m_numSimulationSubSteps; @@ -2363,27 +2374,50 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm int bodyUniqueId = clientCmd.m_initPoseArgs.m_bodyUniqueId; InteralBodyData* body = m_data->getHandle(bodyUniqueId); + btVector3 baseLinVel(0, 0, 0); + btVector3 baseAngVel(0, 0, 0); + + if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_LINEAR_VELOCITY) + { + baseLinVel.setValue(clientCmd.m_initPoseArgs.m_initialStateQdot[0], + clientCmd.m_initPoseArgs.m_initialStateQdot[1], + clientCmd.m_initPoseArgs.m_initialStateQdot[2]); + } + if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_ANGULAR_VELOCITY) + { + baseAngVel.setValue(clientCmd.m_initPoseArgs.m_initialStateQdot[3], + clientCmd.m_initPoseArgs.m_initialStateQdot[4], + clientCmd.m_initPoseArgs.m_initialStateQdot[5]); + } + btVector3 basePos(0, 0, 0); + if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_POSITION) + { + basePos = btVector3( + clientCmd.m_initPoseArgs.m_initialStateQ[0], + clientCmd.m_initPoseArgs.m_initialStateQ[1], + clientCmd.m_initPoseArgs.m_initialStateQ[2]); + } + btQuaternion baseOrn(0, 0, 0, 1); + if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_ORIENTATION) + { + baseOrn.setValue(clientCmd.m_initPoseArgs.m_initialStateQ[3], + clientCmd.m_initPoseArgs.m_initialStateQ[4], + clientCmd.m_initPoseArgs.m_initialStateQ[5], + clientCmd.m_initPoseArgs.m_initialStateQ[6]); + } if (body && body->m_multiBody) { btMultiBody* mb = body->m_multiBody; - btVector3 baseLinVel(0, 0, 0); - btVector3 baseAngVel(0, 0, 0); + if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_LINEAR_VELOCITY) { - baseLinVel.setValue(clientCmd.m_initPoseArgs.m_initialStateQdot[0], - clientCmd.m_initPoseArgs.m_initialStateQdot[1], - clientCmd.m_initPoseArgs.m_initialStateQdot[2]); mb->setBaseVel(baseLinVel); - } if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_ANGULAR_VELOCITY) { - baseAngVel.setValue(clientCmd.m_initPoseArgs.m_initialStateQdot[3], - clientCmd.m_initPoseArgs.m_initialStateQdot[4], - clientCmd.m_initPoseArgs.m_initialStateQdot[5]); mb->setBaseOmega(baseAngVel); } @@ -2396,10 +2430,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm clientCmd.m_initPoseArgs.m_hasInitialStateQ[2]); mb->setBaseVel(baseLinVel); - mb->setBasePos(btVector3( - clientCmd.m_initPoseArgs.m_initialStateQ[0], - clientCmd.m_initPoseArgs.m_initialStateQ[1], - clientCmd.m_initPoseArgs.m_initialStateQ[2])); + mb->setBasePos(basePos); } if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_ORIENTATION) { @@ -2409,10 +2440,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm clientCmd.m_initPoseArgs.m_hasInitialStateQ[6]); mb->setBaseOmega(baseAngVel); - btQuaternion invOrn(clientCmd.m_initPoseArgs.m_initialStateQ[3], - clientCmd.m_initPoseArgs.m_initialStateQ[4], - clientCmd.m_initPoseArgs.m_initialStateQ[5], - clientCmd.m_initPoseArgs.m_initialStateQ[6]); + btQuaternion invOrn(baseOrn); mb->setWorldToBaseRot(invOrn.inverse()); } @@ -2441,6 +2469,31 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm mb->updateCollisionObjectWorldTransforms(scratch_q,scratch_m); + } + + if (body && body->m_rigidBody) + { + if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_LINEAR_VELOCITY) + { + body->m_rigidBody->setLinearVelocity(baseLinVel); + } + if (clientCmd.m_updateFlags & INIT_POSE_HAS_BASE_ANGULAR_VELOCITY) + { + body->m_rigidBody->setAngularVelocity(baseAngVel); + } + + if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_POSITION) + { + body->m_rigidBody->getWorldTransform().setOrigin(basePos); + body->m_rigidBody->setLinearVelocity(baseLinVel); + } + + if (clientCmd.m_updateFlags & INIT_POSE_HAS_INITIAL_ORIENTATION) + { + body->m_rigidBody->getWorldTransform().setRotation(baseOrn); + body->m_rigidBody->setAngularVelocity(baseAngVel); + } + } SharedMemoryStatus& serverCmd =serverStatusOut; @@ -3114,11 +3167,12 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm for (int i = 0; i < clientCmd.m_externalForceArguments.m_numForcesAndTorques; ++i) { InteralBodyData* body = m_data->getHandle(clientCmd.m_externalForceArguments.m_bodyUniqueIds[i]); + bool isLinkFrame = ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_LINK_FRAME) != 0); + if (body && body->m_multiBody) { btMultiBody* mb = body->m_multiBody; - bool isLinkFrame = ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_LINK_FRAME)!=0); - + if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_FORCE)!=0) { btVector3 forceLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i*3+0], @@ -3166,6 +3220,36 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm } } } + + if (body && body->m_rigidBody) + { + btRigidBody* rb = body->m_rigidBody; + if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_FORCE) != 0) + { + btVector3 forceLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); + btVector3 positionLocal( + clientCmd.m_externalForceArguments.m_positions[i * 3 + 0], + clientCmd.m_externalForceArguments.m_positions[i * 3 + 1], + clientCmd.m_externalForceArguments.m_positions[i * 3 + 2]); + + btVector3 forceWorld = isLinkFrame ? forceLocal : rb->getWorldTransform().getBasis()*forceLocal; + btVector3 relPosWorld = isLinkFrame ? positionLocal : rb->getWorldTransform().getBasis()*positionLocal; + rb->applyForce(forceWorld, relPosWorld); + + } + + if ((clientCmd.m_externalForceArguments.m_forceFlags[i] & EF_TORQUE) != 0) + { + btVector3 torqueLocal(clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 0], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 1], + clientCmd.m_externalForceArguments.m_forcesAndTorques[i * 3 + 2]); + + btVector3 torqueWorld = isLinkFrame ? torqueLocal : rb->getWorldTransform().getBasis()*torqueLocal; + rb->applyTorque(torqueWorld); + } + } } SharedMemoryStatus& serverCmd =serverStatusOut; diff --git a/examples/SharedMemory/SharedMemoryCommands.h b/examples/SharedMemory/SharedMemoryCommands.h index c360a5511..fd1c4d94a 100644 --- a/examples/SharedMemory/SharedMemoryCommands.h +++ b/examples/SharedMemory/SharedMemoryCommands.h @@ -287,7 +287,9 @@ enum EnumSimParamUpdateFlags SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS=8, SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 16, SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP=32, - SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS=64 + SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS=64, + SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE=128, + SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 256, }; enum EnumLoadBunnyUpdateFlags @@ -312,6 +314,8 @@ struct SendPhysicsSimulationParameters int m_numSimulationSubSteps; int m_numSolverIterations; bool m_allowRealTimeSimulation; + int m_useSplitImpulse; + double m_splitImpulsePenetrationThreshold; int m_internalSimFlags; double m_defaultContactERP; }; diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 9ed3bdd60..58dc2127e 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -419,6 +419,62 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args) return Py_None; } +static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* args, PyObject *keywds) +{ + double fixedTimeStep = -1; + int numSolverIterations = -1; + int useSplitImpulse = -1; + double splitImpulsePenetrationThreshold = -1; + + if (0 == sm) { + PyErr_SetString(SpamError, "Not connected to physics server."); + return NULL; + } + + static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", NULL }; + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diid", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold)) + { + return NULL; + } + { + b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); + b3SharedMemoryStatusHandle statusHandle; + + if (numSolverIterations >= 0) + { + b3PhysicsParamSetNumSolverIterations(command, numSolverIterations); + } + if (fixedTimeStep >= 0) + { + b3PhysicsParamSetTimeStep(command, fixedTimeStep); + } + if (useSplitImpulse >= 0) + { + b3PhysicsParamSetUseSplitImpulse(command,useSplitImpulse); + } + if (splitImpulsePenetrationThreshold >= 0) + { + b3PhysicsParamSetSplitImpulsePenetrationThreshold(command, splitImpulsePenetrationThreshold); + } + + //ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation); + + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); + } +#if 0 + b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient); + int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx, double gravy, double gravz); + int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep); + int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP); + int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps); + int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation); + int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations); +#endif + + Py_INCREF(Py_None); + return Py_None; +} // Load a robot from a URDF file (universal robot description format) @@ -426,8 +482,14 @@ static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args) // to position (0,0,1) with orientation(0,0,0,1) // els(x,y,z) or // loadURDF(pos_x, pos_y, pos_z, orn_x, orn_y, orn_z, orn_w) -static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args) { +static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject *keywds) +{ int size = PySequence_Size(args); + static char *kwlist[] = { "fileName", "basePosition", "baseOrientation", "useMaximalCoordinates","useFixedBase", NULL }; + + static char *kwlistBackwardCompatible4[] = { "startPosX", "startPosY", "startPosZ", NULL }; + static char *kwlistBackwardCompatible8[] = { "startPosX", "startPosY", "startPosZ", "startOrnX", "startOrnY","startOrnZ","startOrnW", NULL }; + int bodyIndex = -1; const char* urdfFileName = ""; @@ -439,24 +501,79 @@ static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args) { double startOrnY = 0.0; double startOrnZ = 0.0; double startOrnW = 1.0; + int useMaximalCoordinates = 0; + int useFixedBase = 0; + + int backwardsCompatibilityArgs = 0; if (0 == sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - if (size == 1) { - if (!PyArg_ParseTuple(args, "s", &urdfFileName)) return NULL; + + if (PyArg_ParseTupleAndKeywords(args, keywds, "sddd", kwlistBackwardCompatible4, &urdfFileName, &startPosX, + &startPosY, &startPosZ)) + { + backwardsCompatibilityArgs = 1; } - if (size == 4) { - if (!PyArg_ParseTuple(args, "sddd", &urdfFileName, &startPosX, &startPosY, - &startPosZ)) - return NULL; + else + { + PyErr_Clear(); } - if (size == 8) { - if (!PyArg_ParseTuple(args, "sddddddd", &urdfFileName, &startPosX, - &startPosY, &startPosZ, &startOrnX, &startOrnY, - &startOrnZ, &startOrnW)) - return NULL; + + + if (PyArg_ParseTupleAndKeywords(args, keywds, "sddddddd", kwlistBackwardCompatible8,&urdfFileName, &startPosX, + &startPosY, &startPosZ, &startOrnX, &startOrnY,&startOrnZ, &startOrnW)) + { + backwardsCompatibilityArgs = 1; + } + else + { + PyErr_Clear(); + } + + + + if (!backwardsCompatibilityArgs) + { + PyObject* basePosObj = 0; + PyObject* baseOrnObj = 0; + double basePos[3]; + double baseOrn[4]; + + + if (!PyArg_ParseTupleAndKeywords(args, keywds, "s|OOii", kwlist, &urdfFileName, &basePosObj, &baseOrnObj, &useMaximalCoordinates,&useFixedBase)) + { + + return NULL; + } + else + { + if (basePosObj) + { + if (!pybullet_internalSetVectord(basePosObj, basePos)) + { + PyErr_SetString(SpamError, "Cannot convert basePosition."); + return NULL; + } + startPosX = basePos[0]; + startPosY = basePos[1]; + startPosZ = basePos[2]; + + } + if (baseOrnObj) + { + if (!pybullet_internalSetVector4d(baseOrnObj, baseOrn)) + { + PyErr_SetString(SpamError, "Cannot convert baseOrientation."); + return NULL; + } + startOrnX = baseOrn[0]; + startOrnY = baseOrn[1]; + startOrnZ = baseOrn[2]; + startOrnW = baseOrn[3]; + } + } } if (strlen(urdfFileName)) { @@ -473,6 +590,15 @@ static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args) { b3LoadUrdfCommandSetStartPosition(command, startPosX, startPosY, startPosZ); b3LoadUrdfCommandSetStartOrientation(command, startOrnX, startOrnY, startOrnZ, startOrnW); + if (useMaximalCoordinates) + { + b3LoadUrdfCommandSetUseMultiBody(command, 0); + } + if (useFixedBase) + { + b3LoadUrdfCommandSetUseFixedBase(command, 1); + } + statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType != CMD_URDF_LOADING_COMPLETED) { @@ -3483,6 +3609,8 @@ static PyMethodDef SpamMethods[] = { "Set the amount of time to proceed at each call to stepSimulation. (unit " "is seconds, typically range is 0.01 or 0.001)"}, + + {"setDefaultContactERP", pybullet_setDefaultContactERP, METH_VARARGS, "Set the amount of contact penetration Error Recovery Paramater " "(ERP) in each time step. \ @@ -3493,10 +3621,13 @@ static PyMethodDef SpamMethods[] = { "Enable or disable real time simulation (using the real time clock," " RTC) in the physics server. Expects one integer argument, 0 or 1" }, + { "setPhysicsEngineParameter", (PyCFunction)pybullet_setPhysicsEngineParameter, METH_VARARGS | METH_KEYWORDS, + "Set some internal physics engine parameter, such as cfm or erp etc." }, + { "setInternalSimFlags", pybullet_setInternalSimFlags, METH_VARARGS, "This is for experimental purposes, use at own risk, magic may or not happen"}, - {"loadURDF", pybullet_loadURDF, METH_VARARGS, + {"loadURDF", (PyCFunction) pybullet_loadURDF, METH_VARARGS | METH_KEYWORDS, "Create a multibody by loading a URDF file."}, {"loadSDF", pybullet_loadSDF, METH_VARARGS, diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp index 01a59890c..d52852dd8 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraint.cpp @@ -378,7 +378,9 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr btScalar erp = infoGlobal.m_erp2; - if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold)) + + //split impulse is not implemented yet for btMultiBody* + //if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold)) { erp = infoGlobal.m_erp; } @@ -388,19 +390,23 @@ btScalar btMultiBodyConstraint::fillMultiBodyConstraint( btMultiBodySolverConstr btScalar penetrationImpulse = positionalError*solverConstraint.m_jacDiagABInv; btScalar velocityImpulse = velocityError *solverConstraint.m_jacDiagABInv; - if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold)) + //split impulse is not implemented yet for btMultiBody* + + // if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold)) { //combine position and velocity into rhs solverConstraint.m_rhs = penetrationImpulse+velocityImpulse; solverConstraint.m_rhsPenetration = 0.f; - } else + } + /*else { //split position and velocity into rhs and m_rhsPenetration solverConstraint.m_rhs = velocityImpulse; solverConstraint.m_rhsPenetration = penetrationImpulse; } - + */ + solverConstraint.m_cfm = 0.f; solverConstraint.m_lowerLimit = lowerLimit; solverConstraint.m_upperLimit = upperLimit; diff --git a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp index 29f8e469c..aa0755a10 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyConstraintSolver.cpp @@ -528,19 +528,20 @@ void btMultiBodyConstraintSolver::setupMultiBodyContactConstraint(btMultiBodySol if(!isFriction) { - if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold)) + // if (!infoGlobal.m_splitImpulse || (penetration > infoGlobal.m_splitImpulsePenetrationThreshold)) { //combine position and velocity into rhs solverConstraint.m_rhs = penetrationImpulse+velocityImpulse; solverConstraint.m_rhsPenetration = 0.f; - } else + } + /*else { //split position and velocity into rhs and m_rhsPenetration solverConstraint.m_rhs = velocityImpulse; solverConstraint.m_rhsPenetration = penetrationImpulse; } - + */ solverConstraint.m_lowerLimit = 0; solverConstraint.m_upperLimit = 1e10f; } diff --git a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp index d94d1d4ea..4b33cf69d 100644 --- a/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp +++ b/src/BulletDynamics/Featherstone/btMultiBodyDynamicsWorld.cpp @@ -384,7 +384,7 @@ btMultiBodyDynamicsWorld::btMultiBodyDynamicsWorld(btDispatcher* dispatcher,btBr m_multiBodyConstraintSolver(constraintSolver) { //split impulse is not yet supported for Featherstone hierarchies - getSolverInfo().m_splitImpulse = false; +// getSolverInfo().m_splitImpulse = false; getSolverInfo().m_solverMode |=SOLVER_USE_2_FRICTION_DIRECTIONS; m_solverMultiBodyIslandCallback = new MultiBodyInplaceSolverIslandCallback(constraintSolver,dispatcher); } From e20c487e52a3dc5571c2b7d65e10adb69cebdff5 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 1 Dec 2016 09:51:28 -0800 Subject: [PATCH 33/39] fix backward compatibility issue with pybullet:loadURDF --- examples/pybullet/pybullet.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 58dc2127e..a3da3e942 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -487,8 +487,8 @@ static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject *key int size = PySequence_Size(args); static char *kwlist[] = { "fileName", "basePosition", "baseOrientation", "useMaximalCoordinates","useFixedBase", NULL }; - static char *kwlistBackwardCompatible4[] = { "startPosX", "startPosY", "startPosZ", NULL }; - static char *kwlistBackwardCompatible8[] = { "startPosX", "startPosY", "startPosZ", "startOrnX", "startOrnY","startOrnZ","startOrnW", NULL }; + static char *kwlistBackwardCompatible4[] = { "fileName", "startPosX", "startPosY", "startPosZ", NULL }; + static char *kwlistBackwardCompatible8[] = { "fileName", "startPosX", "startPosY", "startPosZ", "startOrnX", "startOrnY","startOrnZ","startOrnW", NULL }; int bodyIndex = -1; From a88272de1b755a4449877e53c83312729224a755 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Thu, 1 Dec 2016 16:47:11 -0800 Subject: [PATCH 34/39] Restore the old constructor for TinyRenderObjectData for backward compatibility. --- .../RenderingExamples/TinyRendererSetup.cpp | 2 +- .../TinyRendererVisualShapeConverter.cpp | 2 +- examples/TinyRenderer/TinyRenderer.cpp | 60 +++++++++++++++---- examples/TinyRenderer/TinyRenderer.h | 10 ++-- 4 files changed, 56 insertions(+), 18 deletions(-) diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index e8cf9f255..7880a1f8c 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -190,7 +190,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui) TinyRenderObjectData* ob = new TinyRenderObjectData( m_internalData->m_rgbColorBuffer, m_internalData->m_depthBuffer, - m_internalData->m_shadowBuffer, + &m_internalData->m_shadowBuffer, &m_internalData->m_segmentationMaskBuffer, m_internalData->m_renderObjects.size()); diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index dc5d7a561..0182f8c18 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -568,7 +568,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const if (vertices.size() && indices.size()) { - TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId); + TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, &m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId); unsigned char* textureImage=0; int textureWidth=0; int textureHeight=0; diff --git a/examples/TinyRenderer/TinyRenderer.cpp b/examples/TinyRenderer/TinyRenderer.cpp index 2f346fcdb..a2bcea5d4 100644 --- a/examples/TinyRenderer/TinyRenderer.cpp +++ b/examples/TinyRenderer/TinyRenderer.cpp @@ -74,7 +74,7 @@ struct Shader : public IShader { Vec4f m_colorRGBA; Matrix& m_viewportMat; - b3AlignedObjectArray& m_shadowBuffer; + b3AlignedObjectArray* m_shadowBuffer; int m_width; int m_height; @@ -86,7 +86,7 @@ struct Shader : public IShader { mat<4,3,float> varying_tri_light_view; mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS - Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Matrix& viewportMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray& shadowBuffer) + Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Matrix& viewportMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray* shadowBuffer) :m_model(model), m_light_dir_local(light_dir_local), m_light_color(light_color), @@ -126,7 +126,7 @@ struct Shader : public IShader { int index_x = b3Max(0, b3Min(m_width-1, int(p[0]))); int index_y = b3Max(0, b3Min(m_height-1, int(p[1]))); int idx = index_x + index_y*m_width; // index in the shadowbuffer array - float shadow = 0.8+0.2*(m_shadowBuffer[idx]<-depth+0.2); // magic coeff to avoid z-fighting + float shadow = 0.8+0.2*(m_shadowBuffer->at(idx)<-depth+0.2); // magic coeff to avoid z-fighting Vec3f bn = (varying_nrm*bar).normalize(); Vec2f uv = varying_uv*bar; @@ -158,7 +158,7 @@ struct Shader : public IShader { } }; -TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray&shadowBuffer) +TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray* shadowBuffer) :m_rgbColorBuffer(rgbColorBuffer), m_depthBuffer(depthBuffer), m_shadowBuffer(shadowBuffer), @@ -167,6 +167,45 @@ m_model(0), m_userData(0), m_userIndex(-1), m_objectIndex(-1) +{ + Vec3f eye(1,1,3); + Vec3f center(0,0,0); + Vec3f up(0,0,1); + m_lightDirWorld.setValue(0,0,0); + m_lightColor.setValue(1, 1, 1); + m_localScaling.setValue(1,1,1); + m_modelMatrix = Matrix::identity(); + +} + +TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer, b3AlignedObjectArray* shadowBuffer, b3AlignedObjectArray* segmentationMaskBuffer, int objectIndex) +:m_rgbColorBuffer(rgbColorBuffer), +m_depthBuffer(depthBuffer), +m_shadowBuffer(shadowBuffer), +m_segmentationMaskBufferPtr(segmentationMaskBuffer), +m_model(0), +m_userData(0), +m_userIndex(-1), +m_objectIndex(objectIndex) +{ + Vec3f eye(1,1,3); + Vec3f center(0,0,0); + Vec3f up(0,0,1); + m_lightDirWorld.setValue(0,0,0); + m_lightColor.setValue(1, 1, 1); + m_localScaling.setValue(1,1,1); + m_modelMatrix = Matrix::identity(); + +} + +TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer) +:m_rgbColorBuffer(rgbColorBuffer), +m_depthBuffer(depthBuffer), +m_segmentationMaskBufferPtr(0), +m_model(0), +m_userData(0), +m_userIndex(-1), +m_objectIndex(-1) { Vec3f eye(1,1,3); Vec3f center(0,0,0); @@ -178,12 +217,9 @@ m_objectIndex(-1) } - - -TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer, b3AlignedObjectArray&shadowBuffer, b3AlignedObjectArray* segmentationMaskBuffer, int objectIndex) +TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer, b3AlignedObjectArray* segmentationMaskBuffer, int objectIndex) :m_rgbColorBuffer(rgbColorBuffer), m_depthBuffer(depthBuffer), -m_shadowBuffer(shadowBuffer), m_segmentationMaskBufferPtr(segmentationMaskBuffer), m_model(0), m_userData(0), @@ -341,7 +377,7 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) renderData.m_viewportMatrix = viewport(0,0,width, height); - b3AlignedObjectArray& shadowbuffer = renderData.m_shadowBuffer; + float* shadowBufferPtr = (renderData.m_shadowBuffer && renderData.m_shadowBuffer->size())?&renderData.m_shadowBuffer->at(0):0; int* segmentationMaskBufferPtr = 0; TGAImage depthFrame(width, height, TGAImage::RGB); @@ -360,7 +396,7 @@ void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData) for (int j=0; j<3; j++) { shader.vertex(i, j); } - triangle(shader.varying_tri, shader, depthFrame, &shadowbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); + triangle(shader.varying_tri, shader, depthFrame, shadowBufferPtr, segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex); } } @@ -381,7 +417,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) renderData.m_viewportMatrix = viewport(0,0,width, height); b3AlignedObjectArray& zbuffer = renderData.m_depthBuffer; - b3AlignedObjectArray& shadowbuffer = renderData.m_shadowBuffer; + b3AlignedObjectArray* shadowBufferPtr = renderData.m_shadowBuffer; int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0; TGAImage& frame = renderData.m_rgbColorBuffer; @@ -393,7 +429,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData) Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix; Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]); - Shader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer); + Shader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowBufferPtr); for (int i=0; infaces(); i++) { diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index d82060382..4b5fc7c5f 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -30,11 +30,13 @@ struct TinyRenderObjectData TGAImage& m_rgbColorBuffer; b3AlignedObjectArray& m_depthBuffer;//required, hence a reference - b3AlignedObjectArray& m_shadowBuffer; + b3AlignedObjectArray* m_shadowBuffer; b3AlignedObjectArray* m_segmentationMaskBufferPtr;//optional, hence a pointer - - TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray&shadowBuffer); - TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray&shadowBuffer, b3AlignedObjectArray* segmentationMaskBuffer,int objectIndex); + + TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer); + TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray* segmentationMaskBuffer,int objectIndex); + TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray* shadowBuffer); + TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer,b3AlignedObjectArray* shadowBuffer, b3AlignedObjectArray* segmentationMaskBuffer,int objectIndex); virtual ~TinyRenderObjectData(); void loadModel(const char* fileName); From 6814e334a252daeda4022dc5b614b9607d5dcbb7 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Thu, 1 Dec 2016 17:54:52 -0800 Subject: [PATCH 35/39] expose numSubSteps to pybullet --- examples/pybullet/pybullet.c | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index a3da3e942..5d8844c4b 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -425,15 +425,16 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar int numSolverIterations = -1; int useSplitImpulse = -1; double splitImpulsePenetrationThreshold = -1; + int numSubSteps = -1; if (0 == sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", NULL }; + static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold","numSubSteps", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diid", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidi", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps)) { return NULL; } @@ -457,6 +458,10 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar { b3PhysicsParamSetSplitImpulsePenetrationThreshold(command, splitImpulsePenetrationThreshold); } + if (numSubSteps>=0) + { + b3PhysicsParamSetNumSubSteps(command,numSubSteps); + } //ret = b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation); From e5aea04e23e29ab3c123fe14483a7bce057069b5 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 2 Dec 2016 13:23:50 -0800 Subject: [PATCH 36/39] add back the 'swapBuffers' in VR demo (slightly lower performance, but easier to use demo. fix issue related to TinyRenderer shadowbuffer API change --- examples/StandaloneMain/hellovr_opengl_main.cpp | 2 +- examples/TinyRenderer/TinyRenderer.h | 2 +- examples/TinyRenderer/main.cpp | 1 - 3 files changed, 2 insertions(+), 3 deletions(-) diff --git a/examples/StandaloneMain/hellovr_opengl_main.cpp b/examples/StandaloneMain/hellovr_opengl_main.cpp index d196c8ee8..89aa74204 100644 --- a/examples/StandaloneMain/hellovr_opengl_main.cpp +++ b/examples/StandaloneMain/hellovr_opengl_main.cpp @@ -855,7 +855,7 @@ void CMainApplication::RenderFrame() // SwapWindow { B3_PROFILE("m_app->swapBuffer"); -// m_app->swapBuffer(); + m_app->swapBuffer(); //SDL_GL_SwapWindow( m_pWindow ); } diff --git a/examples/TinyRenderer/TinyRenderer.h b/examples/TinyRenderer/TinyRenderer.h index 4b5fc7c5f..7bc97aa1d 100644 --- a/examples/TinyRenderer/TinyRenderer.h +++ b/examples/TinyRenderer/TinyRenderer.h @@ -30,7 +30,7 @@ struct TinyRenderObjectData TGAImage& m_rgbColorBuffer; b3AlignedObjectArray& m_depthBuffer;//required, hence a reference - b3AlignedObjectArray* m_shadowBuffer; + b3AlignedObjectArray* m_shadowBuffer;//optional, hence a pointer b3AlignedObjectArray* m_segmentationMaskBufferPtr;//optional, hence a pointer TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray&depthBuffer); diff --git a/examples/TinyRenderer/main.cpp b/examples/TinyRenderer/main.cpp index 614b12d3a..32f5e7edd 100644 --- a/examples/TinyRenderer/main.cpp +++ b/examples/TinyRenderer/main.cpp @@ -147,7 +147,6 @@ int main(int argc, char* argv[]) renderData.m_rgbColorBuffer.set(x,y,color); renderData.m_depthBuffer[x+y*textureWidth] = -1e30f; - renderData.m_shadowBuffer[x+y*textureWidth] = -1e30f; } } From 383b30a4e40a7fe4da6802732b6fabfb3f6807d4 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 2 Dec 2016 14:10:26 -0800 Subject: [PATCH 37/39] reset also needs to reset iterations etc move from 100 to 50 iterations for VR demo --- examples/SharedMemory/PhysicsServerCommandProcessor.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 2872da72b..ed8d95856 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -667,8 +667,6 @@ PhysicsServerCommandProcessor::PhysicsServerCommandProcessor() m_data = new PhysicsServerCommandProcessorInternalData(); createEmptyDynamicsWorld(); - m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001; - m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 100; } @@ -717,6 +715,9 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld() m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0)); m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08; + m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001; + m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50; + } void PhysicsServerCommandProcessor::deleteCachedInverseKinematicsBodies() From 61cfa18923f6f1b88bf87703fd2309bd90868a52 Mon Sep 17 00:00:00 2001 From: erwincoumans Date: Fri, 2 Dec 2016 17:44:00 -0800 Subject: [PATCH 38/39] save default VR camera tuning, requires MIDI controller tweak some values in VR demo --- .../wsg50_one_motor_gripper_free_base.sdf | 8 +++ .../wsg50_one_motor_gripper_new_free_base.sdf | 8 +++ .../PhysicsServerCommandProcessor.cpp | 40 +++++++++++--- .../SharedMemory/PhysicsServerExample.cpp | 54 ++++++++++++++++--- 4 files changed, 97 insertions(+), 13 deletions(-) diff --git a/data/gripper/wsg50_one_motor_gripper_free_base.sdf b/data/gripper/wsg50_one_motor_gripper_free_base.sdf index 7fc3ed2b2..552c36d28 100644 --- a/data/gripper/wsg50_one_motor_gripper_free_base.sdf +++ b/data/gripper/wsg50_one_motor_gripper_free_base.sdf @@ -303,6 +303,10 @@ + + + + 0.042 0 0.145 0 0 1.5708 0.2 @@ -343,6 +347,10 @@ + + + + -0.042 0 0.145 0 0 4.71239 0.2 diff --git a/data/gripper/wsg50_one_motor_gripper_new_free_base.sdf b/data/gripper/wsg50_one_motor_gripper_new_free_base.sdf index 68e2a0a6e..0358f7a6a 100644 --- a/data/gripper/wsg50_one_motor_gripper_new_free_base.sdf +++ b/data/gripper/wsg50_one_motor_gripper_new_free_base.sdf @@ -300,6 +300,10 @@ + + 1.0 + 1.5 + 0.062 0 0.145 0 0 1.5708 0.2 @@ -340,6 +344,10 @@ + + 1.0 + 1.5 + -0.062 0 0.145 0 0 4.71239 0.2 diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index ed8d95856..2b62a92c7 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -48,7 +48,7 @@ int gHuskyId = -1; btTransform huskyTr = btTransform::getIdentity(); int gCreateObjectSimVR = -1; -int gEnableKukaControl = 1; +int gEnableKukaControl = 0; btScalar simTimeScalingFactor = 1; btScalar gRhsClamp = 1.f; @@ -4016,7 +4016,7 @@ void PhysicsServerCommandProcessor::replayFromLogFile(const char* fileName) } -btVector3 gVRGripperPos(0,0,0.2); +btVector3 gVRGripperPos(0.6, 0.4, 0.7); btQuaternion gVRGripperOrn(0,0,0,1); btVector3 gVRController2Pos(0,0,0.2); btQuaternion gVRController2Orn(0,0,0,1); @@ -4156,7 +4156,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() { int bodyId = 0; - if (loadUrdf("pr2_gripper.urdf", btVector3(0, 0, 0.1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size())) + if (loadUrdf("pr2_gripper.urdf", btVector3(-0.2, 0.15, 0.9), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size())) { InteralBodyData* parentBody = m_data->getHandle(bodyId); if (parentBody->m_multiBody) @@ -4186,6 +4186,30 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() loadUrdf("kuka_iiwa/model_vr_limits.urdf", btVector3(1.4, -0.2, 0.6), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); m_data->m_KukaId = bodyId; + InteralBodyData* kukaBody = m_data->getHandle(m_data->m_KukaId); + if (kukaBody->m_multiBody && kukaBody->m_multiBody->getNumDofs() == 7) + { + btScalar q[7]; + q[0] = 0;// -SIMD_HALF_PI; + q[1] = 0; + q[2] = 0; + q[3] = SIMD_HALF_PI; + q[4] = 0; + q[5] = -SIMD_HALF_PI*0.66; + q[6] = 0; + + for (int i = 0; i < 7; i++) + { + kukaBody->m_multiBody->setJointPos(i, q[i]); + } + btAlignedObjectArray scratch_q; + btAlignedObjectArray scratch_m; + kukaBody->m_multiBody->forwardKinematics(scratch_q, scratch_m); + int nLinks = kukaBody->m_multiBody->getNumLinks(); + scratch_q.resize(nLinks + 1); + scratch_m.resize(nLinks + 1); + kukaBody->m_multiBody->updateCollisionObjectWorldTransforms(scratch_q, scratch_m); + } loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .7), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .8), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .9), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); @@ -4194,7 +4218,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() // Load one motor gripper for kuka loadSdf("gripper/wsg50_one_motor_gripper_new_free_base.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true); m_data->m_gripperId = bodyId + 1; - InteralBodyData* kukaBody = m_data->getHandle(m_data->m_KukaId); + InteralBodyData* gripperBody = m_data->getHandle(m_data->m_gripperId); // Reset the default gripper motor maximum torque for damping to 0 @@ -4236,6 +4260,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() m_data->m_dynamicsWorld->addMultiBodyConstraint(m_data->m_kukaGripperRevolute1); m_data->m_dynamicsWorld->addMultiBodyConstraint(m_data->m_kukaGripperRevolute2); + kukaBody = m_data->getHandle(m_data->m_KukaId); if (kukaBody->m_multiBody && kukaBody->m_multiBody->getNumDofs()==7) { gripperBody->m_multiBody->setHasSelfCollision(0); @@ -4289,7 +4314,7 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() // Table area loadUrdf("table/table.urdf", objectWorldTr[0].getOrigin(), objectWorldTr[0].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); - loadUrdf("tray/tray_textured.urdf", objectWorldTr[1].getOrigin(), objectWorldTr[1].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); + //loadUrdf("tray/tray_textured.urdf", objectWorldTr[1].getOrigin(), objectWorldTr[1].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); //loadUrdf("cup_small.urdf", objectWorldTr[2].getOrigin(), objectWorldTr[2].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); //loadUrdf("pitcher_small.urdf", objectWorldTr[3].getOrigin(), objectWorldTr[3].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); loadUrdf("teddy_vhacd.urdf", objectWorldTr[4].getOrigin(), objectWorldTr[4].getRotation(), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size()); @@ -4330,9 +4355,10 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() if (motor) { btScalar posTarget = (-0.048)*btMin(btScalar(0.75), gVRGripper2Analog) / 0.75; - motor->setPositionTarget(posTarget, .2); + motor->setPositionTarget(posTarget, .8); motor->setVelocityTarget(0.0, .5); - motor->setMaxAppliedImpulse(5.0); + motor->setMaxAppliedImpulse(1.0); + } } diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index e5b4cc3e4..0a909e938 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -27,6 +27,7 @@ //@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet! extern btVector3 gLastPickPos; btVector3 gVRTeleportPos1(0,0,0); +btScalar gVRTeleportRotZ = 0; btQuaternion gVRTeleportOrn(0, 0, 0,1); extern btVector3 gVRGripperPos; extern btQuaternion gVRGripperOrn; @@ -46,10 +47,47 @@ extern btScalar simTimeScalingFactor; extern bool gVRGripperClosed; -#if B3_USE_MIDI +const char* startFileNameVR = "0_VRDemoSettings.txt"; #include +//remember the settings (you don't want to re-tune again and again...) +static void saveCurrentSettingsVR() +{ + FILE* f = fopen(startFileNameVR, "w"); + if (f) + { + fprintf(f, "--camPosX= %f\n", gVRTeleportPos1[0]); + fprintf(f, "--camPosY= %f\n", gVRTeleportPos1[1]); + fprintf(f, "--camPosZ= %f\n", gVRTeleportPos1[2]); + fprintf(f, "--camRotZ= %f\n", gVRTeleportRotZ); + fclose(f); + } +}; + +static void loadCurrentSettingsVR(b3CommandLineArgs& args) +{ + int currentEntry = 0; + FILE* f = fopen(startFileNameVR, "r"); + if (f) + { + char oneline[1024]; + char* argv[] = { 0,&oneline[0] }; + + while (fgets(oneline, 1024, f) != NULL) + { + char *pos; + if ((pos = strchr(oneline, '\n')) != NULL) + *pos = '\0'; + args.addArgs(2, argv); + } + fclose(f); + } + +}; +#if B3_USE_MIDI + + static float getParamf(float rangeMin, float rangeMax, int midiVal) { float v = rangeMin + (rangeMax - rangeMin)* (float(midiVal / 127.)); @@ -70,9 +108,10 @@ void midiCallback(double deltatime, std::vector< unsigned char > *message, void { if (message->at(1) == 16) { - float rotZ = getParamf(-3.1415, 3.1415, message->at(2)); - gVRTeleportOrn = btQuaternion(btVector3(0, 0, 1), rotZ); - b3Printf("gVRTeleportOrn rotZ = %f\n", rotZ); + gVRTeleportRotZ= getParamf(-3.1415, 3.1415, message->at(2)); + gVRTeleportOrn = btQuaternion(btVector3(0, 0, 1), gVRTeleportRotZ); + saveCurrentSettingsVR(); + b3Printf("gVRTeleportOrn rotZ = %f\n", gVRTeleportRotZ); } if (message->at(1) == 32) @@ -85,6 +124,7 @@ void midiCallback(double deltatime, std::vector< unsigned char > *message, void if (message->at(1) == i) { gVRTeleportPos1[i] = getParamf(-2, 2, message->at(2)); + saveCurrentSettingsVR(); b3Printf("gVRTeleportPos[%d] = %f\n", i,gVRTeleportPos1[i]); } @@ -927,7 +967,7 @@ public: virtual void processCommandLineArgs(int argc, char* argv[]) { b3CommandLineArgs args(argc,argv); - + loadCurrentSettingsVR(args); if (args.GetCmdLineArgument("camPosX", gVRTeleportPos1[0])) { printf("camPosX=%f\n", gVRTeleportPos1[0]); @@ -1665,8 +1705,10 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt return; if (gGraspingController < 0) + { gGraspingController = controllerId; - + gEnableKukaControl = true; + } if (controllerId != gGraspingController) { if (button == 1 && state == 0) From 024ab6725be20887e34e73cf8d7358e29207ee58 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Mon, 5 Dec 2016 11:54:56 -0800 Subject: [PATCH 39/39] expose pybullet.setPhysicsEngineParameter(numSubSteps=int) --- examples/pybullet/pybullet.c | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index a3da3e942..21a4b7051 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -425,15 +425,16 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar int numSolverIterations = -1; int useSplitImpulse = -1; double splitImpulsePenetrationThreshold = -1; + int numSubSteps = -1; if (0 == sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } - static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", NULL }; + static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diid", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidi", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps)) { return NULL; } @@ -445,6 +446,10 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar { b3PhysicsParamSetNumSolverIterations(command, numSolverIterations); } + if (numSubSteps >= 0) + { + b3PhysicsParamSetNumSubSteps(command, numSubSteps); + } if (fixedTimeStep >= 0) { b3PhysicsParamSetTimeStep(command, fixedTimeStep);

T0W zwnw?OPn3k%Kh^HzjyOH3QqIorPLEvC{Qm$gt)5$ZP)f%uHckriLlcq5ex0k!d|UfV zX}&D*mY=2liuX^BW`;Y{v_2qQXJ$Fc1EIm^y?aa=ot4{KM-EyWt96ncs#F-r8+!EM zjyn5M=q-0Xe)!?>a@WRQAJVMtqY=w)#(Sl8JMHBgl&I$z=acF&$2D{IV%Foc*DmaT za$~uV&PM3Lm$$gVJR0Eqb)eq(i{g&4_FH)_CVROsu_pfjHw55;pW*{Po%pXp_*3v- zQ}Cv}Z>V1+cF_4=U@*<|A#dSj>JAC@#ww$^T@Rl=AX~=|jkT3UK3Tq%z$5PEiTtvE zO2fHt;pp%fH92KC8$LA?|^M_ru;6BHJKqSUUel$B(eTOk8%cU(`@c;uaev| zLZ;yY5(nJm`d1O~Xho=e1=C=L8%QpN)Uim}!(1pQ=Q-(|k%7m{#dX?Vk$LuOh@_Sk zn#^uKUP^)68T#{9qt%9my-QjU_mu+G9}pEE}I2XOWFtcm=TxK)vrR%GSE@DHgKJxbWEr%5DNZ5Ni_ zTx;fX`*26EuUf6*U2;2jxQ-{dj}dQRWFcQT>V2x+oGkYCtsmL$rG%GrEA8FKL5|*; z^sZCl1-7xT$zdIx^I1ViYib)=g4t zfFoN$<;N6YVsPH$9jF=+3tKVnTktp-dxTia>@W8?gXbJ0A{^~9sJ59K{ zy*s1SZ7&Qa)UH@C4y}e>dw_CB878XyJ@`|uc(>uLy_LSLq1gCb+&-%Ww;5TcByDs# zKP+SddB`WPUNL+%@N(lz*7c&gcByeaq+ztUY{0o|i5c*q?Z`M?#NhFsm>8(%Or-;n znr*sOs>2EuisDCN>6SUh1COUZ)upL_Y-wH`(-!LHYab*OwuM#TkV7V4%*X&bF~H7F zeuAuDX?pjI^;@f`^wyB>D%Q}%i*TT1FfphZAn;ByFRc9;r5xJ>XuSzu=sco zF10YrGlP(}(F|t;1BL~-1aK<(gO^j3(>!~l>KZPWWqD<%={mNSJiAR%votcPJgo4x zQ|}Y=sK^+|J!%V|3hMq2cy&vQTRV*{Zn7?IT_>_>4oZY0<>ZgLM@ri8UyXF{gc?*g zS6&&4^HjRJY2#V##F2PXRbZnGs)G&R(enqhIDZs)%KOEBE^SXx+SiH|FcfT5Rryx~9lHDGyH5@Hc|27P zop-9)CatUMmhW$++DU%4qCmMwbXU`7nJ{ylz)-E((w@o6z zbn6SIVyt-$u$|=w?2@F6@s24zDE`N{)7(d>Y4`H#8hyfI3-Je^XvKIDDUT|J4-BP2 z>BVO2MHHaUTlQ=4c+`AB;;jbjMYo$!T`on6>g7^T?3uyZ1dx-4SvW#^r(OU#+40?< zi#`^7D4WCfmOo+BbvdS*`o`YXo;j`L+EL?`vK}H=04^N}0OT6K@bADrA=U0Chg1H~ zlUlS*wmw&t49@ISDGXIfOc%;9iCx*3YE+MtMNVO{+M$CEEa~zSmLv472DPG5s z>&LijKM3^y0NO9%FNWpOW72OX(qlH0$hwc%BaC^awg}EfKY77BPH+bqt-k>HLgV5e zk9=*X-FQP!uxTx%wz-zp+23r?g=m^$K3ulYPIi_ceA(i0OLp3dh9v)T|`4g*3H9mrc|lc3H_~C5+MF6)I0aao2%fzwlS$ zew*=2#2!wUHQmOWV*=aEvyH^@#AH7uao>_LgUxDq*WliltlPKteX{9HB;NtEkXynS zbVeV;liYB6@mR`oZtqiMk~~X8_;auL2VI$T86<`qIE%{jlGe8)7}~o*CnqN@$gf)P z$-dV#WoxTjSZ^>C#_Cc|na{uDRJuq?xCe1!N%a`W#yWdfN#bo0H7zfEaIM|qphc17+NC{42?{{x@UCy| z+LwkSktUvap5W!AxQu@BF@SfBXVW|yd+sZn3HE=p?!A~?O}pfdWWyjm2qzgH-9{@# zVVdH>rt;Zig|ZqsK4$}_JL0gTmJbnK#vPVOe1fH;Rg|265hElXdt$l`D^au4?JZ)C z3#j)g2tw}29lG`Q?kc%%FH)V9+GeeJBHyj$y~8O0xdm`KV;Se(tJ(NTr-i(mrM~D$ z+*df|RmOVzaaWT>wVvg-Zf`MvcO2jbcJ6c2X!NM{%_j3mu~{tPj_NmUzDYRpy-3IB zQsPz1S|)=vrRwSk_lqM$L&N6&?YQnguWI7_PvcMcMzp){?Fdz^M2#e|$js{+^~Y>r zXQf#1Z;0{bvB;UlAK0*4t`#q!n&yA`!xHk=KDm%7bz-@&5&|H>FM9SNOd@0 zfj%41{BNe)>smbCR^Z<%%w$&}khwX@921Q9ss1c@4(d&261%P=l|+|sv9{c(JO^aK zRR=!5O22cVO?|If$>IB{w1_6&*H-@kXWFjZleK`yB%FY1aj0wBeY3+gq%&H=O8M5| z)=s>9hdBD?mdID`dH0DtIiUEq%ExaN1tIFu~|cKs$+SYISWXxPdlS=vm~na zueqe~Hiu#1O-oEIHLbjXjIvy&)=)VtSvl?0boc9DHTZ|%XTy8zn@z1Yss8{8CG47Q zrk8q`J7$_97Drj~SzPYOa&f@N12u7g@PCZ7eJ)S2>6Uh5 z?AQ7dZzMVq8pvB}fI%!A9mHgD;NCa=o;*X~JB#nOTgJ0#S6^U~D_I(LONAsb-I4(e zzP(QzSLpu$!oP;rUk5xjs9NayUYDZ$@?EvGcT*W;e2ivBVoPCq_5&Ejb3QikZj<7; z8(6Z_?R4K1YS%?S(sXEU$(0TXc{0(B{1DhAl1ahlt~iH#ErXEqf7x%so+`c6TR`#t zgL&d5hS@BqOY3`dw9=wxMlREmJm+LkSd5XeerE0Se~vt7;hP_bJ}A>P?I%z1E}QnN z%WDhr?HfeiVc9qe214LrNCAhaudiD9B; z&U9PY`S;+KvEW#|e{~OxJUgs-s?Omy*xKpy{g`>h!OMc{@{kJToG)AuE7ra>rlH`! zgjP0U*F^C4gW|}haiQt(7~f72Oss-eSqjf2iV*pv9mA&pV!yK@XUVW|x6cM!S0F%JZYNx){_Yl)z^voW9S3$|NbPUO6dhs#L_ z-la3NoDkhc044q^_%q>qEic4+PlsjIJXfek<;<@=kNixu%c!y@w~-hAS>T=JbF`w6 z%rlO@Jv-okjxRMWXIR%Y&k^6q=IX*2?ah_bOq-0E+k{w{l*tXag=`SjbHg4F@L$Cn zd%TJSu6CDm@PHLn%;drF#nS+5IAA(mT-z&j!VS0Kn&g55KcIl$$0FA7}fSCDVi zG>eC5(seN0G^GLirM^Li9*67Ab;hOaVB=;)nlJXN%tgd0vj9aPBY5^bvG3SaPvFf` z_9d1paU@{v9!so_IXzKHZ_IN=&xh_6rfDwi+ixsTl3%_@1NFz_O@hH~OA&Q#3#yj~ z?FJ@{0iL+;_?o_Jy$F`(YFo<;@~+t=HiQXLzF8FKx*kX6-lI2SU%Y_{IKvD8f3McN zO*`T?y{X;W+3Gr{+auVenq8Afh^j)Uk%sM{b~)%Pm)7*_J7l*JM{u$(^76_<35I@L z4E(s~k8#%-qtq6~3z=bx*^!rWV+Z}L_NQ3*qHO~EM!pudrSzMmyoH@Uc|tHD9lGrp z;0$7x;>HyWvCL*@zzkcWA8O6kqlyfL+{=t-p>8?+0jfmuqo4S@@fTS5g|6!!Ah=sd zwFz4;7A1-ljZYsSHv!I8qoO=m;c_QCZut z`A%BORgx84;E~5%nrzA@cH9S+3ElJ^YE33gaL81QV<+XutyI-6qha@3%i1yrQUy^4 zW}~`$lG`>Fz+O6vqau>|U{!b=ahkh$@x1%PKN#AqdFf3^)afn(xu7lQBCf^+&*S*szBkYWxDes`L`=E`MAbDl`~m=oq27e z9eqKjrKgyj?&+M9(xox;SS7X(8u@c1jgCU~U#&XLL@l|7S%+Wg`qV2T!}oW6?nZgf zu6~tf%JE3sw4QU#8Z<95!@$uZvt_qn^v@LW0m z6{I~uTnYeLbtaMBRyTFsk&%oVj7cP)FCcaKeqt*9mYe4ydD1fzoG9RDu=o6GGiK2e z2-=|Z$LWd?4YieKGIaAIz-)7hkzi2d?)$5Q??ezRL77!myPR?;jg}T-8_ez-ZZYfr zMNd+!No^KiE3vlo$?7SWg-Qk_vCjttidbb}`+?ieMotIPpuA=~dUekPaZ6C>Te6*P zVfmSI{NvJ!tLI?kD;)cDqMtJ;`*L^MK2fxP4trHwZCB0IE^TDCxQs&@x=c^YC~W5* zw#Ps0)Gw$YQx8wRkP1x zD4sNFRhVU?Ib8NW)c*i4%sDC#t|%8<2zg(a?e#e1R(`dsNv7LJ<=e?|B+{%wRBjxf zn4drgHEaOM^&L-oM!51~W@5;yGB)%2Q%d6?9v8AWEo%&z&IFN$z|YdSuZiCS>~FLS zi;oUz_WFLXzdAH5WAl5FfN{^bt z`>m76sJ;Vume0eQef`bF#4$87p=Dv?G=33yU&HbEb5MrnV%mk}y5wKO_I;-fpDTAv`qPMyLyzKi zlX2opT^+6@YwN?CZLyt`Aq1-f>3~P!Tu1FoS3+xxGxIbeI^rEFeVc< z#JLCh*U^6k{3rha2&cm(WuEe7)R*n1DSzdOE6T62AR47B>`bHB_}f&|rMB@VuOy8d z8_CPJm7TmXJZGu(sy6DfIc0J3w(Jp%)|J{!+Qz5mv63IP%BaNPpP1l**b&nnl}bO| zM<>d=W8`h+lp5-aRx;U=w&>#XFj=?Y^MQ)#yb_BomZ2lJ`m0BD0YTi|zMR)F49@oZ zS#!Gs8?ejy*58KXSai$JE?FaKqu2sA6^?n_IRs-rjRWhc@1FyIci>$%2925<$jpl( zV2Gb2@PABKc@@kuYV5ZjWxtrdM8%KFeo^1Q(z!o@*HT-2EzstM7}#mDZjkL{=ffiW&ZG?FcEKD_8tziKQm`wf*^#W+#1p0yw_kdvsao75 zD-4egBP5kmla9ElwIL6j+hb(&m!qG)N4LLRR&@6;%)Vu;k|oOly@@|K^v9_6qfl3| zX3iIi27);kdxBMm{Iln=9R7Z_#(ZMZ)WH8+Pvyy87!Detjc73-HKyElZ)mwS4yg%Y~x{g1w$t1F@ zB%->I9Iwob2=wCywYAR>+)HQXycV&v*+~-Je5GPI8`NQa&$+5>hMCySVJ4TP*xhcL zO&e2P@T9>OYbjeG2{`AKpl7Phs#T~juN%#s2R?2_rtE zn!oT{Lw!{)KeZvcZ?doM5fRn*g(XNv1xkW_v)a9IcsAeSkB6q3_8W^*sM5&{WJcKl z00GBN6pZxAu6mQ!#*vPO7lL)od&0jDHA^|P*zTG?_?6j5JV?=7EUo6s3xW%l3O13P zU>w(V@a{hwe$1L)wS3xK(`s6r{{UqmH=dR*Ra}x3l>{pcHg@#RdR1Qv!=Y%}R+pvt zs%+*$gaE!S5O9RhBYHx_Y3!~QjaciZ=;uvoln zZKWsd;PrJaf=@tIfFo~u%ke+MdyfEW6G^A)NvTI1YZ1(48+zvqQ9}c_s0Y4#R-E0% z%4%vJ5+4w}Hn$pHv8czRYBOw(3+a>3C*~z&ROMJ;k^sYG5rJI3lkoolQqg=uy4Adk z;ueiblGP+=WKb0CXIy2F6$Q5P0`wUqdhdWV!Ev5v$ns%jcY89l@gE+dm zEZmYw05Aj`kV(aOMc$yXc%ti1)NN+B))MeK#@aWmJwkkKD+Sf(gTPU=9vD)@|LF7}$5je;zgWfKH`(;byt>r1B&w0c)#w zLzdsrn9AXS9G*riPvIZN*>&wrw7Bjh@?*5~?Ps`!mMf+h+MC!7yknky>#G-y7xt~D zr>DuTX}8vU0|}dTq>IdM2?Q%CB}RB4j>Yk2nZ7$JS25b6d7 zKppu#1!v@G%ch5?cq_%Tc#l#`)P`**UQp=ardWR6u?O+54g&Bu9zX)MydSUH>bEyr z7C*EG`M?4^x#XUhZhDVe^DhGH8h(kX-^X(e)Yi(d%AQyHLY>*)BBLF^X8?hWWAgO< zJ)!Znyf?P2*0U>>iCGmPoGwPxE7*>i=cuWaZ@B!9hROc`vu;^!Qr~QVvd*W;A={qA z<;naFcfKFe=d-qwOXZqRIv?IgG(-2P+%Oz*)H0qsit<|-lGj#NyHOt2E)@^mBhx&8 zTJ#MI#1}Wu=e5yWd=Rlp`Q6TUWb{9+J0+lK^e#VzE;RX*`#$jfm4Rlom3;U)>bX3O z`c-+gi0!T&uA`d9IR-XI9uti8=uguIw5%?n)$ZAq?o#R#wIhyS-OPWzjCCCdH4OS? zuZbd)_bVmExe><2us3x)bsnGox;%;BLrX-8I4mA$FP2ErcQeB%W6y2Aqw7*z+<$9b zH_aWzuOW&6tf7hE_CBZST))`o@crM}=Z)>aVjW<9ryqFZ+BD^It&R*5azIO8HlL*?yJo;Hr8oOGt?daS8*SzTj; z9K%2E%CENWFnjl^_d0d$#MUxR3VpgUl#(dMV!_GElZ^44jCJCx>o0GpT}K|Nxz{K6 zk#n&1!R?=?N;MUcttIMeHyHA5lVQYjK;en?%ATEj`c#@;n{97vHMDXz>1OjLzzMwi z{{SqX!i_%G*Fv$5-qmC;AAiyl3@#;M*BTvw6e$nK-X>QiTICN56W2x`BkINOQE{$~-nAYg;7nYe4 zp(U99VAH0#o_iIyg`|>3QI}=;zN5GD#ZNAplNmD|^lMFKR%m9E?Dk{IRDh8oJ@`1_ zWYrsZuOhy55C9ah;D;>H|9C5EFfK0vika9r!R(eXh zCB4$$Lp8(6#M7W%xjd|6rg4xzokNJzS2#b3R@d5=nXH5CAZDYI5hv%B!-fKe`k38jBeo}k?0JYTTt!P>JayzTx zaV4F^f)pr0Tws>%kI$ZX#bimQ9}UelzMp3;n-@DlcgH!&T<|bG4L7i@b7_1pXQ11% z+*reMtPCnlYDioWfKR4K=hnRP_*&R%pJuny87H>`?CCqJ4WymUp;X`j*bsB*D%JkI z;%yn^jz~r2q-qb_CX;lCzuZC8F~4M+RFq1wp*3n<%#5#=y9Cj*B1T`yiXC_UN?vCt!?4l zeApsnc^8nXfr9QW&jY4&UWKG-wry!3y0&X~xKNQ?GZo0_O0V###{}|8s<)mNyo*ta zJ6ZMZHDNf3;*$d(?vsPYeP~QIx#zw!_#+?0y(Mhqi(Im`x`tJ`SmtYZredwJWQm9G z5HZ03@;ya(z31%dt!Tb5w2sH&{jc^_zsr4hJj%JxMK6CiX@RLV6 z^qO7ghkP@tTls!mS8>A8%WQ{&?JR2(wiJ@ANg2#x_u-upy3Fx{jYkc(3+Fv+-ZsE<8)(E5^2x^vsal-F==Hgp3Ht zMj3IOf-pN^SDO5H_-lFK{WnO_{1vQCr1(okis5e`OSc+?uW}0yHfMFmtwk_N`@x4+DxfzKcc;hRgppH()qSls!M zw+pcR#Et>%at?Xoy)(p~6_WE^YwLTxb4$?guVsP@xz5X(5*?+QNWMny2_Znsag&PZ zG+kp*w1VO_@c#gW^($#2cK*~blc;16V**uWk#T@FIO8Wg@H?YdMPrxQ>#64ViryNv zhRVhmu4bAmDHU0-be^p=EwTpY(W1P!|V#WtEr@l~{GJDx3Cf)VxOW zL#9b=`n8;L$$GQuQT>hxqihF=kC^o(m53?;;;J<}icv`O-x8*yc?F5Qp32_UqZ31K zYO%9zCym=dAe|+4PKsUd(I(9iE@H+usou=xZ z9q^CEjXOxUpZ*e!7Si@6OO>|riL9rV zZSN#%vL@$Z(fqjudFl_$JvvuJbw(~am_8`cWU|rYSf1A6G!N!7u-_x~D~_c=I3Bg+ zntjN!@aD9vts6;mlM_3B>jym#AanX+y)A;w6gJhz%r^YEKAmgL{8?`umYt|=^A_T1 zOUTaOcpiXvjI%y`H+)f)h3AD{mKT8#u|&P=V!s=rMC0DIPvEg6R8JgLV~%}(=qE?IYA z@}>KF)J8=@2<7v;C$E0>Jlc_<(mu~B^ZUjHPCtls=M)xq zW?ZumTOY-g@B_)uPg&p9ixM%DE^XSnyK#bqSS@@`$Re7RG=9QLI1RS*ST z+fy5d1P@x3C-Uvowp*~yc|TvyrN^jpq7NV$2i;+fy*ckw#kEMoH(X$K9CfC{BkBwH zw%{H|M*S)&A&^V^%Z;t*r>-dG3znq33hU=1ZB_YMN8jT-4{CH9r=Xu(sW&JXDW6 zLX6v$nT|$(hNj315xj>!SY>PtxbOJUG;%Rt-ZOE5yS-J4?UqK~Wchiper(5Nd zb2BgCd(`c)2|WHM8vD6Xx)hn5rL-PIrpU0YX5{OCK*}?gTT=k^4 z)N#~h_1^UR%e$$;<21JOmqM}t*d0LVezhF=^IcT1jgChnih5i5gUtKgGBS4VruMkH zlYOQ*#tP);u%e-6WIV1tD5)!%A8*`n7b7|KrCGeCKX>W|GfrW&_UpmLSCHkGjO{;_ zdHS71V^WUg{{VK)BV=)oosC*CGsnXPZoMfZky$qUz^^?x0I?Tv>~5d_s-De^qvT_| zaoj=36;}5~j_C@>yIVQP`^tT3FggDK7)_!0pH95Bx{lvc`x=&(B?3tyB}vXZW3Fq$ z?!GA9OW|vM9XCgB1g#>-vJ)oE;ZyyP0U-6xJpr$5@%Et?gY>4jTYoZHhS^@;G3KxX zgYE~ZubwV6IW7d(Hn7b!EjDllToxpS+C6$w1E}#=#>MbrJ9-1tfn9Hgv|Tgd55r`-x{gKI z1lL5w7HL_y3$&5Q$N*z$rn5w zqj{=rrsV{Kg>RH{I%c>}8%wNfo;ba2O3|%#5&$UagpEML;Pha9 zNB;n;-ToG9@OZDn^4-H6zGB?Utg;-CH*Os|WD)w;oBV4x+9$+I9YcEg;x%=0a=$BZ z0^_$Gf2AD4<+;Gvcz00MwI;B(v$~S$K`#c+nE)K*el%)2Cb8f<+j*w7xv{v6iKCEo z4ciP4Ut?O(`0n#V@m9OhY$!#oP%CN>s zw;{NF++g}=uRW>Ue7YWUulR!F#ME_3+y zuG)JX?0dt!$>g#qT%D{5$KzX`7%c~ab%~i(cFhcZG6r`a^NPcEHxcbow`l>eI*RDD z$X)y!aEtRt6~gYv1Y{9|>xyz6&!j#cYf#(x6H13phC2(J{XJv3SH!VTfx~P(tA8w- z*|EF6`%3B%%L~Z}`#gw_4mW!H*8$)wcGLbI!4r9&W)-6)z#xzb$UKGVj@9TEvFYF1 zvB4y5i_2Ag(Izs$=cgGUf-~rIQjuENwccFU0Ul-vzjGoytY;> zz!S8i4XmgAs&8=A<23&O5L@0!7?M3g^51C0b27BfPD?)SHXP@H?OpG~`Lxlg+d(&% zW)&R5F0kS9q^@Mn6|za>bscMp@V$-ahIE+qMVrHy5Z;uw**O;y+MFC6gYKLR^XPcR zUD6_k((X%Zi;X(+Hi?y#7Yglz(BnPwIHE(1?t3kySHBK!zqTUrM0Z2U9(;_yxyTq# zlyt}=J$ejw$3x*QZs*0GD6_G@xQhEk`#IDkiDE=;pq+#;Ibct0jEvVG;p5?b2jRq; zMx}crYF6rw*7CyB3DvSn9*ebb2I4_p*{;J-@I23?Ug};Lu+rkNx`GQtF<-NxfMJ>Q zobDJH3!eG*=61QSLY;?JZ7cvRo1DXT}^L)wV=GUCB>Vxl0$F~caS+% z7%JSHcg_i}+rfSbe~5k!dr2f)3yW(>E#g?DIg~SQ9C7mwfPs)OGgudX6PLhR!&+Nw z5Z_4l07nyBv~o!>&i2^Ma@hkICnOxv%!e44Y9xS%AvejhNH2j2(nkC;1s=W*C z<&^L`9^6-{d>GR$G`&+$y12Ku)MJ7zwsT7&phoJdt<+<&Z>B4W@V>F3#{^ntt)$4h zp149<$vOmnPu)2Co3O=Oj>5DxZ6@zc*Q1Y1({(FN3fzb$aV|XaKJi$au1-eaLGR5& z8n(w-sraI8Z&hg{(k=A}aOQi9zy#?a+Cs!|PI)|zJJznBX(jHXHm#=Htg;Jot!C4! zJ)>ix$M=ppXNt!D#s1yVA(Ks;P}ABu$CAbqwg=inGi3DXgY>S_)56xb+FhJFwc{<= zh(RRqkgIS;2qfTiAmDq_=18b`pF^ zw%0W1>~#z6Dm_~9e7LO{&)IJFb@LD2jGSj65D!moAI1I)@df^&B*#{dP?K)MF^z3j zMj&NM^b7~_4i8$x@D`^c>l3$$JTmdgXCrwN&JstnMc^_rf)0B1&pj$fbJsi*@WB&J zosH$HTugpbFbn0WKkC*+;k^ksBns-ZI3!6H#`Xy;)-Srs{{SH)(2ftN?ZtCC4!Nh> zmDrOsajx*bS@RGuJmae=$9_HQv(UVIr0V*OzMCsYZ#ax?ByCnFqWs){g-=2A66lvJ zqIlW9(RJn6w%wn&A7{G+_3l?AxaT6e?QrQaSq_^U;d)n{8f!~=2}3@GD0o1T4$2kTDc@~fKn znl;9$6}`rnHPq4Iy0lNSQO`LZ-EmsB8fK|^Z*a{tmls=n)plPlWykQym<0L)r$2>J z@VAHcjXr3jvr`N!Y_iNe+$4;6Dh@e6?_##Fnu;-!X{{O(0f{C1!`K{EXayO3VGOJG zeL}^hYjR72l#|To_`3detE5P})w;En*PR|h$qn$_@Z+XWTz*vsqj@O3R*%cn?Lh&R z$Cq(|lfgcoooZ?9G<&Phmuzw}31oz^SqT3Ccy{g0R^V&hU0pugF>kivaOPOPWSIw0 zr>gP?1cOvHognILB91#&novx9XmOFO9{wB58@O1N&B>)dCL zdeXD;de1vG<1#ysoi>g+#s&^?%`$Z)(X?ybHYohIxP?^hTX`ElLJM%;PNKE0CwqA| z$r|~`1Th3}AaZgBKLd(xpJ!`%=Q7D~OpB2l$XPh(-Ri!Zt7}o}u-o0oZtEasAy*s) zBm&(kW4II8_=$|mwmm_lWg{DMsKc=warCS9`on4#p}e-wLQ#I{>Bv1O(rqK%E3yc@ z?XtXOv*ocI^WKY?W|lUF-QkgA=m|TKyJxo<&MLPjLQCsbxP_K8A~9SeBZJR=4@%|c zy=A!anFZ97M`WJ^e>&=x3JT!ylgwoz!jj-7=+4c)-EWu6U_0H2Ycb^S3M2 z_ibVAo+>1h*dqI!;_K1rk*s>87O&MPft(EtLlC*u+|(~z`kX~dr1$KSkosD zkTLp`T^7HjN3Pm=Zt%^yw=ibfNap}oH>iD%#z(jP)cz zrQ+>BRk;1k(6liP@dwPKAXX7Nh3y`76K!mj6qh}(`nRmKQ7 z>V0WiCZ~(wCy%MGeNjzn(iMp^36H(0LLfpf%5(pgRS4k4u>?BzuEIh(+6-t3=ae{ z2FB(*^gTOL@(yOq{{R+Q-N%0CXG%CgmuG?azg+?K7$~7)hIkICWU$-hQ*rFMiLRR z8KNA6&;I~grrpDvp^+EFs3BP`<+r<%NLZNUiVr$BJF%V!I6n24tLgTBF7Wf(+*(=c zesrSe%bxWiX8<0AgYA*&pGxTUFA3e5Jo`9gMUpbF5-46igdPW|Ij$STa%x@&L7QDQ z{ONW|?`+fga1u8rGB&X|`H8?iGewz5>pVB%*!0!=MT~bgb4YlB?!4uM~>R$}Pw+p4pvPl}hop*1zvBoz@*a2CGM87+yf$SN6jjPE>S9Plex%EYvp@$RYO@Ay#K#-X9! z_(x3CEZQmIwbV5$w);e0U{ywrSIO?=kQK9&khrfSy!cZGhx{L_Y7ZoKcA$g{9rCrk z^LA{U$jT2vw~}+zV0{^3sd#V2J|MW7^7~BGq|#;kRL1M)@|L5W%gAE2Yc)(UNh2||L!b<;$YaM9^rolb zEjIJU7JeV_wx_JmuSSk9yi0E%+3j^$m3WFVkWw~f+6dqU1m`v2zqB@$sAwJ|x6*H} z7JIvUXyueDg0U9_ln&pCFX*KP& z-l62O+uYBv5^*6Q0&+b)E77%yq=wp8S&x&n^Zmn&2F-cyui^=H9}8+x$@2j!VX?Gi zfynjt;}y~5Wp1Z0X*6=T?>AtAc_Xb%SwQ)vhGt{DW0TXltff{(VCQ=F>T&-7*Q@>? zwvzA7kg}|C;EasnzMhpN4!&l)nNC8L8x&`+(xIBtKeDScZ<8k~6#Rp+C*0?XxpNF_ zD=M&&SY-UXueDD;qN$^cD}UU@kn=g=ragHbKplr_2G!Nsk#x??tTFQBW4F?)?I=rS z`vOO5xov0XzTCe|0iLJwsqeJUvQ00XyJTKMgV%~BZh{$MKG@rC)iItM9G`l-6wP@f zJ1T`oPd}xtq%;kX3!NSFFPcRvfm*Ipd5POsxs!h|2K^3~KApGyecFQ`pU$ zjBMI^9xxBSYQ4+>)Xf}`hGxNB{Kwv{Y4PN%GM_O{2q&WBzxn2)n^H+Fbt7bqzGAaT zcHnesZN0pET1E31u`PlsXl7e&H_Y&$ZOn_;J!#El48WiDW2OgxtsaF%kjJ)EW-_a7;GbHzZHZ#}nF;i& zg499s?j>8(>S}99)){wg1;5>*+J>P$-~~42mpJMEb4^**fMz{U(xZ9Ro6AW2$5KZ2 z$IG8ekXrCE$8K;(LHSgHBiczTmRyxlxxKMf?caQiq-_M`am6^P^SdhNj(QpklHWGv zJw2!^rlOT)IKyWg9D|;{X>H206@A{vJw54@NZ)zBhl)!UefxIq!js6)>q|sWQb_kJ z4DKg(c;hu{OO1s}t`z*O&o~ubUu=rR4o+0{{5YYLdoJzR=jNo|gGAEYE_Rk?+t7oG zD#XmNq-xpwxd(1Z9`sa;PRH7p60>Dj80)(|KgOd6Blxk@lhT9ob?Ch_O6aO~@;K}C z_OCxvuyRNgWqxJoM`27$IOe+ZnmE=)8&$~pfIjrH#fTVV?|%pw{AuvUs}|3gl^M=@ z)oWpDLbhfr_M6O;YbZ^dxZ}P(YDr`%ZzO+supm(@v31bF0$jxXqG5%H2aAc%tMus9-D#f$78|z*1zp0t!?7FS&5N;({5L3AG*Lj zkEza1JuA&*v}xhn(MjhYH{)IR#B1g8r-eK-J9)9&!am0DFD|5D7xW-toYiiN*ysEm z;5}Q$mk%DEzGQ04=DWC5LEq-}*-Qh z_-(!ud_UBNn=#cc+BTgP&d~gJ9)J>Y-nLi0<_3eN^ezO0JfwrdiR;D@fU5qqhSCj+GpC@t8hc%j?cK`qx}` zF_K7Vz55Ic=WdfH8CLJ^G19dyt~Y4S<-R^`&Cd)gG_rY~T}d6?i%lCw>2dp} zBW_PnJ^FO?u5U$>^G)!@y@WC^n6abh91a&N*N*km=-QsOY_ZO;*<4!813Joa^Qbs% zj^p~!TDfmr)zIPKhC+k{U+jNXp9fFWhW|nbHN6x>@~SpN$`%Fq021M{k3P1>?tL~ z%&5GdmvK9J>OHBxBk>NS;n-%INwu|_@-$>ob~ncBj1#xNUOH9uj%ZuUSQ~P$$gJ7i zMovFp&bbeZpBC=CC*kQAPql^}PUQ?x`O%3Kl0adM^#JwH2eGM6><)LqUMQIO8&uF* z3mv+R)N*by{{H}Sl19_hXgTekxa(f2@R!1N+Lo0Ct;UBYp>-X~$g|no2bBo<0bnq8 zjO6qjWY?1T7f6O{_@a{f-aDA%NjC=hOP;C^Z>Bh}X83%Xx5EqjE9BKC+cm(DqY%Dm zBapAi>Cg~9l{Fo-2rILp@hW(K#tCm{Yo%Ndvd`r#%V@1@B%K_}Hz{0m$vXa%ITMbI#gv1gGlY&U)87m5tIpL*XZhZGInkj?&*m z3k|zQWb@ijF{5w0hE~a7d-GjZqwwEP)-PHOSm`=!cg$bU(x4XB_aU>lXdEjBJmarU z_0IS&Ow;xBk5*}HAf70QiRR93a&Sh~>+^Gfe>&5DihuBoYZkf)wzRy`H2}+Z=B{nx zA-~ngxmQ#;7+^sd^%W`Hdm1`F!DaYssJ5QEmZiQjB#!b~JpTZY^yHoh9ANaWrXL4r zpAuT$_Veu8#paz3#JNzTehDh?wD8OA>UiYVVAm}?R`=HWe(fUW*+6?aXIq49gOrWQ z8^$>V;fj&(S^f*vFezP)i`vPOJ~B7{$|K>j6u9JV-RJx6Yo zn&y{lu40lC$L(doLJ-@cA`_gu-jdVS(!C%<(Eiu4~7_(uCux{l*djtho~ zf@o$Y!8X_cx-Q*_txkV36f2r4}7mqF~`=jkHOohJYl5jS9e0Iuur%9yW zt&Xi{aIlqQZF3$rvw_zmoRR83#=8Fi3`;in_QxbLHeAHBZD|*rp7|hij=uG!KZv5e zf3a;hUuwxmm+pd~@>{XTaZ62!FgzKl{iDO7-gcU65<{a&wrhd>J9EL?)0*6cA5kA@ zhJUn4BxQ-2N0_+lxq6a1WM?L@uBbxSAQf#~`Y0;11t~aB}JM zX_~wu*7|QRX!9W44>>p;GIBY^ZC!Z2cx+)098k$-{{SdPB$hwy`*HLqr3<(l+IVQ$ zt_IlyE>$E=>YsuC03x%sd)!L`$8Nr4q!nO?3^UlTPWj@i*!Zs3S&hxqbIUfxLd!2N z+>xJp)7C}8!jfpx+(W1|N6TZiP_P|2`EqhN^rvt)?XOnm8+&zYUzLFa%|2V;{{VTp z$j?Js@#}Im$hWt|vn~syfQ17ccK}9xtAWyWE89H{R^r|{buyvuk3M2afw*9CfO-*K zMv|>Qi6X3*Z*_bKSsO91Bw&>OA-Ar0=}9{>CXJ0tUtK!jMKp3k(iK#ZS8ycydedMA zIb?4zvWH?0!n<3cCmniVRxX)wCxY~Nt#7U`b#EaT7Z(G}xtrCPsN2UUfGbMh`!iP4 zqL$9;Na6!Ac}zl+&Kn)hb5C(v#a%aCxVyS$S**pe4qt3+w*-!y9AJ0k8n9Mru71%B z>v3@)%0)NG6;FI0Pi#?dX?Rn~^6am<0oV^LfI5cnoYgedj5ha;Br-+i=PIn>$@BvU zk3ca{9!P)oyg9m8kI8Azlp|amA6$F-;;2dDyE`dvAhlVVLA3xzRc7o?Jt|0iOC`pK zn)=lDlH#Psdm8Qf!>zLt<8vaTdg}! z@}!AwA(%3PT*l6rT_J($&SV?tSwN<3aTB$bZQ0%0QJXu*3xzBuMp_#CBKs! zEA56uAoA1!$oY;*&w6%?d-m3k?GP+-E>zCYhj$~Aa1Ty8{VI13q&g0|wv#oyHma-D zrAd!&;d&3{Ti@E2_7X>Q88%!gP19T`VtVuZ@!GQf!=>tX4I?eW%B`{4Qy>A8f;}q4 z8XPtjk|c9(w}&r=u`(6UB!ax;(kDX~#{NIkV4Wt}6wPnKOC9iqixa@l0P;F_>s7VC zAKXEvE%lw|o2U7YuqEQ8D>2E!Gv|}<>-g2*82AdqU$nQGZ?@a3?@+OP+3CPIIr{U~ zvM11H-mqL--Cjo=Ta-Pf(ogq}Ndp~d*_ES0+37lNy!Neq;q|q!7 z?mN~^#fslbntMINO$geuNbQeaqZwiTb4vP#hd=S4=@Du9*St}yL#D=6<&N41x_$20 z19Gnm>OsfSxygJj;N4$EwR?Ey`#r!rZljiH-sr0BW3Yu$mFf=!_ciH;;(b2WH?!2E zYs&^@UpUO$)Ss9fjAR4XJu5p$_@StH%F5tFrR#RLP~1JbG%#Djm>j6ccO-Qr{G^l6 z3ObeOc}K$!g1#5(2_7Zo-1GC9fHNDY7ps~ z)}aQaeHotEi7y%zl|lQ`C@TWz7%E0jT-RZL4~Vr5F}#^{-sIj##e%N{`Bj1|Do z*15kG>DsjRb4PW3XBDo^jTAq-oseT-+^2!RIqQ+@$)nT{3zzm!@n?*DU2&^7i1a-^ zJD82F%#!J{tdTF5hJE|KW|6ayybryc)}Djl4+#7}@gmyzP8HFnYlU0+EsM^wfTS>A zF_?(+)T!j>n)T79uA!n@s@dDLZ4<{lk2A>oM@$}jeKA~Jr-QsV;hDd)=d+nsLRL2O zWVn?J5%<2d_w$2#_#;Li$AY>u&r z?RG%EPsy+^S3 zHRuujuU5Z`*52N0iLNpujy21%0FnUj#c>`q*X``QJ#%K!?UGr%&CE8H;~Pl-06d>+ z^qu+~R((zyDVEvtB+l%RG0!9Mt14Ck%oxohCE5Y5g2_JQR@&dhPXeq% z14ka!;O@@@J^NB5drP(VE;jBU_VwnXb=>Fg;a4MI&MIjmLn&-F)6{zP{JPNLZPYYG zZs>4&eiRQgGFpTT;x+l^|r3-2FP#m)cFohGai!NTZOQr4~@c zAHe>#6`r@KMr8XX#l$Ni0EpXZZg{AiFu3`-VV|k|eQ2`k7bXHBDBBxGF_PbVnwHTP zJEbbj%bs}T`f*jHjf8A@+A=rwk1&fiC6sDfZq;3~S_T|{7$>j$ z)k@t|qkO@KLQPF&btRUm35ga)&&-+Of$V;?>wyi7`%G*XCBlWs1d?f4k7ubap3zt% zGeW{bqieCkh0i>D)pL4oW`DS<20&i*HO>D3_LM8;E({}Lw?)TpDuSt3JnRdMg*-Pk zO)CYnSfB=!ZFTjZ?XBRrb1bloCC+>O(eT~zbtFfPw=Uxd8`q+EV<7Itu0t| zELuebct-N~6WH`0N|eJI{nf@><~ih51ww9={JV3H=U3*F62?0(-aR;``v%2%muK$& zY~uuz)}vw0er4kzbIxkj+)=VSL%VK1UBoL9&T~*Dx0H4-EB9BPooYaq8*wCU&&)77 z^!n7%qQxFIhCNO?QD7NMH_NqGCyWYkn-S*>+3o97)UC$LA%~db4Uy1sO^QYvSFYZ0 zY0%3Y5`OT0@kTH^W34)8S#9HG7-b(ny#Zi0FqBQ+XHEbl;)+|PZ{6WTWpZ=ZsiLHv zPquu6AZFc+9`zmAU-}a0PBs0f!fbHKGBO|YRKeJS7qUEHSM$Lje{_oc~ z^{+nc>{cd)HuvxTH0|3LJvrzoCjmj~I^cDtsowirJn%72>8x%eC7 zOH2JW?jI&$B-Y|#ji>mdVcl?g`{S*9-k>ie*I|x0ZQ8`4XO)`_8?Xbv73SX_{3m0q z_{YPkeH@Exb0Dxek@k3eJ$t>1$K(Z&A+lrHrM(@BM#}(Fi2jM4%JY(T$ zVE)#Y>s5t>k1e|GF#^9TVTKBfcI)d>)%7W8aXtm`l-@JfqO-T!yVEZFe(Lu)_Vljv z;-AAUV(4i$x;$m9?Bfx-6R;Q0-)~&?Cz30p_+#Lx{upY~TFEorOMIisyEq7O$&CL1 zbo4#*p0(P~3r(?^q+*SpM+56s81)pcc&)FEue=YdjW1rhX(P8#!brb*&ItKOV~=X! z{BNq;YWm#QHhb17n=Fh1u7BABwS5Vz{4llgW$)TGXyEgqEEFLB09zMDR>wUn=ii7P z7XJW*YsFXEd~G3EWXcBXwDJew4nGQ~Vo`@8Z;@2z8Og>E=Uq38{taFDW5d^)rNz`Y zHa7N#=t*uu?mS=&_0Dn*F~xHZyH3~KHjsJa^{+v`_``4FpM`hYB-RYKYiwdyM#3^E z7(H?c1Ew)m5SMf2ooyhN@>R2jC}CDIG6nM4PEJW3Irhy%VDdt(BYed`7$=fFas6uc zuF^+viz5A>r`;T5*!omIWgA<|kcM7aTlllmx}mYpEx{%QnV02h2TY38)7mjeq|Mms^rBye~f`r@ys(mtU0Z{kl5>;4h4 zv(@emwcU)ZvTW@0qd3Br=ii)XpT?~X6;jUQZPY$ppgYmz&Qo#ul;arb`BZ)lzS49L z4(bbi;g~fG%}U?w(0PCrwCk4{87Dn32Trt_PN8i2S&mCTv_~X$QmBqw4wR0PD zxD!~v6ZHE(_(5-*RJhXF_7AhH$`U~2@#P)}Imb*^_OW}T-Oc90*GnDJ0WSD3BO|AN z^}zg1wDA79pvLWSGHO;%#gcEF#xu28FAP^a5}@FmoKm+?Cip+_>hD&))1|nvj_NF| zNb8=2jP4`&hfq(_y(3MA)%;;~rrk-b+Rr`Hi+NyQIv+5drx?Kmi~_uM$9m!Z7<_58 z@HT~~!*8eGO?hG&t{v_Q#^m#m7oEKFI-2?i!X7`g@eRd~iJ-CjM8OZ*V?@b~+W@0+ zmimBt4u-I)Cv!?_~&_lv5A@~mT<2kOi9Qq*bHzz@l*UN)<=arMJ3mW zEG^z?mEv1t62>IwZ=Ld@f zj9_qh2cFH&bIo_Z7W@$=x2M|b5$cmQvc?+dn_(cljfOVJalLWDBy*8oRjPi^Hva(F z*AT&e9xH}ZX&+UxBrZ+6x;*Vjq4twfun2cnqs z&hJ5y*BLcFon+n%)Mbikr1Mf=HOrqdm=5sz?dve5ONFHz7WvAVaBnbT}jhiN5)(B9ezKoQ6VjG1-S&(7x2-(yy)>`rbI~+Y+qto!d@N2N?A2Shw0G?w79L zvfAnwT7z&cgoZ`H=OITY0CwqAZu}Q{q3Ch7oXx67BeeGd7Glat%P3ROWc}X6aYr!X zcTsBA_e&kcz0*Z{LgEEtH;?be{jtVZs3xvKuM>R*t@W(7Gv{!f;5i2$`1XB8alRk7 zI_xptS-{dSmz0u6rrgPrLoQZgImkT@dwNtq@QmEc8XG9C=5@;m zUQ9Ss*!12&_Bf~NmcvL;!bQ0AnG=58?FX*qI6Qk&Kz6qFR4{eM;*1j#FlL%Td^5wSgIb_QI3DlHJf>NB$n`@X`z^qQIiE7M;I97AI`4n_fqOM zLN+^Y2_Y6kjlg&R0QFVs1~smh@2oAtvs%Nn4ZBH_W0E&7UWchYIjfHYMdbO=!*0e# z#G*j$DL$j9UY&Z?IDA2Ipg^{z=C@{Tfu&L9Wb?-yW9#0mY7(rH#UAgp%^)0)ncF;M zcKvDkfn&;Lm64P*j0nhM<&64w{3%~klTAd8zST3Y%;Dr482W&F`_{LI^&2fdHc6If zV~tAhxJFkkjsP7LR1)d7dg@(BCb!>p{;f&qSFSzDqtF9E@g>H$yK0>f=yJt`^?yRAm{r7G@pD>@a$C2d_2E=`a16eGE5|i31J4>vn|n!vV?m z=kOKOSZH5mo=+zD!qJWUC6fyv&jTxr4`Z5Mq{!cGPS5R4B+KQQ)NNqo?Hhu$qEND#V4Ab`1im+{;HDB(#J%< zynnVMTuBOsNkLeZ6y$(9DCG3ynnKiv#kzg2v*Fp6`R*)b$R=x98YgERiBdD3obg#U z8rGL6ih1s@H^Y}i49wDCdM*PuPP}{7>zg>W`C8UVkyI(eugt5S#OJTlu~Whpx>HSY z4dO>?`B|ooa03oDka}~|ADul`qvbTLb*S|nWv9E;Bxq6~#wX#S&Ts%6lhca5r0bUV z(n}ug&msNXW_DSm9nLxqJu}5|^TobZlHN9wHkXH1+(^e_IjZ`+U z_}<=Emc}t@ZU~-e+~nTEJt&xMqnbhHG}1?LAlm07oB}d1Pw7?s z$Snd$(_LuoB)h^#nKvAD&m3o^bPIa78uXVs964<@m5w(Zf z-M&%tsN2Cj1J}}(iq_^G$BE}xvyJYqWQANaNpM3W5zi+F^u;fTd`n}b-Nz}AL6td} zE>bW*h~t*@z!eqcrJdd6du=4Q+}i??wXieD!61D_Ua;`Zwxy|g*A{bmaiQ2Og zXvoOP9_JNj#XbwPpHp^{ZCM$VnDZdOQ;?@SPrv2XsA&2v&Y!8ZhB;Aj@_x&4K|)6xHC@;%PXu% z(v^u1OyFdXQ`0r8rR#dWr*zhKx?FmFyMN0`Ct~J4@A9@VNXJ2n!SOb$rP}I#PuTSf zwn)_TBW&Nhsp@(3rOGBjbqty|l^e{FTui9V8H8=~AG>q)$@Q-n@kft*L#_CLTIxDn znmwF%4+wdoX<)q}Sg8`>NY6O{umwjo>Ao=Wwf3iNC7ztWW}4RtBoUxSbIAw~T;r%G zn&9H`wcW;J+$sWSHZx6?AbhzQO zv4$HIT*Vw%RpX;zVyerk>WQhtZyc8XO#G<21~l8>Zy$#hakw65@h;QETI4qN3w`~O zqDEBRMzExp7tgzeGMuumGDsYgjMvD2waAw(Tl1)bT;(MDY*>0!yv9b8$bYmp$v$X;9stK7kJh-Kh_-S^V{d(N z50clJxl}8(VV#d2zn(a*tHc&|(`nk0$2G>ECB$SvP@(66hujWE+?=isdy3BZ({}Ut zUqy~q+->b5x7ZW|7)aD)fKC|ToPKrbJDfMU=a-iX(f!{qXzAI%3Qsq2U9x@V9Fvay z>Zo9YhVQrk0I!;RTkUPx?Zqug>S}4QO|5GXSisS=mrf##wgLjj86@-^^*mQa@dv?H zeiHI7be%%qR3n$K{GN-Fir@ z=Cfd0)@BkFUz-jFGxZN!c`uhZ-6O@dXp zWml7KPb3VF^UX*S&hEjQ-Z`M!!-hNa^rAf{%2ko1WsR7X8*!Q~aS3p%ziPLg^8Mg2 z7-FJ>N>Kj*-CnMD9kk?2TXjBUlkQWHu_)*3%|{NSz4vXx^aB{rxfMN45j@hZjDB2g zBBwbS``N0KTp1?MeCN}Ob0W_(7C2lUr?0kXwTFC*<~9*W8Ntt5IatO^BSef_A2H|; zKgy!BxM<|Ve4zZ?Rmo)i_s+YUv2jg;)k|)}doNAD{c2ZZ=I%N~c$+y=x%s*3Ijd12 z+NHkn>(3l?p&;^h=M1^+&|{jC;_IAztIq&`g*!G$PUV_5;GLxK2T@abQZguI+B3#M z%^Q`sHs6~(pTeX@l6gL1oDMjtDQ&3bI~cBhPJUnECZzHf605kWZWNxRd(&XSkhjdG zj#mKj{(l;7rzDd=O8x8=&w8B&sMBp1n8)T}j;EzKSeW==!Fa}cRXcKF#{>bv9<`w@ z`|MKe-!}kL>I+c3zWXb#;NLLg9NTj9;UCOxWf+(mF^yD7~?z9_Ot#nTlYTA9X za*<_aNRM(l6Q21sT`qnjXqRRkx(>4npORUDiKSomf|0lD&3Xe&0o%B%bj3Kvw^6b% zR@@GK2sP(0M@zqFeZS-ED27SZ&uWJOknhygt{B9gWdRW41|&NRgSgD`$)jc<4Bl>rjkqJZs(v8w zHl^_L@@wmRH=5GUP$7}P3|NnsIO7A{R&Kqn-gx)G@O_}a_NIq$zG}Qj=1DkTsV5wF zA4-Nbz0uF=Q0q|XHn&=W-$`bGM-9xt`D!`Zpq`!ZJu9~TpFDpKo#Ht(=^}wG^-a5G z$y2>^wR-cMp0(*-D)APX;r#~A-&k8+l0XQxnjlQ2dnh~-F`vr3PAEr@{vpXVzMmsn z-AlN~0({X#4=sVvc%(&A{ z#g)GEZzK_JW=!$B8R>ydT@d#@gHE@Z<&sl$mwTLrX!-yTwt9Cx>%l%e_&QGy_}+WC zR(UM%u`|iEm5x)8Q$4*$rtDP@hnoJaZQ`3)tZpu>r{aTF1I2^JFLGat;Sh znWb@+)6Ug{?H{<5(6pk&O22pa2)TGVvSK-*>x$qUPuO0FU42C6$u-)bK4Z+V`@M&s0nI6hvmA8KTz0QD_^Kw=v|G!FG&@$ew{|93 zqTIISjyFfs3<<{v73jK*^GoEq$f_I&fJG;v?OeyiO;Y1d_-Cnn&E(6r-)gW0iDB6C zan_$rN{Z@3@IS(^-(K3=-m}`mAj3$%JIryApbq_c>0e2F9Pku2wvGLlscp86io9U& z^3HRE=-53CcrU=MYVO~{zFSDM+3F0Tk~QA;`x`!DfI&Y1(m*Z0-5?%^t$knNPlXHN z4Ip@fPq$WWP%7WOlQfF5bB78}6fhiTo(SZMMe$>iGWvq@D)X z#&;DxNj-aX#dOym8NSyvYdt36Eu@!8%Ouej=2i4uwd1(9LmEh+_vER_<07H>lQf<^ypzc%PKIIS%@|b;6R%7Y&#xyQ`OR`S{v4P+ zm83V<7mKH`EYgxBWheT3Q`B3X&&2_KtIoe;WVdO6VA12RJv(*lPPNe5b+wtUBDU0{ z1I#(tvNk#SeLqU)qtxPnK{` z0FA&5@H-Cmo1)pnak}z5pC`!*jG5(qdj4lTRjZ#4Tf?oveH#6;>*ftKPqZip0|4~w zaC%W;aN6YHAaTTMRh`fF8R?AfGkjIJ<}J~-Ol z557%kcz(vu#kzXjM>H_%5#>bQUfEdx0CoFgwt1@e+AYg`n*1ExK$Y-!7`qqff)qn_=YMtye79gd~#{!wOH*>5;UK`i2nd}$>TWm zBDHnv7LQ1dIU${;oBmowA#5&s0pIZF+L@!+M*5UCc2@@0UAxx}T_W`8@kxl8**7ldsel_gYUdEtK3~#&mHtT zjvZy##dFZ6Nx;u+gY8x|EoL*f_X{+;3G$vGb`hRQ{{TNq7NAnswRpi>UC`XBx!UPA z;@R%Nj+p2wy{?-iq{n2xYLQ5J97?%fxlla@D{99^()AUR;^I45?ip7W^Ai%TG51+{ z$mz%*O0BHw7UdOXwN~9B&yYac7bF64pU?jQ)V2dU=0C7bw-ep8EV)E{Zo&TmWlzda zy>)sXq4vg_^7`Hw-UUG%WMSk|F}cd|xxG7PxoGt*H^f@OOMxURIfYSnEKSg0la4tj z*Bz@;+G}qQ>%!JM=8g-9zFD{JXUA1I$=pcq){Q{xuC;~J9IVj63e2h!HDU5EOoBR8 zI*ylXticxl05aWJk^r1G@z}8H$MNF1gMT)?BYD=g@?8c$GRhW6XXM@ue;s%bP;Tzj^^48X7)8QgQA{k@;)_5hox&c^zGt}+ov=&p} zYIgU{kp-L)d9q24p6mv5(~R4{9vLiSRxJ`FyL`jX%6a>scEJ2=%=}Ax zf8w7ICC!iawT;AsWS0vs`aw=`p}MMjb)|Q(mHL>Mw<1ki81B63Cbo-gi)(hV`Ndn0 zIAn#u;DrM@#(1s$Cq%r}O5JL0J&lwh9@5zy%M3&2!Hy%wIXvShCbWDZ@V>{x2^_c6 zNqaPhae`ZPkphq6W7Us2{A;XTUe@;V;>~T;6xtDWGsh$Js(L?)EcMHojpm-y+%QB5AQ3EnxMR~E=C!pOJ27Ih4LU@+ zUa~^JDvpCIxCYN)ey0^LgS5-IY~yQ~<`Ksufef)G*BpQYbK9*J6S1?T_-{|JSehGI zO0fR`S{#$lJy);!>rK@3>wBB|7&XMqh!BSvRX&@~Ada<{E|I8d`p7o6vf10LfT|?w zsG+{`3a6fX9@U%UZF1{N)Emi;;_~tt0C)wFluH@w^D7UVZgHOVJw%sOZ9#vh*lF`d zs|=tPW@y0<{{FwOL0FIDt68U&W}0ahHNcJISpYv=WMkJgX*@!@{kHgFk)cuZ{hry( zigDZ?1~}lF=dG6ORJ~h!Snj2^+;%M1dr$jWY<2dhYnpko&Y7rvrtfjp8p(o^0E`9t z`*Bn}OQk*brk57?m(nW#02r4M+@DRk$KzIPt=Cx8?jetLyq4udMJ!txiOvFcKD+}} zJV&FmY4K0HPJ5u+8b3GgDeM3vk>9NrK_S|1yM5v1`z_NojPeqweBUxgQJi34k~*Jk z*DK@QTTs=Rt*ve*Eo&HU<`x8=zvmUP{fTEhcJ{I~hDDFe-t1%ur;l9Ve@fL$8;uIf zZk4D>d1sxc&9n^}Jo|7*wM>dRjRR6^s7!a4T9VCjIe#;1;d+K0G5u;iE5sHPTunXI z#q3KQjF5$h<%03|hv%Mu3etnYlU+Q}$k55=F_Um+jinvJ;{XNdaaMHC3&#tiN9Os! zW;90(ymmS2MOQ&}Iju`Thfu!zWL7J6=943dCuDw^IqAUl=DGcEL$#WAjyruG;l5Uq z8C|833GJ5j9rInMjU;5aX}8JdN}Q6aK5jwAKZNw=xk&V{?L9}%X)*GXBF4K(?4u{3 z9Zf5D74;cyYjNRAS&UcFTed>Ta#!T%G$4}Je-FXYi86+dHl}JC{3dAVqzDcT{7O}I`HMfzbx|?ZY(Lol_zT+JSy;2Ej zsU5mqT3LUjN%As=DVKf zCqs%B!^tbOeBCqNpL7;02!GZzgfQETDD?d~sfyc+?=Q@fNKh3Xq%wy~^R*@+bf{%fR*52sg}T4rR>oL!#yJ#9>tVR) zE{bKcx42m3Jf=eDoV_0aM7sBsQbhERF-;8<<5;I;>H@@76{B6GDn_- zf!O+*g49V5$~QLZo!*6}Bq+%sR%TMY0X$-yVc0Vql6B-``P9aCWeQQSdJVY2sMbxl zCwI%Yu20sL+8WfF2FQ@%TL+LqsrE zpJ7N&#jAMZmGaV!pyX$^fBMxhv1n#yl~zSwhpv6=I(ejy4XL(2UNevL)~@OH@;pq& zcYWC4p1I8zV)P^sZ@AnfR(9l!@C7*&Yvp#gVoB*l4$UUkUvrK?$4VxRmM=3uGj#2d zLoE%scLNEJY#y|!x=5Sn^lzm)D7@xToOjRg)HgGvM90f92d5aRKu@8*46i zWMrSEIylx#nEBkm;AHd9=}m>zZhEtBAAIzwBSS8rtVY)C4srFPUZLbBr@BkFZK1no zG*zFlHPf+K0w#V@nkeNc`$28n?JUgOv(SHbow1N}#?zm#(z%^O;!EiL|0{J8aaE$320$8r0XL)Vbi<=e5pEzX3x$VTN0x1k;B z(>CJ2GkxrRDjRo>;iU3pjzt(Gs|L<`0gtUo63EBpMs9sNeQBtPA{n&Qo>E`tY;_e^ zz}^eD@II9_t-O;-=T7sxyAn4u6UX7#)PjDRsSY3J+@y?g*!xj&3k|GW?)vrm)uvI; zY8w9l{8rYMmhfLl%nzF~0I)=(Cz5*h;D1W#2~;J6ZWt};T;GcIr|_Mn)~TsHEu-7S z8)RVli6A|5{6mm1JJmaXiaK=Hww6|RR`=3fz_%L}@W`$AMo$^_T;y|2>IUWI<2Q$I zB-9aY{D|a{)ZqM!p1k{JzFD}}eEas2dEQ88B$akK>GJ(Z>0b5mqs2`hfiJA=<2P5g zOZH}jF6Kab;YU;3*ERFSqWQyXM=D6C7(G;upy!eN>n^24*YSUgFFav2yI)Nu*V$9c ziJT0DA5TwO+4x1`={yPIm~WeSwV4ceep-?Wka7Cp{ur)dtzI~oXXRBtDeYQGe5XXW zRf0G_hDTOArS@Uz?N5}g_C346pBAF{hp$a-Yi%{WHu0HN+1D-3I#)@5^G7G|Hvoj~ zEsSx`9eE#>eDC3Z8r}FN=ITowzIDPB%kr`FoPq7unm#0JGiwmuOQ_sSG-$~gEs&wQ zfDZ>F@~3c=PNPQnEe^k+{j=@Y7PnJNFomKYx7rq$NuG-Gp7}7zq z5h*I+ne#2+;3yewHtIz zHpVDXaU=^SK<&A(Ta4~F9csKbo_)5~;OCt5tzQ<{u8ZQit=2$R7|{U|7Tmjf9Q}G$ zUA6NEW*;JAJx?6&((d}c~u6eCbhu5EE@iw0>(B4JT97v&o`MnS4%~jNV zokf~oC1PbzHpl#4`2PS3x#0_DI?ar6#J395sAVhAcO+HcQc~`HO=;oFUlsU%>0^@C zE2!};p>_S-xXCEp#(4nx;-k0GEVQ}g@@-{;JBW8p34D}s*A3ifr=T@~;Eg_Q3gYre zJnOrAhsQ`Ih!po&=S+iakx z-pM3qtyhiXTXktCbHaD7$-sV(R7_a9TT=w|(@%`ukTI@pnhF*Yr8HFYRXgR1+uJ;Ba=_vEbxm?_(#X z1$BNQwz1OVhT=Hx8b!lOikON&_H*CrIIch9exax8J`~5DG-v_HWsP#CEy{o1?eb#B)hAMRcoe=0eQGfx9CloRgm4g?&q>_>21!%bQFWA7qpF zb3!vDQv=4=9rKFlXj)5Y zaQ^_KqTNQPe9OG9-}bUAnx^MPGq|5x(sg?n?&6K?&j?9}FtZ*CzB&=mk80GPLXOQX z-|V)L+@TD(luZPRae%CO+tY)}kzB8Y^t+eTE}q)v6^=zdTHQD9joUkMK!9RN# z6|vweJE?6L*~S_;_dH@uD_euqj(%+P#az7AV@(p(VP&|D3v8W`=XNo%y$(4TJmQy2 zw6)YPBa2Ow`#$(CC5k}Nhz?IG4`bJZ#(GnV?iv(^uGf%B4c4C=hifU6Wn^zdpXo{A zeFkfrr7s+ED&-r@Vdkj%S4VT9O=op+ZK@=e`i!yeN8CSq=)m+j{P?W9Z43KC(q^={ zc`uO%@F%@u@GY6~sYO5l00F)@Mu(HJ3*YUv^Hf=#IZ0H8?ITgU)pk4^`p80722rg#nOjORRx5OWoL zJfCe7!FddJcT-_x`#Ws&w+`H6C$4%{_l5Kb?rz!(OXauKEzj;@)B*DDP5~>sf*U7{ za(xeM9Y)6UNAT_6lc-JopC`(U6djBYNfeBO>w(j~Q?~Ji#r?gepQ*f&+uOKe(VgdL z(^uF70G+@JY{9KK`GrRc``aX<}>Wac-@(oi54p z*k_P&#t*MgaaXh(`E{#_BTKcog<=vklCTmgoZw*cbB?1Y`3hQ|rLSp4tUrBgY~2jc zx+lp!26@k>De|!LHSRU|?yj`aac>$VY-A`{tYnUbbCdZKQE9ijPlzt=Ba%k821Dh@ zAoH1+j-X@P(yZwA8lB3;aNlLRg56pZX&NkwfafewG2nFDuz}ol9M*`wiDHipePhWf9jgG2PX&hW zr>$e@dV^eE7}>4bNac2kd$5V+ExFE+-b~WNbj(OZZ2;low zn_g{2DzOR3jv&W4Dtiw~t*iV|fv*0`bu($~NAA*GGR!g5o|(=@G63V6p7msxWQ=KR4Z(IIYjL%U_S#hA1Jn6b@%XOaP?4@} ztt5&w7+fbRPfj!6-=%GMJHsvFMT+v*Q-V2>_jxEpo>o0U`HA)8@t}9Ho27VK<4>}h z<57pqU7lQ#G@*=u_u6^Sx8qi1@iTZ~n!?t~1zZM>3y}W+C>;(6JAHX0HQVWM-URcm z*53Z<@B~3Tzbtmi?Z-GdHAeUCx}q~)>2XHOGeZ(OtH&yIRxC5v_W%z{pEM)Rbqz{A zUhj0$B292Yd5&`!^w^|z&*5EnhMGSK_<32IPrSM=OHC;Z(UaK!0C<7ebg1U=is;&< z#;d7H)~dr~VM@&B13xGo$mgbU?^N}j65j7fMz@aXp5?#i)MV#^L*pT_N0|36rmHRF zQeH>ps;?!yvZ~(y08CXVHD=fEO|6@GlPd23s0?s@3BUv1ku{r*KT3`}ZAw(M&yOMio%h>n&aameli?vVf`IdWqCQT$RBAJ+_)cO19#GGRt2<=i9WS%SxArQ-WBv@Ey zVcKQqoDsmm&pi!Y(DnP-?P7x3)g-gG0R*if46W1*cRr@Fyg{kME}0yV`F6IuK4y1~ zP-6!<_xL&eM*p!kpydU@p+-MGl_Lq06X!lO)+Jm%*agINcdUVMc&rY7c)M>Ko z(U~HL?XkyjPD!1&Ml;9+AJ>Cg@2a~&3tTp-HOzp0nr5}~{%_*Q3;|s9$j>}g8~*?j zY8LiBb(~U72#~C?I+S(6Jn_ae)48CizJ*)KB!d0nyN_3$UJwv@hGt?vhjBUN_9Cm^ z=?!gQ%p~&Ka3k^yZzPt+)dP@u=cQe=*L7`LNhX5fVtns$aDletfDZhQhq295(X<)$ zU2U$l3yXcfd^NL`Tply>^dqnoi8kW!-m7hFzvzv7^6eyABy0iWXdsTAYfn|vt?l%f zY+5L7Eh8w5v0Vjs&sF(}9m%ZQofAvByx6zX*}P+RQf6scPhP4qpRW|#xwN}$$)UPy zj!5#JRCO<&yknkw)8)7pF0TAJZ4%qxYY28W$Pzge{Gk2O^zZ9jt0MNw9k;Y5O*N+TTjWyq%Oq)&&nyQ*DxIf*b$vEjWRq66n`vfc zSc>_W0|bRV`U60E96yP!8&R}YSDM`ng%0atvd!17bLm|CZ43|P%O>A7FeGUVYEPq{ zKPvPsZ^DvX%&l=Hy}XJ%&C*2d*dzEsBPWy3HOctDM6|TkEun@R>DVJmLd0D%JF@}u zlauoMQEs7Uxy|Xb>HZ(Syjd1Gh16k0^1^3TJc34g@zCP}ooAyin6pc7slTS8(YWpN{G=J#`BY7Mjy@9~W@sCkdd_jM2brqx^Xj^k6%Av%2wqTE&8T~4s z#CyiNvVz^FTa~xU#UPJhBc9dOeQa|19HND~VYz&!kBo)ozO^09>kyGuQI&=RAFrh` zx5C?e#=-s^)ShzNM<c?qttw54sPn5%{_t64prcn+scA!v^Z%e9MVH z;9UUr98qK%kip@dwrg>JBzk--e&Yn;x1bbGtp=|QO6~x!pGe;o#V+5&H z9Ag;cnx^`4+OFnRXy(aWw^AqzScW_KEyD=jNY$4F1C7Jb`qLI!WhcwV?2W;?5Pc|^ zDjkuAZ!itSjFlf>PkMoF!b{ua>`hLIotEJ$R{6;~-`g^H^n$cVi#p zP{%jhn|2*@>(exnx0ZfymuSf+wMnE}9&b!hF-XRD5EmOj`ctjsTY}qu_Hx+mMWkM4 zRN|SoE>)eoA5X1X zM%^0uYn`Jf-jld&$)k;uJ=porQJnEfG7^4PV9}4L6!nxwipS~AK(1SN%y35UOwd$B zjgOqaFfp;(bKAXFoc~#JlP!2l!dsYsm@gu?a=_J>hMeNNnC6a9^ z_c<8JIT$$g2Q}ysfU*4Fd4cAb;3Mu|mv7zn^{+2OsN$pWZ-o3}gZm`f+sx4wj%z8* zQp28k+Cj+lH8fuhHEk-|CDZ(0u3O0t)@7Ki@kx#e!w&w(9@U}ZKZcqQjO4YF`p0zE z&KyY*F*!XjSx!jrim!X{mJjV1ZY*_;V#%%YQ4-+E9#5*8pe$Oii?p&lyX`kuSKREE zHs%xbR#U(k>OtvJU3kO9npLe&>E}KtcG7|Y365hDT#bEqu(X@{fct-N#8_hrMws0}FVRE?7TnuNgu z4xgu=G2Tbq@{z{&IN*DGk4lfj{xZJsrNq)$zn1qf0@eD$Ub#*WEtp(?-X_hbXosQ9DHT@vNCt1Yh2% zMBg&`_#lm-2eKbg_6WZP_m)mfrFqEJX(+lbq!6K?jdYyX0LYJEVC2$9Wdk z%AOf|9@ste-mxq-J8d&dNe!o%(9C@0ELU*ONcH~!3f8spu8V!9-f8pwqfJ|tb+n1& zGZbuPcCh8SrhE+$Ml;d?f^hQ?uas02{2_qM4xC^3=WJu)j$*vDsQ8EeLd zOL7|ke6kF8!Om;X{vhZg$5XYGYBs(^ljOq_vw2&O-WlL=oa5S)+;Kke{hfRRZ>jt= z(N|8n`yyN0iCPJ;?K82-WZH3#eZHM5yF|Lubi0o#C~v&NeB^`yGN>o+_vzJrJ61>R z=ixg&55t;$oO4Mnt<|bZCWU|mZOC#vXY=R1b{B4R#ceL)+Q#j!HxSnHnIuedNyn#L z9=NVaUizI8*oVTF@yBVKc$!N%TbSJLc>S^42caUnYfDM>OBmPWzPF9I5)ryAXOF|s zd)FZkhGfy28UcwQS-REd`*S`m*op~GbIPv`AQHx8w( zDmm&`_#0Tak~Vd}SCZr(Az@5o2aFNQKetK&%H@k$b^iba z>$1$yg;YLO)vpa4s!vx#k%QRwu8T^!vDc2+mg7sfQ-zEY!H=q*!`S{64c4i0w@^)a zBD`?t%eow}^jTNt48y@fsg8;gpbMRofzULd2vnt1M zRaQf_q(%MN`l%l;ZbAI3qScLwG2C1@hAeG`)>4~$0-cLvI0m06*J8GlqAiTS+7>ff z>k&pau$g?j*gA8!jD0bV^{c2futy!liEn?Ww$<`x`EG3vPtEESdW?^1s4Qfdc~-Er z-g*#^IP&CW=Np}H0r#rjBb!>$t-QO<-)D)G;zeD^Gk^=I>F>=N^a*(qX*%4RC=yx6 z43Y0+Nj1V&Zqy4IEzA=XG=tm(~=4U0=5>6SL1XaXqw>%w-+Ajo5m zFsG(H2R`*aso}e*;6*JXO^{541z0b$hN{>1H`Cr27mq0+L8nl|2T`bNwo9KF%Fp zeY>G)V2qui3vOb1ZsTeBPajIp*8FQCUA4TC$)^37e5)LrLwXVj$Nlnu8p&@H>JNC& zB-X18WgNFzQ?cL>az{hRpbm#s_>nZ0@W*kc-pOvoq6RP<4mlq-eo#FRTE@807sV4p zd8galT`7%&&vZ~bHbFUFDSF}xD6xxv85hG<0}J~S=fe>!*AhlqWh6wI4H4_}4&8blIIZ0uU7F$k)X}BQ!ysdD zpDBq)URS9mwJy@m_U=Y$A(=egvSa6sSNqI*fmrum1iX)2^KAZWS*_T@A&_iPG5kGq z@5KOiQYF>xlKCb(wYY>x1nf&NBchSWKVM&Jk427c9?9mBF0H{;RWJM2bJz@zU&gX@ zZAVbkS8tbb9PJs3JBi^Tm9TjO7{L10_M55PY1&_zHRE4C&;T(IyM}XsN#JwHB9|#L z@-y|VF8g1H<&7FR8JSJM+a#^mZa_On^A$_PI{nm8!{wE2^$2v`$NGUn@Au++%vGiQrzHV z7Qx{5yEUcFoveyx)4;fY-FYZ?B96{C4tP2IDy&wP6Y47@l1(zcSymH|F_d6scXsKT zT7dh17u;#Ob=9?&p0N2cJW@&X?VkfJglud%AZDg*QsVyrPL4~hH7%AV04#vVBp%>& zCme!%`qi(o=rG*a+)E|pt0-nGxc%lloG~Y!rxjk|^qp4z;!8`BtxB7v2S(57F-^*qxB!y%U$Ag@nzf=DJ>Zv>t7Tc*V7HICRPzPxW><)gu-Fwyr z)b=6nE!WJJ&77HAE3~&mj2?Ze9S2R);+&XpU<*Z!eR65)&dW!gI@>Kl=RzGQtfm3pIsg zcaQ=%Np4ls9)zB!^7_w;yS1t@lvoXs%-2<&J>yo^hVO+!6} z{;OOc#64S0O+{>c%|hx-nI1`RagX>82=@ac`Bhr`kDH=6roOtr)+AQEw@Yke2;V;- z-~c@;ggT|ZmAS6&FD@Hq3acImVf6iLU4ln%7_;*swcq9xm2&bnI`Pg8V`>_;wd~VL z6^lmJ@|?*h$}XF?0Ce^gB$&L+KZzP7`i_MRlG?>$E{l0n2^ipGhCKa0F4g&2@y5gZ z2jVuhX(iIl_B*L!&d^JhVmZcgNg2<*ex-QpQN14oVCWD*7x#9 zxf^PR&#CsO!m*iQSvW%=$x-tt@5iM<15Gr(Tz+FZk~XO1^{s``ZFG6kOV*zKW@PP1L#y0>HVWbhcCPt^6S=-HI1+H)AfZXD;oH9$>q zsLg+MB$G_iO#HNr*kklR(xG$aV`wZ7uV2ce@{7n>y7$jY(zUbQX15!ac?cBsVtRmj zU{uIG39Pip&99kpHq{ZGs-*8Z{{ScQsM*7a)GUnM7Z~8w)`w|0ZPI4i&9!A^&I1O=)-IGlM628UEFjd3^7XAACO5Y zP*|O+ImQn^T6DKQbV$mber$8i4-!u5tTVR+Ip7+7q_M;s?+(0$=}_zmSc+Sj5qGbf zmR_nk9?4I@h;y!WdiXvx~6p#K00NcR5#4&vZr9@JcE zVrcitxMg}Nr!BwP)cw#pC>&*JCIc9=INHpN$C2$)PYVQA8&sY-rbh`cwEa#6T8=H_ z<}LE`k4`GJ4xwotBFv0TW9AGx{xx1}o_=5#=Ewka`ctl?5)Hd{vhYalRU~HnyO@K3 z5BM6JCLFznP39>WW?x(`;Ap91gi4&Z9kOVnL27->@@`Ch-1-i*k0O#idQvRDZ}AWl zj2;2)Ox~(gF4wdGeWWhHu>O#xo^w((ieveZH*9CM z0CQSapQvk|HM-QVVVh60wF27S115a_<;c(EKN{)t&$nzEiWz*-yNnWWMNc2_kK*hq zl0@}54-xznlf}CIwbk~aKA~p~(Ybqh)8xS)bx0$RYS+|$5@<5nTzOh;wYt3hvAK`wJ<7myr z^L>Wl4&Svd2hcZcb6#)bZ-q8K3h-U!4EVHa(fjGb&Pad4omDYu)bA(m8 z(ywHqy(mV;=Ke369jhYN>PDL^@-S?YN%@KO&1@)$(H->-$K_U4 zS8ta;Fc>g5Ki12Q*{{2z^td`2dLqRrops*<=xNBKfEfKIM{TcGphaF-!aE} zp>u3r7h)P{mXZl{Q|EYfe!19z=e^43-( zcYFXpt#?Mr9Pe^Fa=*m8Ti&`~hE`@@7g%!43lp_ROaol>aWv{c;|sU|er);?{uR}H zCOf=iXA3(lk{z*bJ^2{Ps$pv$X#aY)}e82 ze2F9$cTg#Y*}3K>>$f2AdV1FPhrCO9;cpn*X!o$2pS8eEsEBT7lbk6$VE%kn&0^P3 z(eE#oec(mb*;S(%mcOMejVeuIk3mSv7v89;9{9TOe8 z3bB7AQeC@Pwczs?X^um`2mS82C!8L5s`1^ktZfV%TVYMI9D8Rp0bc3sA&pzhlHPfb z3Ui4V4!u44de&cwv|CRT>K+@lh80WO%d-w;apbC=#{-UglfbQ^E%NDXBenC4au<$QuY1-kTaA-FcUR9*=!+mb!E+TSzdJ*YX^luMY z=#ogb6C^Th$}FfieUC7qr_XyATt))ZL z40#9J0E*;1H*s~OYFK|V>6DK+{o=g#&wr=2c6zUg>~$fwSZ*YTf&0QsCOdj@RK#Rx z+CH5TlHS|O^KEWff!(-$?wh`u_BE-0Ezn@nf1}FZC~JU3U<1MT`qwpLWVM=gvbdKm zDR5cB0y2GTrP4knGzkjdTir`+r1`D0%?-yKbRL{$j)Eb%o@-^dnoZXVxfqD;5_)Yv z<60VO+({g3J-W+k$A6IOBpL0y-{^BzEj5iaSpBL?XyHaX)&%*O9-OW)e;QpXWz=t@ zSgx8f$1NH*#v`W#wF5Tc@m$ssf5g5>N^IKEhVvr>*d72L^>vP&;_V$*`&LV9sMH^` zu=3UU=ri}enax3}_*&K|7kpBAat*Ix z%{w41c$dR}*_XC#(#}Am@_Y1COOw*0uR`X;)|t&P#20_aY9#Sx!geTh});Nvu7k#+cU%&f8oA z<+6^AxNZo{UI_H6@$>aZn8sUHECWOE@(RKTCq@6aj~ph9`vdIb4pPjasqRVY|Dv zTg!{3mOu6BhTPn6tBjNNHD6Ehys2{0PQPo8;e<;mkSI+502gk)wb^KQQLV6PwGXu_ zVHP+-vnDfu3jE*ay*pSpH7)Muws?{-X19?*0Fk)o{hquI+*KbGY8U!_mBO>D!z4gN z3hZt9=Qzh0_p8xsI(#;)(m^C_IVkJ<*Z%;3=OkA-;>(D20dH?>b2YqzP*0ec`#O?N zc6BGV1}GS?A; zLd_P$&u8RWKsHOzA0`+wY`^_BVI$nMo63GJ+qQA&ol>9D5lvX`#cDxVrecK zS1i0_f;;i}R2pTrsjJH(>E{zF=JMFXng0I3x8Ypwc`c zb#19F%S#IFkIQFxpUedFw~X~Zwb$ypi$MgCyGJ6Tv!X>Ak)4M_jN+P_ymxwYY`9x? zkPM~J8`Zr+V;@7Fl)~pBsoF;j*z+!Cnle;vvwg1E$z99`LFv}A?ezUh<=uoK;lbgd zQ5eAB6T$v<=tE0Zw3V+lPqoIl*=-fN$gzRW?gn%3oYq#Scc$G~t-Omg+gO6Y$h%vp zBzper)cWLcjE)=TCwSmqQsV~t!cI*Xw1(bg{760 z=Zxcl^f~^PJU`)$Hg=L|?c=zZZrIG`HHoEn5LHpD;Z7=cnOR z1-)Wtu<(`7*={Z7x%m)EB-mFclZ)NNcwpgqu{?<1?W|$dR$1&Uq$0M)*09vhG z_(%Q{Z5!$}Nfu8K3qarkwq+e(g0A!Bc)`7O*wTlH*R}%tj$YB zUk=^rtK{58wqKikemuMB#pXzc9oEX3KSgm$>;E+lyZ>!4Lj`n zm+X)7Wy3545XaLzbf({0J5L%(c{Ff<3Cuuk13sN{eS1__-YJIDQxT-Pl!|29P)oT9 z!8{S14F3T7snco@-Cp^o&hl?86P1*FgVzU)d*+3{q+6+jdY1Z?`@Dru=4J{jXOi1%#k35n_Pv>1$w12iV*%sf+j!vnukL8a407~X> z^m}V_B=D@0UiFnqkCfwpMhD~$1sWC9=Pz`k{$e(zac6IHClN;vog}3H00?aG1#(_9 z(k9VDycY{4xRpe$F!M$^&JYoTc_5Sd*Pv@R_YiN6OGv)Z$-CtFiYKrfjOX#J)V*6R zHOy9WNpRVYJi=sX%WznzA2Iggt6=JRkDIJ%kX>q8OkP}T89}-x0mnQ74?OnC>MQcc z<0huskBn~?ZP#~E-%48UWHHHd+naG^B!EdLjE*_4*H4S^+-RD0-}a<;dR#36?DG%F zB7NKh9XbJmMl;E;$gdpg_Ko9f=C$*h&2Ju9W0RIDT%WE8J@9{>Z-v#f8jnNGAn@j; zKgKOJboO~QPqf>8o&u$d%7hhBjGS|mjOPZad`q{OYjQ2+#k)%+re84-7{NKqxqi-ttC@dpTll+jk;|!6csV&p(A>c+Mt$ZDDBHS7M@+=rP|v*Qu_( z+0M+19asA~nQazCM;j$_13ULPILIA%9csR-87#`It+?d#mLA5Ib&>8_S8}?X4X3B! z>rqc9*smG6Qm47(AAHqpM&x$3`xAETXE{4_iqo~zKGUYNNi1{&~4m);rpZMMZ-e8OulE!<{rhpeeqMap(N8NF|%936m8E@ z_3fIs_IVoBS`DLVJF>izI)hatM@dhZvS&W{IQOL|aNA>hRI-Cn@Pt~Gt(w?8a(Oo@ zB`zI^$aTrjwPfk8N-~u5H(&+md-L_JF9%y+c!uKRPquQ2aE-Zw{D=S~XYu2&TBGD! z>9*l!l4iR5rV^V#8R~Q2&^t3#RWPdWLGv8tdgI=%L47csD@b9DmuO{f*yw9M z=sCC>nU!G!4d}m0ciHwwyLfDM0fG8a%W%+i(aj6CE)`?P-dvpL)YO)92AAb;F}sDv z4MXJ=Oh0}B$KD*&))RRP{;gSCxIC>)y9l^W)RU_g$iewP5!R~9r7zi}xcf%e zRtm6%+(OX$%m-1s9eL;~ z(UTVV$&O9|3V)SAZhW}e6_s1AY4$}UmA45QhbzZD>FHvY=90%Dw{JB0dw@6{zZ#9e zSQq8{+;#cBwA;J3`zT^L4~G4FRN~l6Z?s9UsmKSo#X~DW5(m!c_H^Wy#syHgylLjz zs#}Z&#%g$7eDxcdqvtsWn*!o)I?2Id+xp^*_7_rUty0CeuWy~y)G2PB~;GSRJt1N%N z+w!Y%$UXa2)M%X6&#+~Wb_pNEJJc*hw<@D^NTauZ zttO;rT|Q>D+HMsOlqLIxvA}P}u|6I6vsUpXyx-dz7xp~Xt>uyC?-Cy6PfTYW&(zaH zM?rmSE!DcllgSHi-MI#Hj@ zRMhmCbz29H;x%Ywh^&Z5QQTs@%i_j?W8wI8ty&!(8_gEk%3de&4B#jL^N#-jUrx2^ z&*ur$gYy3X5cM_XU$kD0arPC|Ek)Bp!^^pWGDhCHY<~`Yz0DG}hPOP2Q@gRf*Qb+B zwfhabIcVeGyK3i(isDZtPb;;Ka!2{^Rc)u(yO-`LJ9hs70PH>SoK&((q83s+XP)(n z>}ViUC*5b`zr95ya!)jixGu%o4|0F{;*l53lV)(a$v8gZfZju#v1K?=bJD0fiv#Xl zN%vQR2NXwdzAxg&dU~JhN>!mv%lC7FbJTq)%;dOb<8BYH=|qQey!})wFlP4eT*r-C zXl7jIv~@$Xl43yV8lL+rLp(yGR+ zue;@wBd9-K)t{(tc0sjQ2O|Tgy>_FOnl_W07HfqCmNo#My{n_}Wwdu*Ah+7>xkmJL zAU5uLdY@|LttIl6Luboz#ygQ+U&CvawDCQZ&%#E;sR~O*dl8P54SF7@soq>qt!VDE zT*Ez!5}6ouJvry7#dO#D_Mtpc&3Pbgt+VFp--at8wTSLDNgK?#Nu*bm%^xL4tp#pb)B`=ol_kQ3g|nPtLY$xL`cwc)3tO_ntg`;%bYRNM*FXJZ z>s78^7TX~6H%Y-b>FN4YZNxC4{q@G~RPHUa8Fe-9*>}gA4qR+DYAFtZ#=w2zd%tDeGvz+}iitUrf z_Zoe~YbCqyw;L6ebAU6!VV}&`n|v(PY;WwE>JLF~0OljXN*4mT;}a%c-4hoZ%2b$adO$r|K_ zSO*K=1Rj4X>9lVSX?`cY@_)1>wV83TBp)NW>~oEv`qvX?WqY{R_D{0SCkb#rcf2P~UP2szShVDg8ym^Y-(>;hI zkL&GI*j?Mq2)Xj%XuuJ&ZrdsD2^|eqbdFn}_?OLUws!*$9mMRa52y{hZ|BFaYKHPz zED}Y!+9WN?lk#Jn5Jy@7-;2$*5t+7@g}142Tg_g|NZ|Iak4x27L@gv4M(Mw*<2mR2 zYtJL`Jo-kP`-@g)W0u{}WaN@R$gYP<)|*wf9)4quxl&sj{fHmr&>m*wHyUzkGBZT; zDzW|B92NHjR*bHp)nbloG~oG+{{S*)s4MqPb5_>UCx|1O!dV$D*-OI7mFvhPoa4}n z>-5W;JKK*gJL`DvBRFKZV-86i;IP^;>T#M0WxGu|Z%5g_*>7(otChH7Q3pKj(Jo%izj(I@ z9G2ViJYxs0GHH`r$)=*5Q2X6JX>KF=%|3n5**&!A!b zYg+qMlgWf$eV+ON2`6aUqa8YCg0y9i4c;w@l5eysw&Id~oQalBya0H{YoFJ3t2FaG z%Q?Q)GxULZ1J?xPap{3o+r=7fy~;E;_bUvX7{=(;PpXnXAlw?()BYjGWBV_cbu>yh zd2+;{{dW!r;hJchYGPY>Ywg$O8wo7pkwW3`?iF4!$@{T(;qoxWN+UAjsQ3xk0!d03f#4yg$!+XrQH!97V^i* zILIu(gP-uM9aif5PthldueA&1x+R(~G^(K>bpYUu{*|SpYqwGOdfGdIpcb}LuC0$W zpH2rnc0ADhg>v?@cN1AOHn7hH#4is206maKF^ryh!RH*;MW$-k`hJ=%ZzGO5B$WM; zZ5bKacI2F?;~B1JP1X|YU2B_-B1?!-PwvsTC>^?k`B#0RYL@pAO1QUKSOXIIAL@n% zcq6F(l_BV8XqSyNK1?!PNjP1;Y>D?s>_{2>s*6E=49zvP(a9pNNeUaxlcss(@yAM{ zw#{{WC)vz_qfQ{(W0<80w0}`e!u6fQnI?d(IJi&Ss956 zsXUlL-yj}It*t;=UE9az#6wBINS)AiAKk(IJ*g(rth~QEIAge$GDc-$%nmwp$vlb# z?q%4)XQ|&v(fP66FU(A1=LTd?&x+f5X~aT|u6WQ9PJ zdhILp$>>k5I^$gXHMEyE4AZPCTVWfEe|P5WJ^J>m4gH~EZG9)18%Zl|gKWk{Uz?~0 zf=~Nhsx%{{TUc!#>rw28xeu6HQ|a z&5RL}#RfCTJ$qCi*f837f*97*dSf!m(&qyoFCLs@pHW+}$1=VK)kSOt#_k8bILD!z zmCjqmJ{E^iiC76fTov3Mkysu;0P&vHf5MX+O%;C8XZCqnoU%luAQ?Wq^c8CQ3AF(v zZRR(Y#G(6~gOGm?nW)wYZS9t3nURPgfPXUs+ar_jO3bavgq~nvma;68bdz9EfAQ@8 zHP7nSSD5mAxtKwm zzHDJe;;p=oW1cbIjcght7TZg>xSiyDc{hQ=wd2J53Fyo3>UZ%k9KG zWA9^@J^A&mTdxbO^6ysrJ2IWDua=Y^#lD~jX zb2>$ptUB%W(%fm1G>PTQ<;oeD4#a`RJ*k@4hoiBy`$eVX_APai#ux!|nK;4E1A*GK zwIORRkdjES&2urztUtTl*}w#o&;I~e`cq`k+GUS*!p%OzmD}Y;zKRIz-;>&wqtj!< ze`vXyZw~4cUp3=gOQuN}A~4KO!n=TBj(Pk@HTeGC8NAl+H4m`IHQ=-_JdPP#$%q_p zI6ri7PC8fX*X=*x-?Q0kSCH!-T#IkEbx2O>6;SY05?c${a@fUwMR?CsT~oxj7gpxp zHMn-zV~K6mkduNVUKiy97vd2Qzrx`F^18?vj{vHV4I zzB5(0*X1TpDol(kbDRuu`u>&I%(@)i3U?CupTV`HA(XEij=80@y8Aukk~}coe7XJT zECKcRsYRMDppeMSt-%eCm~q~twSq6UKbXyxjj@sU$Q)H}h3Hp?zK0!u{Z(%AShVSUsOMbA zk)6MIj=c00S}VyV8Fpp~(UjzUJ*em!+~4pvzPds*H>)dI$Wg$FwzMn{3_G4U$9j{; z`bxF*I)oRH-dpMb%N|#3h%>;)`RQ2tcA+#^@!}sb@OG)>F+67;-u~64;#>O$@b;H) z9CJ17D16pN!gW8H>(ZyLpk?1%`4a9kZiT*J$_Q@!Vxf}W-e?JlnYN$0>A^m=V#98w zrbr}KYm{yAH3iDDBQDmBk+2n1oKo@yabv{)05;{{j07ix+wiF1kzg(J zD*`@XKZO4PjXv5jdvp8Fta&8krCNJcy-5>%J7K^BJh11dttX*Z?nQRHZPj|26FhO6 zq96|2vA4fW;MM7M0Jr-lUKK#jIsw!C{VJPWqRd-+aKvFgZhfkHgjyqcR^7Kot-Bp@ z_p#d*8M~TXZ{N3*ll7~S6@Y^za(}GA1B|zReKA(G4Nh%N^?bI!WL(1oVoWM2>yOf_ExSpTX#{0X08dX-R;{h#RCb$dusk!bZ>Qtd zq^p*e>24-Xs$FxDk&rQ3658U;Uv69Z)pIOXmSuwOI2&0<)~o*jYsqgKH<(qMh6?!H zJ;eZ9OFg7Aw$h_Nho{z}C1qw`x^sX)sN=h9gxt>Fr1$*lDKA-@ zhcWiJDu=JPHE&gS+b z0-=_9BGeW$42>HC#!|y-5!jBul}=;cig?3kZ#>ey#7Aplws9;mw2K~3-fXja^HM2} zNt!6wWpR*yhtizc0CBs5dUULh8CYrq!q@4cu(#E&6nS!xIXNBAPAd6Fv9lGde=*yR z=Z>bGJ-*+XFxymmaw=9!UxCZ#MfTK(B%km4{;9G`xbXG+%Wd|9Qf z<&D&L)^`~y>IfWXf(QpS7mWNTZ{ptzU1@g!wxYDv*C+h?JLRSv%Isnym*-cUY)8z7&}{_ zZ>@D74E_#XYptqV>egObM*)U8n1)r8BjyJuI9~qsHhn_&JmsxKzr5YJFG1R&*ENN- z@KxofmWu_!-86)q;~cIC=K%VCHPmXq3iV$P*y@tsN904Ljoa~*xEv3Y*Et6rxfRFw zvdG;0Jk)NCo?AvhjgQN_Z!Lk}jw@gOjn7`wq>|HEv%Z=MJd+WP#yb&>gnFM}YP(}C>RCv#LK!S> zH*mjsF~{blAI746K3j`5L35Pfjxt+!^2aBoUD0hWY&8=cU`V%7G%{r5DaXpg+#Wr} z1r@FuM=~Xytk`zSrgv@bd8b;elc^BItYjZ5?A&wH10C~Kt_;ks+<>h!;`#t8E&r9!yFJ zw2*wNndM2x%t-Xjb=uXot#hE>-N$#Q-AN?K7CE02<+FzL3&+=*@sAF8TkT&FH3-(@ zb@cO+@56h)tc(>PyOWH zYVHji;1>sW?4#HSw9O*c_~?NK!f#^#1@nRk;%C$f`j*OB;O4wXn)R!`i7^J&d+di0&e|k32&n zks@)}{{W3oXMO#j09fs|bqd)ax93$5>RKKkx{Gvj3wgd%<;l_g$@Tnd{*U4)?xJ`a zM3E!fN=i6iQl$R?Ls*uwe`xMjiFYX^IKgcD{{Wt9-L8*!GQpW`Bm+4)+mYKJ%8sDo zdI~MA-Lkc%(6Gvz^jp4$!h^HvO^ghfyK0vfHme+SNRY<6nH6^<9QFEp^{U*RO~}o))FF3mnLsZ7W<0;3?^Ag; z_tx^a+XU>2N^c+QJ8|^KdZT4?rRo;mbh0g`qaPS_%yW-G-nsP{1HC)Qv9Y#}J9uW( z3i4xj4+|1=k=%3d-hy>D{5z{^S{U06?Zvw1_i?d4OQ`1ykC)ejT_bq?Z@yhZ-Y+va zW>8lLK7)_SxoZ(|75eRvGN}Z)`IqnquhX2>olYC2)LLbkZ(=0#8koWi_Fw2Kx)gR- zNoPKq*A}yRAT9}rhITpr?sNF!u$As4mu$QImF1-|=3GkJjr$gFTV<0Ck$x`vNubr0`+$nKXccJi(GkLOg=PmfG1H`v+ZQSz&&n2Yrz zsh~GDbl(wbcM(F9%@fBV1gkJRfII?m$I`kzJ{U;*N7+n_&z~qtcARy|^!isL4~OG; zB=Tg3PiYUFLLH^@bHbeCJv&gE14}$@C)*ljY+;E zA}Co&Hq%715Jz*I@z_)vmbDg`Rc-WJ3+0dy-ee(@chnF@J*%71HT!E{F)uDIC0*r| zNQzizpbT(MD|brpo!5zM+U^qs#JdR8vPUYff0uXVL_}h1x|OBl{Ps~=aCbzLvJ4(L zZrJy$ei(yI*Q`Fq)^|IXB??|BGJtsbvB|4<{t~l}?AyzICSw5H?}TnvJnR@Gemy`G z+i7&WeNSof%u}uwFm@O0e(B?WjK*=j@IpYBRKf<&j)TFex9%L&dn>@iI zjl>Rm1sUU|K3zqY7V_x~)I0Se1uG3QR z{{Z&Gt20|ou&(biKQm|@hd9aa#d5OfKiT@F^4rHGDIEDo{D6@lAQD#}dy_z;V^Ze! z;#)Z6Qys6IiyxTrZsVy6G5{W?lI3r&7cUN%C7UQQ?JSZIJC1s1)Y52LJ;l|_8@tPi z74ev)w`j(3gO1xzw>7I5hMLOQNA``x?%5e{-LKFwG!K~+EHubg+Fifs(r0t2mv>L^ z6WIGypKFIpVHV%s%tHk8Ic)MW0N{1@s{+kl6pr1k)NMX%V2#7nb~QrV!PdG>wak)S zTdK6X-a{Yn2*CMsoSFvTaTwa`1sdWwyp$&`=8j1I?@x2ZO?#wT9X<%-b^AWn*pdyx zPyruE(?e>~gj9(bbtHWKK2kX2p|0Y?Q-*a}w@}*K*|NwL2kQjkt;=3cGg&IoJk&8qK{C-dt{uW{+cVtq^6;^Q)6v2_a^V zCT7SVJL4zUJk@K)lHTGp7O*60+qaodKK(zPM6_i@#A)NUn(`Q9ibX^(6D%o(bIHNZ zbDvtPsOwCcb6yLZ?UZqSN9PUHaop45f-CqM zE2A`#GLf=Ep%(;`k~{SLD>F^CK3Dyvb$gWXmZ-t6{{XW5rg^RiRobq&Wn5vKBRm7& z75O*gO+U!j?h4!7+CkT-S%&~7|M z;>*t`NLjTjYk4muco+uzI`xpZO`s9qIXJ~~UNVPm)KTppFVFKg&N4`@r^7xhyzsw? zwQ01)lHdD!-c3I2GX3aeWh?;g$`8`H&mG9On%d15%B>z5amXQ#MRu!oIiAHqbtbB_ zHN$R^P$(dB3h)h7MO&1Sq*mUs;4o}t@yXASmbr|2u#y`s*|r@F}7UptGj$*p@I7*7yec$(rxL&0_=1CBr4&!u5$ z%CBp}?P)kH{{VH5wRK(+)h{f9tTJ1&!ZKo20h|HU4y2D$O5uLyEybsos>vd%G>Ufu zK4F|>@_O^@Q{KU-U)$QrJl5)yFh~HA3FPBDSEu7fp>)@`k~1(?Z|;q&`1Yz+w}Qs$ zmN;WCpO~MUcfLQv@v7XZY;9|LXzzU(%;yD&Qvm6t! z7C;F+cNJdV!e)nZ$sB5+Kh)kyGS9BCu_cD2=x=^*u4|`qZf} zney#WTdzKq73#-o6U%Mkh97X_@Tsj#a$xQ%!1UZkf6i)ox&Z5`S>?j+RmK!!twymr z%e!weu1-e;9E^`&rA*3Zy9&9&u+H9}olPaUljdb$y-qp-M1Ubc(2R*29eD3UMI36` z8<#j49GZN|B7m_b?C=Qnqypn`SvG~o)v9`xrH2>9YBsXBetJ;^JBZHaJu-WHP#<)G zcNOCskMUE4%Mn)GLlLx$^rZJAsU^g0+gSXh_s3yT?7$h_wD1Wy{3^tftcbDx^D1%( zJQ13XeX&kecXQ7N{Pd-M<$4HPVd_N`&p02w^B+_lDrU4 z6&P2kBDB zx68*rH#JDRp}Wee@WGd-6`$fi3h5p(wuT*M&d*R5u4RQTF@)#+O8+!H^8kI;*Py-f2fi{#61 zZ3NFA(Xux&?gV4gBDt@J{{RwXwD=Ob)}?dyhOvr4nE~A+20K^O@<7P#^sXP`zr!1^ z0$NW7hpaWdfw7Rur!>ULBzgVeLH&B3YtL`|U3q=rTQ3d9>GoKz%<+80JLjU2(`aHy z&#ggGxt*_gj_1X?&BgufvQ2Sx<+58PM`a$$I0M_>t3>TA;x#2(xg#AZbzLIs!}rZ^ zc?_1fF)Fc&Oe+lFujVmK7XZFL<)>2BJF`M)!v=h@-NN;*v%y{gj{8qtYgoD#x;?an zN~b&BK*ki~xvo2LkwXmi$*)P(J~mj}csozg^t~)?TVoyAoBddP07~=Dc{%s#LVW{G zk%#dr_rrRf%qK&FOME6IRziq<4iA3B_p6#7z2dI~cwKb}bxT;RZWx&0owd4IMEbpYZ5vy-yw~uF= zfyVB=I`M&@rE$JE)c*jpJPN8`Z1)#IB5ZaG^L;wd@`$JV#OEb;@mPNmH5u)6eLMF? z<`FB%v8t9O*J%uW2Ow2K>5(mp9~AB;e->OMjU=CCw}usW8(r07P&4j2R~YC}Z3N}c zNC)Nzw>4@QZ?6_fuWlr`zPOmpGnU?2k6wHB`ePIrm8Di?WNpQB^see=Rzwgqipsw; zNO8NlKAhKY@Yq8qh~o2v$gK(DGxFz;z3u$#k%1N``4w`q-46=o`aZ%#*J)|qX8V=kXP<-~0_l`~tkP-L+HjDh&ojYm+?pGLQv?7D<2 zH~f0LfzBI{dC#tMo-si>vys;PGi!OFN#yEsHw5`?{c+fK1M6H5!r1itPZY^Jt6W>g z?YAkkmM1u0eDR)oSEo+eU5t+;u}yIh%WP0HpYm&m@SEG}zY!#lY?d&rt#K5tib|*i zs+2qqa5LATs&PZy_wNAf+AguLU0T6!e`Bdy!UStPf*3AW0JC)Axf~qsuTHhqhL@+C zdx%+N{{WuH81IaZ++=5`O7XoCD11+@$Ni^!Czz!b3r1Dj9E0-VMlqb6k4ow9XOmBH zHI2;jou=K<=lNf!Bw*+B#c@8o)Ryus#jI?x{_ATd8E`)Jc@KiFwJSvP zBx$UfrQIBfoyQ$}bT#SPUx@BCNT5sRiSj`*I_-1m$FI4oh9LD~tJqRDda78rq7pWbox{u{3E)jWOEiwql zulS1G(RBO26kSIO$r{YeHX}%=s!6~c@m4Kl)Abu~GR}D+Q}UEX!N~rV4yhvDX?u5~ z%&ban8#o7yj)&_(9ZgGnxissEtaT<>r?%ltskTKUsK@#ItESVThT`31l1TT+50sHF z%P+sRdHuV|t2}aF$8jX_oxWiN^z2Wt?_E`f|X*AXHX1$WuNtF4Ex8*xee2gE$ zgd6H>Y8Lut-%^go(m3Odq>*I#S8m1jC)4q&T2F+>h;;Rq z>iRo5nZZdOB?|oGmK_JRYS?&I<3dK2bw#+iUofuhc_lNClRXKl)Cl6#ZKbwfE=iMf zGMqwRYjxZXaK}EqD;#K27LISU+uTUG+RdH$&m$xXzBMRpBZd}fVNlG(MoVricmX?l z`d3HcJs#HHND}JiCX!_+;#jcCc*Z^Y{*-kCnY7Yn((YPW?fm6tNw*1@>^LBx8O8zU z+}Ba2Pd2stud%F)3vNk_fj8r^?g8&zQ+Q%IG_T%ie`;4_7>*_52R*6tqez9Jh8B)NyDV5a2kXb>iUrDbb88W$p_!G|CFPmat_Q9u#^fr* z-b~H7oHhZ+x%$=|nwBlU*D#Pr!i?=-Z%UqRO>Fdbx{_OjQlJ7HZX|nSr7maG&yvOa zm?JQK?ll>vs9AQY^*C#clY%T6LOLVYF zJ-8%Gz*Yx1VNuv>@wKeWb!5=V9EIEn@)swA=}^sOZj!XYZf22=)IeJUB=u5pkJ62W zt2KhGs>T@^c8nZ07w|PTjEm*@KWGw4IU~#r!m)JCYT;$_q=}Ki=m#$2Mdj3AX^<3n-Z5!H_pw>?h z%^6m0t-rs};~DzYN#aOa=15*a4AC&&kNhL+)0)MX#hOBFPqbWIw&U{cW^DWPto;*R zwM*Oi5=ooRlx;C{Q*!eQ9@~8ebwGy`Wy0iVd zCRBel*t=t&x<(IEoN-OnykK2qXjS9+c7x|8!;h%0W?vRwS>L%^wu@@-Lbz?CxW+!c zDqFkMsKq7bch{O+))BKuX$wsw^EJFmvSS^2?^!5YP`!rR$-a^`0A=M;=-l-}J7cJ; zmfkpqJuzl)wp=#dz~Vi}-vExEg;VgRtM*jz_Tl$o;uA%Z*#$M~UyOwF`SGA=77amn;@1Sl4l4%tEd^cO-x-@bAZ( zoZ8HWPqkiM%-<_rT}Wn?k2yS^IVZ2KYodj&(k5FRo{227PR8ORBPtaHwmiK5026xg z&MS}BB3s+(*`(VNg4?sS=hP1M=>8mE?Tb6cmf*B@@q;18-zYO}-SjL+KZSXn_-SsK zwl^oqmHVzi+guC~KT6Nk?R6~@&2A)`6}7ly5irZ0r>+?1jQjdk5vxvY zO{dzV^2rh+V>n^Q@~O~!vugKBvVAJvP4`Q6AaMA9lY{T=+N#-2ABJyXn#S>NE+ZtB z*ia6~o62ExY-1JAs{QgPSS+&@}9@uk3n@bB0D~ApDr**T8`=1MI!l9H7NZhnRY30VK z(lmxYlsh(Ausfcap_9zV8(8)f`GcwE`Y*$O7I-IH^R&McNvLV}1bNoFm@;f#**i$c z2OJJR`rU>1#A_Wg*`$SUH7_pUTS~Ucz2SY^a?95Mo=!SexlPkx{n)_@LB}=WTI$&R zApN6PQl9#2T{~8R?x!a%S=gVDWA9~vBhb>b8bxo~(YO3X(_75_<5=xv=O{Oxq#9eJi%_Nxq6+8^!b?Hd7aJN^JYFA4o#M4PKs0{KPvB1FmfWW9q@wsvvq2r}U zAd!v={HQr6vHt)fki^`_jopfYnx3V3giHIJed4Dd?|o>BZ{7rC`M&TVd(!7Qrn;C(9vRV|O49l?FGy=KIau{{Tv~(yx?NQFjBCIs7@OV}=>b zhH2!5vAJ-YgZ}`9QrBX4D_$bXg?8gXO8m5-(|GYd69$U$a?Y6oPSEg@HM2@_m>d8{F6-aw9Os@ zm12Hup5DT`J3B@G&$N?l(kz2x$&JdrdY<3bi!TppejR&>wD@9KE+s8Ig}!Dduh4o9 zf{ll5NOVm$`@>G{YC}TDAwe13Pd{IJmruRCu!m&Otf{z(4S0m$_A{A-AxQf)uSTA%i& zUOSn**%A@unDfa9Nc7-jbgw{oXNzQ}^4=)r{n=)G`C~Zez6E)TM4G?Ey;>Hy^Srs( z36)HUS#gfN2eIO*>WMu|!Lc@%;#+uaWil+@Sx0z==26I8cRZY&*P(cg!`i7>;j%Wz z%Q8zS+b|sPK+byg&p78CS1a)A!_aCPeY}mRTg|92^HGrR+Nwy;Y9xycMts9SVcEaB=}2_yl{@@1e2LXG6KgZ&5`PThps;w<#c~8!e2PXRf3bXW5Ykb4_wzx;ZG7>M=Y0&+fv+Z zMPO936Vvdki7v*Znlo8gw1HVsR15%0gY4eE)d<(+w~{oPAGGuWPrD-f5$ReQCa(S> z)M19+ZMQP><>w1C9=^h)xd{!d%O$FojgCn>X7s=#gY=@nT=4d=ue3=!eVJLjwI>2L z?^YwzlK$ydHdr?N%v1#!?Ty>E5sDSMb=6-ba)?5>s+1_ot@h z*q2P#FSNa3jFT{jBmfCeN7R4%tF_VmMAz4Y%&}RUV#WfXjz#*A2y%EQIQrKkCEeVp z-d)x$+?I2jSho73X)ARWppSXAivIrq=9mz0Nc3!e z6><$yEmF;IA)T3{I}+aa_l&F4IQc4XTt)uR7uJ z-vglhDXS_yGe>TlP0U|08R*#S?~XcE$$VuT)@-*|URyBz)9v})hZ!Avdequ( zm!;b2HwfNspPc1VXh|r?9Cgn%9B?m&?AGFFV7j)Ae5mJkR&4s?y)DB-tnjwIU^Lj+ zU0yBQefbr#0LOFNvBhjzc-G%iw~`gRx4M~FDEmwXKbyWAp{@e+#gDSo@<@5)ihh3I@iwoGDj=vn`l;MoP-T?cuK^_w?S5QOWzP$ZIkRatsHm}gt%rd z2k~v>WOLi5D~z+#?ez-_hmo!(xn>00iOR#YcRs9rI#fEpiSIN!=vFuq7LiWbFxXH# z5z`b0nY*g%_M&x?`X-L?fe~(Sy?Xn8nW+=S*80RY(8q6kZEp|_x6ItgeOtagg>trj zHkS8MR+G%QRFiwE5A|gK021{X_r+{z-Y&DTg<-=ilH{zSF}U)0&Nv>_w*zZQ@eZ4z z$0|v6Ia|iYQ|2-D$R3o-yUF!!V%@ac`D2gHRxDfhaYmr22P1|(i0N3GvnVFhS zM2ip}aUD7VjCyyac?F`)B#9hK>`01S?QXd&N8HD3Qy*Opheh#brEOx+&2c1!7^0PQ zWo74(*vTh6(#@|)3P~eM(9H3XDN8T8H>Ws}4dqfUeC^L?Lh9~plw4lGa zNE&P7xm|Z+ISYL;`ShSYNteTr3)Nf3xn*JZnpQyP(?7*lS4@)ZGOX8+u$`+rX9uzA z{c9G>;yg2Imlm@_G?MT(gS!K{BRxHXTkFZMB~U{ZldcX1+#H@OpYczKt!%Za zqlFa5v=5kd$UJASTyaN2d2g#Bm&96ZC(N@EIW_$n!VtE8(t)OgfiOw zvM5wW3=x=GLBZTca60jirE_=JEvw2SOKTf7*u}Ot%;fQw1Y-l91!;I<=1mt;WwpGT z%w8vvK3FojQS!LQPfvW0NO{kVKrVn1h{UgG*`BeU{kQ{*GdG>2|HqaHBIPTZ6I z+}Gm=iS1;uv-?c2%(nAKm@XIpRHpZY^ZDbcsVY z`P*jWh6HD80QktxEAsEho<5sZ@I{W6t#2lurI$-$gtWtVCviOoCurjtJa?_|>d!+e zma)dz>9P$M?GQ}fO1GBk%2bk6wm*-WUe%8sg8SUbLgCxh~By>F0 zi%o5#x|4i1>fT<_wk@i->w(ig^${_}}|ts&UTKUr#Yt24A5ONqRF_ZC0KPHqdg5=j_1t02vv}6!?L(Pu0Nf1QFwCS zYDM#j@Di&az1b#lvkOP!a?z zf4z>ls&_9U9nrF?ux&TDBO9-@BU3UbZA>D!L!x74{DO) z2{$3zxDZNi;5YvOu8Uhyc(OE%zh{FUV~*J*06oo5L8zq2(&b$@F4kV;cBie&ZebZc zI*PXjv1}2e{?4$PC1OBjB20P~QVFWJTIH?Hw2{YRmdxWI#^tvD1fP1IZh@%CuH<*x z{{S*E&O+s@O4`w*Rb`NYxRbZ0IjlCtMq$Y#tvc=xD`cCPt7E4OKl;@aPg+~YLRV0z8k(kG^RPno~{{UW<=RZN5nn;s(KfL?DDzL}pPeuf3 z6G_#!ali)v)0)%-$Sv2LvF4^&R5N*ss>*Oiaf*@S$ldpW7{^S~u*j^~qU~pG+0O6Q zpyWGz&AGq4deqB46_vjB?WzeB&n=4*y;rxb8lfRl>NQ=mMyyA0XrZBuo>Z$24i8!> z>KA9)Zn=+X=W*cY`O*d^c2?-P+sENaB&@JFBhGbD#OJB>%|mi^3+qK|U69Lw4)xrC zp1fC@b@>)p2^g~g+2g0ys_N^gPh`>Qvs&BTDaiXwWzoku91vHWbK0e{hH+_&nH8iw z5}8%}1!eem#m%j2y0w(n7dF4ya)e18NLz&?hEhjGt=V)S=xNECK34?d$ceSy7bkQGwGve@bbXLN_@q*!mMyu=<`c@$12w z4~K0mZsUqeO-p*i1aL1Bh3@^h9r~K#?|wY^n*Q1t9;R=G=MwXzb}^47W>``ANXzKGicsu|>z-^~ZW#y-V^IB`(eL6W5bZQX@d4 zFYkkzRpK%ia~_91htjn4zY1y|Ahm0Y8!L&UjzJR@8QR2d{02MJ+g(9uWWSWruv7PV z8K^w6>)YjCqpfvvd??hdd=+`DTt>ESYbII=RIH4=Wrx!}JJ%mI(M0)KnOO0Ppd+7z z!mwsm+qWNddVijkmEy_df;eMT^LL|Q6ZZ#P)%oXahEQ2ooO*q6Sw1RThqn7=xQ&tp zRg^r-8wFxQfCiEa5MRg+*lEdc66uT4C=sJq@AB0wIF1>wr zs><=0V|6iS3JE71_xG+QJ61-G*KWhYup^v$itfG$O?H}v^l^OBHp7jdD8N1HtP6Xd zt!=7(f(b2FOQ`Kp#lu1~ha;iKb6Q$%r=x0dTr`Vy3e5)S0YV(fzzRVC;PP^M16cOg zH*w1)#E~`9<7VR9M0x(`sSLMQ7E8L>R!Cd;PYyfd*YT-iBY7 zdgRw}AyPc(Bb@rkRZW7d3oob zPUKX-VbJyaf3=moyIXVRB$p{NPnP}>y9AGZN4;mtTHNZieQ!-gxBETEn70_qGX!Fz z*z@{xUEhYJ)9yr{Wmzs3X*TYDJhSVM@#|i4JQ-(kq*}vu9n=V<$X%o?#DkH%`+5#5 zw(yOL>GM3cH*D@rL-V^J|<-ZU-HwgG6x@ss9^B~ zkU=bQ$h)pS`#9VP^d6Nyr*U+Mr_oiEoCsej+B8DZAhSgV- z42Q1(9%y2=q<$aOwJ4{KJ4xO-6yT#jKY*^ayhnXK+&2?LExC-JFvi|n5soUEjN#)5a zNXnAjWHN*P*8rUQQ?(Ba+UgR<);GRmN6f}0IaAjF`uk?6cvo9(6hkC`XkEmsNwlnQ z>bb@baay{rrw*$IVGUz+r+#hY0VVa$IqBYw$JDvu`SlGB3$2)i?13reN zn^e5A(|LG&=^V_76uH=WIp^E!Svp;`_jc^hD%?W|`J)7u`e&~c>258p+Tv-Wn%+4G zz+^0~fs71u`O&cUG#|t_7q@aWl0$L38S=R+pHc`vfUR!}X*!b@lGP%TGD~a{gpmD1 ze~og`c$-bsBv~(QB1|C#?U<^gcE}^QrCo0kY4(X6Hn-DD5c$ioJD&rmGzqJlSMuE2 zt4DpNT*9|a%-|TKhnyZ4gOT4qolSA0Sxu%%ZKlboTF9-sNhNU6#0NO&FilYK_r-ln zM!sf-NxYL8KqbQi(C2C69AoKS1pfdQLECZ1Z>Kbg^)xg+Qb{&Vc?O>( zaL5`x(R1!wu|I}t_x9D*^zt^GCW6LI#%XP&!h`FEAmD$q#baoCb*=WVaSrRysxl1m zhDXmpJLlz*9An^RH!p=`E!DlO)S#~E(NBya@-TUeh`@vruLi)U*aUrckg-XOa% z$6Sp4Ydc215l+);ki&T<<1A`R`Cty)NFk1T9MpO=x|Oo(5$cvP++JF-=H0g;TyRFx zcs=pWSB~Q98&+nIbdusi+lW!vU=iuwf%1>O)h?4%nPIgyt9i>H0ho@sOn$iOQE7fA z)Z@9hj#R(2)74Zdm;GBD9l-z@>4Hh?PS-CY)TTjqV{kPKFg8q$pCA>%366IVPp1N# zt4xx|ZiZ`use~Ymy2sz&C#6)9ut#FWuZyL(vUHC1kjyr-81fVjnCd@31!4aH!a%0p zdrN!e`$fUpWq5w?KZbGbT34|xys-%3o5^8_fnmWU^V6WmC*HE|{4qSSTpzQU)mwAj zc|0IJjyiSk)})g4mD=br#WLPaBys0u!!(hx$0dS;R*#JCr|`tyeb?G80AJ1`vQ z<{9hHrDB;a?5&e^&}id~fXlhm5!dK*R;{748fx97b4;v&oyqdAQULYlg1p&&*4I$A z(rsExICi$*Jb57bX_7(QKJI?CrY^NDB5yJq7oKLx0A)~j!OtN69Q#){qw90oShm|) zC0XLkk|ULA4tUPfz^;PV#dF%p6mwi(m=vq52uqYBz8Gg6YNAh5sJHR?j?PK1bpHS? znQ*>rUTV2Kk-+@1+Miy2#eJfJ_*8W@DNaWQ&b&~UmLBo6CQqWA?v=-3CACU#E_TTy72hW`R#PvVUv;0Y@ zYFBzp%jMlB?ab$Bkr7v+9Pz~s;q5{vkz$q^5;P1EXDRd<{c%%hORuept-9OAA&d+x zt0anjO7tuIjUd?L{9~uIaa-x~>NgOr!y=5um0`&wjQ;>4dQ>pmLv5?Iyf>=L8Y4@+ zyt2)MjlAUX&lTtwR}*R%6HR+>wXNa-3PP_I?BlOce!O#8I+mqq_p1-tV8n^Jj1k7z zIXwyFeN7vac4o(C4fLP9g(7RAxJn&Ikl9#QqMo)V1UGd%1{)J?;nrjtS4r zoEqu8NVZ_1kvz*~On&sNURFJaU#()zsYj@`+k1;YEnCS2l(drbzzyg+_GJ2x_Ior|@}x{jK4H%R5kco9?j-ibbeayY ztm?XtlFrPw<7|qv1SNUKSGd670a9Q1k{IT^wP+{3b;O2HncI$=N3b58QK+>@`8)RN zu)dGsFNh_ZOS*Z!&dR9>%R&JeTn@)4I2q#|>+^fW@!VUY?zhUyafTl&XFQLm&{yh* z?c=G#W$@l>%Xk}4xZ0a0l2%m<(Y|$3%5j6!BhtSs{A;UAt6g0EqHWFdZY+LjK+Xnw z{yll^U08K<3a-qdsNAKso}IhPZ!k>>jx+PA&N&^k+Pvpgyi+^JxtM1l`g2`O$sLj_ zXKv8IW9eK>(ko8*Z#APl7Cmrlsxdj+cPEZNv`(uZ%w%8yC#mczS5}jB6K=?2j5GIf z!5I41f7)3}{{R*aa=pFlQaxAgR_!YlEeL;(sfPJe5x>50uQ0< zOK{D3Cg~lvu*XA!I`*n;qGwi(OJHLd#^LE#bo*9{(V~`Zq4AN8#ZR&H=9PwSd_U3c zZl2>%)Wf!$r3Gv(iiYAwKO{#yup=bnvg5r&sB6F4x3kG6<#|ciQ=$({bRSBSQn#~% z!}fL}StOHp+L}nz09^dIKSdbFy<`ZQXY$u`?QVGM$?Ho&6P;nn)LfBkhN z7hZn$W(_l)!Hx?9&l#(7n`<|ZgF6M=vCuD;dgLDcYK&$pa?(h7>bn;?`q9m)QMXYN z>PsXI=A*33f~(a>zr90qWCNBA-12ZRe+st^>X6K%a=E}b>Gh{6dxs0i+ScQd zh>qUW1~Kk+U#}hMi)$Ud-sNX!$0M<)UD?fRG>q|>T~{tKyJxtnGD2-;SqzHI`P`|U z$bZ`7AC(uf4cTsc_FIq}M!U3A=564f zIl-$QHD4!CiWM-j+1tl&oc-;iEPoPBOVoRq`-{W(d*e9cu4%qodEGsR!Hn}(BeXNk z^D$W2vGSaZVx<1hTUj=%XK~NWa2A&+SrI~fq0D~2F+bBar)-lG-Ia$$A1zZGkS{qs zj^FE6EwwqLX4=~`k;faVZK&;X_3WyO&CFqX6Wr7>+=KG7D7SraR{mw}3qT(oj7<=TGlmO=Ct3dEvJ?O?-`{IN=e z?#X89)Ou9(DMrMlkMQBWbJ)>QM;_7t04)H{dUc|tF3-2NhF1Hl!Q>9K){*wF%j`$@ zsfjM!kC&dAq;~U9IZzJ(bgw+>Clba{!m!<(@-a{{Wyi1cs`pW~#?u^(tfxO;YMRdC zOkzm++nvgIT=vBXn_p7IAYsdW@6Qz~^Y>V*V;LR3w7?`Am45IU%@VT!ynXIC=9=83 zN#%Usd6;$?>s&v^pBU?!4V|u^q1wlJd#Ub>64-bFz*kY}_qjZDuGpM6-T?H*?!V{q zuRQq2@m;-ub;+5Z6A5ZpxJ@P~S^91#5g8RT{1iEbA@d+{!td!TDCr|JwOytN@D zZ0^{4<2~`8&ZGb(!P6nmN=L1 zF;(EO1S$OMw)kK0&t37g)sCxeJaF0C+yUoG#IYzr+MsnGjU~9Hwx@ObMSMb!LD1hr z;#=)OL6DXqZR007`kvm^^X(4@R>c>fG~QcbPSGI7NUUERLv0Pcx?G@|Nux7GyR2m8 zPdKX=5_yY^1_Weh(zCuG-!$-P#^O5&qw|S?&7HSa|@*nt$@Tc+XT`@4-jyJf2j1|Zr z57xa4;A~4fT?2ElM<{#|obmqv>NV$Z453!&!zb4@=pO@xvA=a<(dEhvbk5P&>%}q0 zvFZtBG-6|GeGdK!LvyZbtj%PyQ51_7E>sh$eXSKDoiDNpH>OXQeu^jLK;DAXy z)Vdk|%+{xp)<(OtR&!UsdVl0mOOPJ zWM>?7AHTgaeoEm(MLVA zJ{ccz$6rne$iN<>6=%fS-nFH8k594H?HclXS9xHDXY&~&Ckj=EIKqR$_N-kp;@R{s zhCFc>jXXDTCH9$dZw{L-5?z=Q05g$;%8rySxo2_W6q7=})86%dTc$sbY zuforYw)X*JYmsj?yh`#zI03f?KXi}02OMLL^{;)bXg)IW1^)oswBNAmk0fO$Sd}3; zIox(~Gn1cu5-T}I#+PTjcvHqu_#aAHuCFX)l5MLUhNTbgCf&~H`&d5xsf}%K ztzAtCSZq{Fg#t~>9!_}ABztqy-niWaH2O!`^(hwlpa=K+mDKV;L+SwbN|5F1boSZ=hFhCSCPt4a!s0$wPhrMEK9#>@ z(hG%;%6TA~X=(W=pIbRxys`O%%4Eo3$}`U$ z#W;yaQ(M9p&0_K!d9JPFE@UyN^AU168%=3yULRdw&0ATLX_a!qBjtOKrEyZ~a@w-3 zyU5T)m~c+#R>pD-CX?dpsU70jCT47TtO}fZP_B!ywP&v1*j_EK+q~#4-zEo4!`ZRZztiNb!Nh4z*+8fw|O?eWQq_+MphW6x0@+?ZK zRPRmZPfU*Ww<9h5Yb0BvlWT4A#~hx+`U=Xw_-po?Cb(OB$n9Y&jVwgUCO1gQ;JvalvbGBxfUVh%Or(pJR&XtUMWgVj)=| zk~P_%Gj{GzMF-T6*0{e5_?Be2ZP%9;_Zv>kNXpXs@$~L%(EK~%4NFtB7O~45F)|jC zSy)Ke#ts#S9>>;=Nw-ECounFllH6Qs6I;)4zv=<`P<9{f6Y6Rm9xIJwZ<%>0w}@^` zrtA*<9zRN>9sP?$&2fEiGp-|2$LEMI_dx6E-n9HVq|2q~b6s1kJ1#dD-i3)?qa>aW zd~~1{iKhO~(cT-TxOBHh**QSVv>yB(gFW+_=%tY$)6(PZ*|wcR+D9ZyA#gvx+WIkJNQI93@#(f9pRxB*Pw)8uBt?!y^%ovTd!6Dd3K$#;Wnx8^?n_9)a zowcNsPjupWVg>fvhVv9;07xM5+rO=Hwl}uA<=|N4@@0jvh*5xUps_suRBGDo){Si% z$)>Y4uq63~#3#0M$gGR671`cfM5$_QCs$^a$0IO|;|GEVUr|qS=xSZJ_C}!Q+TuB{ ze3F1W7Rq(bKMIOF>wCh{{h}6Wqrp}ASqF3J?afuQ{?fiilEN}Bqg}})>9`TlXLkih zw_284D~Jb~G`9B_n@65}l~s1n%v288rWzFNUGKD|jypL%`+#tSBB?ni2l>{HlXGJ& znumNwp^B;uZelnDatE)qWLaFY-cBP}Q!IW@m3HGiV0Eou3&#btH;`Ovd#&Vb{_@yl zXZS(KO!|6I65Pzu+fBHd%~Ud~q1`cJ+yY2oF`QRLVXE2bac#AqP`J67@`YnxF}}Qy zmpw-#io_G>?#*jwwmBn+6EfQ}<+pI49zFdlQ$(?oMVe`y&CTP)1X+MEiB5iAbN%kr z29`P~d~0t!$|PBp6+(!!q2aBZ#-} zSaiygK{y?N%{NCDI*;0#!&c1Jsz(`FA_RBH!+sd7y+-cV@*S-tcUO?9!hynMdwP0z z#ai(8nPv7k=9)h<{iKnVkot^c^`*GEO@!0z;nUVO)Er8NJ5$*>hXsI=$7^QM?aZvm=ji0>IhTT1T11fJ&|KmB#Z$Tqvkf4oVrM)B5!(fD@8_BK+wkaB>x+}ptn zKZN(^s5QWdapq?(%05%;T`|<<^dgN6{$9_R5s}B|QbnlCVLKS`s{a5XJ9EV{$_ACy zRfuN!c{uA%mepZJk%)hH^IR}0M{ML1 z?@zTJM6yTztPZ?%HPv_*S^Hmz(CQOK8nkK(Cqdw>w8U{3zvD1-_-P zv_~iIRC#lC01PSqzl}!>?h%8i`J3ec^r%MY&p4BBBPSTG0i`|Vn_e`6D|Pus4l?~f z$I~R|ryc5LstH(+P|~Ee{{WV;+;O;seaxKjDmz%1KK-nx1YnE-T5w<4$7rxaW9M9L z!^qBlW*u7tzqM4qGDR-QE!jhkti=!OQ>glAI?~b`iQ$FDy0+_a;1N}teF_0VNFE?+U0+s{Lf zy;dfkH6(2ZcO-g$pGt;QC5rsV=Fd#z(kL-p0?J7Ga6kI=`9sjL320>bSnbAh&px#i zvqEv@kc-yA8$0DKa~GCB*A7I>*OSON$7;m*gYZJr#-9;%{aQcl z`0OD}->G7<&dNsKF@wOtreEEt!!lrClhwKIYqj{R`$B1d5420GeJ1AC<6B1- z@xrOOU^vd^0|Nka$8nFR&b}-0cBSK8O|P{}>x;XI82ruv3)h7MfIDCcK$fLgimPC5 z-RqjU9m>YLSQTPV-N!Ya!+glfe70`8$I3IuKGpBu7WgNj#jD2-qo>;4$l7#9eW2|! zlgp{&sQh|RQ_%9i3h7o_rNnm^x7M&h49b(mBM|Z{cLS#t^e4iP3tIRm!p7d#`S0Mk znXVDA1Z&U*Q_md^dz$BbXYi-MRuS8-pw_w>k&47)m&th#`&<%!q<%HuY1#$7o|SJM zkNkVX5`-%G5&)wI@}`M;oG0xu5xV$mwA@DiMGP;ie4VFxo~y zIUxT4g?%~k2f#7-)5Z2TcfKI7)AaooF(cVc_s$!07Wsw-02#qG8Aju#Q z0pxb)*0yhEQ3|%*t)53ct0Tu2ziia}+ljY2TSgGCBZ0s_PMG$sU`)2q=VYBy5>;Dq z2OYVjgssKIpLt644bUEX(}D(tqfp;ASd+y;A@Y-P<#U2Rx@&7AD-M8pPx6w%x_S!q zZ-kfs0A{go+{NXNwm zwLK!m+AEi1Ya4y3c4gFjqp=33yOJe_NY)=dH5*yhHebL4&*zG%ZF6y_D3;-x;yY8i zU7y__;5n@wX3f0ixUiZ#tv=)lBXDrXz6j~pHC9`cWnG&)cZ{1^WNhF*(wOz9hk+*Y z*4(1TxsN`8o(HvBzeb+bSljs#NyyBZD0_epH4{m4){$yj_t;91%3XFkXNYUVrfF&MiXC zt+uON+&<+p1uEF-jNl5pqd9I`(%o$2xQw)I6l9Sqk{ORo59?dWqsJbn2H4`fw~jS` zGHk{&M=O=$u;$axnqi7-T&t14ZqN^)BZ|GMoBcMzOL%66@f<2h6@v+T9QtFfJJSQP z(&w1m&km7mYdy{2@{{aD32ng{<0r3Nk z^#uA?oBTM`r||Z({ieK02r7YN`A+3*k=s7~vtF6uUy9K9OG!6P9Bq9x$I6Av1ZLyr zW1O!(+|=rei#GfLV7 z?QSHuYj}$^F~S6k8T+SqWf(jjGhBayz93KH+v~^iMxAl3PYM~Lm1G0SQH&uf26@Ia z)4pmS7iv0f-n(ls)UFm+fGklwYEcjp1Z+kQ2qX@oq|q~_@P~(?w(*lLpK)=nX|r2` zE_|bG!bay{-H=DhNX9pNaBH!#@aCVS>)+aKbqse_v4(3~XK4QTIa!qCZXU-6gIp{# zw}&(h2IozR)kYNmfzTu zBi>t`(n041nSniUKK5{W_8jyT=DLoet8Aj;)uD-)HMyVWXw-Dt`1wH?#xgOEwbf}b zS!zBWwz--ci6oBwL)_XoA-+8*G%2>- zht96q8QqS9w_i%<{1>cVORYvNgnE>B5|Z9*pE{Ks`C)KWUZX<@_ zqgfE7k0;&Qr@tT4s_6bMc`al?Y|@o*5@j2fMFX4;D_h3CHqv}Yp<1?^Hm4=^nyO6} zpo+}_=vFyb1>@>|VUb*gmx|-iH5;fVnmFc!=1(q7#Dmj}57LgBf!M=sZ+EBL&kfbp zjm(1!mm7B)EPQLKXfg)4ypHp%3o{I;9q>By>x#y?zK-L=5y>o&r<(Z;N~utOgVMBo z`+XwaVTSX}c~|#k*XB>57RP!{66+pcTBf(GRbj}yI*qtAanl!>#dP(W2d}pc@)WSAS|-% zEgKKO=iaJ1?gyjzZu?2pt-Q&!`+*Mfk$s{P!7-h{N{4A7dmLx2L#|!e_+&iGHtT7L zXrO4BWh2y{e?yWh&o6vWd8OFJHH>!>Y3nkoO>D<(3_V9sPoco8SH2?Du71yO*YN5R zDuA&`_oGqQcTbpA0kHbS@mjQU#~6=sd_EXB?SgyMZ?0R~`OK>Jo7d%S-ehunW3T0! zpt|!d=lVoz8Dc<4Wb+mKWM{oi2AvGvXPIZSjo4_)k?o(Y7Yl{oh_wx3)-|<~>SVV7 zfR1(oGlR5$hIp#?-xHZVU?Z!Q&tvYt}AxIDXUnm1u5NxL-SV@;UFo z=eJB(DWY0Oad#Wq>iTRmOuLyTNg0$6_jvE?f$Ljx+uTcW<*lxlsEh&T!tJ?^I{K6B zXcp%5+Ke|z(=2&Zm2z9(DtPJqsz|kr zKN<-?;T*VytYMBDl?Y-|v4=f)9sdBWW$BuxY~+&a2t-q|tP#rJG7;AR9)B8li!_KL zvyE;vJIOq_nZ%a2MVy|1m1B(OuNcL0dS%nw#pSe@3O65=kk1h5jyXTdj-_sIc-}~( zniaN|YjtzE@Wxag%?6h9kbroO<$e#%cPPv$wMwt}eXg z7!Mvp$UQpZxZA%HLv3mqjm(>VR7Or*4oNN0ckN4dO^-~}HG5m@D9ksv5YDVe?$a9x z{^`%nk>3~<&%>^2hT(2r;^kvggkutwV~jW67|&pRd9F_2-7FS2ZFIKg;WzD84VCHj zscudE>Z3t*B#^3n-@Mzf`--H>jCDGFTHeM>-9F;p>sgJ`LiYn|m3|1xZ1o-TFnd>D zYpBPlyR`4S7Ajy(N{yG~2xC7Y(~OBepZa&$Ve;T3%|Az16(Q z3Pz+lw_%PB0nRCkTIhNY{3W3*)){P8K*(c32nFL9I43`^deqarLWWpd?J`Hk?1;lQ z>~VqLAEkN!0E6sqHGdDT>+5@8m@q8tOJ~^juFU9BX!a4wa?(xYC?$X_T%O~c{uC=A zZK0=s;yWD|N|H~s+_mh3Y_O`Zj(5)(0C0VMF;sLP66unN)+CYcW;wW(Wgjo8RU_B8 zrEBPVzMco3+IFQq@`Au6v!5vk*8>N;eiXO9Keu&PeLm%OHuD=qxEzo<&!qrN_ckqO zG%?4QVm@}Sadn#nxxk^A~@Bq(ER(nki>5K;1l?CrPQ9MoL%2p z$$rfCs}y`iG;pWy19jw*dUwSd$B7j;NpEYlF@5FvO3^LAp67)K{>~BMf-x4^gb&80D_rox85tU(5IG3 zB)GC^K=Pqj?bQ#<%BbX%x09a!qP{eO)ueWZckee4yB9qB3i`|b3M+s1d%G03o>}di zD!x-~NRQqqQ<7J{LE!c6UnVO?^R2?OFWK9ENcr=g2>zAbM(!sqP0ZgKK-Tug-c)Ze zuJ8%KQJ?ZT^sZY`mA6MEe<_Rrdu}}S#}(XsMe&T@DYmowWN2lzgr}ZI%`)y{cXS>7 zJA2m?6uTx8ZS$2_0~>wb=C+N@Z>dx=iCMl;xM$lu_M!C*j zfm$%z);AeaKf6k^i>sp2DyKWPg}_YnfHPOBB-ArW8b^^J+`k}RK<143VOuPrh8XVT zf1g^nr|69|PquYU%fBwz3-zr{E5d$YEp>Tow5ot(%l^D~sFlFPX~n!K&ol1Zh1h%g z)Y@y!sBQ`7K7L?Vmd|sa@v9TtSm~3py8X9nFv9{A4%~G7YU22zkv`97Z*LaEk+`4U z4s*saOQxkqvoh{<_Oocr%2#p0RptKxF5itTHtPk$D@I*%P7C3NdVWUwUo45?n<$ zmb;;g23%w19S7@2l{L&>O6~pFEf~j8dvV{|rqQ%}nWMV>!xdGpp~&463Gp#1VF7PKwG6UJC7-ICe6&G4^^wOTg7r4De|a0eX6YXn_uQTcn2M6 za|N0!*dO7O%)@79GD*j!Xhk$=-!yx<<+l986%DqZfUM2ARd`oyWxvLxR*VtmG|Jrw zKQ@0FhpADyWiFBlm7_)DA%iIA*EGvZbvL7S)eXrAKJTt7C523f_o`KwIRo;k^!VYH zR${B@GPud9>IByXVvm01RA$@wb5mW<4aggO!5aMAN#SZeLQ8p_cH641Ir{#6DYq{S zR*8t^jnwYW@0V%y9r&YCUCM+j1>3YK?1wnDkbf^TRFXO>qkERE{t~ zPPZ4e>mn zub88{@$-F073-f1yl1EUW$=tX8Pv3!ir6H{C@)$mRissu%V1k4r?>O3P}Bba zYVQz3aSU=>=?!Zb3Q;Y{k%0AllhXqjuOYRCl1;4LamgbC@vD(Ai0?jPw>UV?0qgnF z)Hgn^@g|+1ca((tv6LoKTYuk!M@6*mTR>o1%P$~2Lqo|PI=l4HaxY+<$>Ft ze>#ie?z0A`s2SnF^8{*EK7a%R81(Cd-n6H=64>XplML6l5?imA4pbtiL&iFL^~Gmh z$nxNEg<|XvdRX09jm245^z5go282zLpDbXnazBu+i`dI@#5=9xP0^?B^7+RkeJii{ zTW=caizIRZ=1yJM=PSVD&=5h$J*$p}Nkg(L?^fdkeNS#{xA|D^(=Fp!Rz{o5Srn^x3=ae!!i#Hvu)rUl06#DvTxZsyxr)W@)s4K-#^*n9j2{00hIyu1CVe_cCY#K;U)>z2 z2R`)I(;Ljn&AZG}KgwVM;kAL;+E(BIKR^EfSgs#QSaoj$%cfgJ_KikKH$x++-GDym$G%2B zm1E9-j9PJ5rupwqPHp7ZSqaIsrV z%t#Uq=rfO)d;4~&v`uEm{t}P0T|wvWR%Qnrp1IGdIP3bKwfY?zBsv4(csw9LqCZN4goUq~9JJf;j->cjMl*w66i&U+T7~ z*FssY32!R|6eEF>M&8Fc=|jS{Hw_Cymhwy#+FVILmxaIpk%OG$uS(L_dB@%;RrmCM<8-?LB=stchnNG)qFa?zwlMX)wJK}cJjCH!OQLA3NoOD zB)8DudRFGW;l$By6U(=0q*U`1#~5ZH{{VSF!S9pCDEMXK$ux;Bw0nzn)UK|fTXdE} z1m7pkgYE}G)C`XGS6S7kzKUq>q_<~{@a+}AN$t*f>GI?b)ViA@9XXp?xo@^_yMMb2 z+lAR~Pak&~BlY(+>Y5kBldC~%scF+llW5R^a~p%SfC`fs9YG;aJdVDVm*%Jj$`FnVILk!dTE-0O>?%WDLdvRK>PM9h~P@$+{@Q`hV5S3CpZ z8x0!k?WI=RR*{&A*zS>3^aq^a^{p)%Mu){Z+QWH&r~RTB%UZ>A@+d|2VrwzQfA7hnp%ObHU7ob1hUidVwXmt15^m>1V*`tNvx`7B;m;#cp!9RQMlhZw` z1H!&MnJuQb)wKJ2cqf#%+3tc%9HjBNWEmss282>cZCkTdg+YX24fZF;HXF55t~0u0q>dyn|}9$2&?0XOr$kyx@I! z>ssCs*DfqM4U+ z)FG1|V#cxODY>K)4D}whQG82bcecjt+-aua42dGfWQCZ24(^NV>Ds2!bh~S9Gjw{K z(XLL$+CV%tQSf~cLG(D-lLWVmr~grmk_fs^3@k{IqlS78a+jAbQ^znaFELF8HQ|}ZY(~B z{{Yom-XF2N)AX3^?BtcsQ8tmIx0sNLE{cIV5ZME;IpKR|tI$_v7(8)4lM=-k`SzIKcN>2X^O}}Vifw;w z99o5%$q(I*SmP!`f_TqfeQI4#!M6HIifgMohP89CWP)XxH=K}2;jw@?=M`SgTMa(# zRy(WAV+j%JobYpxUe!UPF8B|{Iz8U5&v3VvP{=X8Pt2>+82Z;&7QF*&G0CT2NrleF zk;1p~$ok^At9?GVVy@&4;4yHiaXwGqr91&aEM~W?PZQ10SZ8lih zltzddWb56qD?a!89tMWu#%q}x+`KrN;hQIeum(J1aQzQ@)zK%lmrlf%ku0(j%6!Gh zIp;Y40QJxt8~Rq0V{~C#jY4a7l|OK95D+-^41fC7r9AqFf;3x;t97x|d{L?i8yYu=?k#5}u5KFEACgxrvNIfeVB)m2?-D?!Z#H(fg`G@0?Aw(*9FRWl zbJy0bX@=hO!}1Ta+Wn=ZC4R|s3kgOzP)Nq^oFB@rUU;|c>1pK0HN5tbY-W};RddD% z%aBhQB=@R_t)XVsY;Q-OZ+Q)@4Z$poRk{A}UiGWtp9I`Vdo|>rVv`Jh%_LBA7aXgO zikOC3rL zc4-ZXSXBsS-h7-MI&+M4&1OZVO`>XhF0|C$hG`WheU7K6Ubx8Vis`kjM*89A^8D+` zWCdBv4XC7kgnmDTU`uPMYgW%|3oLh$L$!>Io4Dt4=OA!1oKqFb@#;4hP)TgC*vD@e z45aQ>9RC0bIURe}Rnw)+l0&Dp#CIF;T^zYV-=1^$X0~AP#pUgqwZ-%!$v6N=ujXUd z3xm(4SGMrW#j7gYc`>(jUzJzi0PR2$zls2>f1}+x&u+5bTo~8P33j;$pPM)wa&gb+ zSbi_j#CjY}J;t9OnJ9(hW4VCpNFLs`+fCt{>swX1nr0VFO0MYxr?AfM-$7nw;@vWB zTU3kBx;Ik>VHyMosGr5pQ_pjr^ji7}?{nfW_$Z=j`cH|h(PNHJ+_8#bC&~*DOkp$F z4DZK$SI7FspXH-Qku-8#pjA2AO6Q#WA6~WfNBk77`E9&kq}%P&{#A1_NB;mH7VV#x zAm<7}Jvh&$eA8{HPDI-q%vDXuykHK!d!K6bC}|Upw6)O1_=TyxxBc7Y{b27nrO9uL|IReuV!3jWg;=&Q#{$DG(&v&EF^qeft1poZyJ7P^%M1X1o|P<>xi!|i z_UY8LHt_Mc2$)lj{{H09n#9s1Yc<0;haob@(RFcV+XABjxl3o9 z@zSg67AvRTh*mw@e~ca3_o*+TWa=_SXB&Biq|SKhiresi_Jq21^IEdaZ#BCK267kF z`tjIS4e$v7m=y~!`=hDtj8uAT21}KWKi#t)#EJsuzLl+iVqJN^Gf0b-1vq2))D!A> zx@nn4;!B)&HFo3S?d-NMak|w+BQs`fc?YfybMnU4H%sO`b08SPbTqmQw20DYqIzS|ka{Rnt9Dh0j>!Dud@o;v2U4=;q2^Y=&u}CUM zRR`Xf%B4PKeZUX~?|PKks>H>apP>uC10J8PE7&yZIpI>laNjW9`BPOIXyuR{!ATj; zMte~mg1x5nk@qV%0G1?vG}*1z-rwbE70)1NIj91=ZV01u2IB|Xt;c-Q#JL5Bpgn%3 ztHBFS{5uYPGCKO_-k0v3*&t+s-oJ$e^6F18wK9D0$N@uca=gwbN~`9^=b~HH?>HyF-kB5T{va z_WC3qU8THMu(!?oln4)OU{+s?yj!QY+O&J<=2;%e=2l`>IgIis<+zMoQqb=0yTGD^p&3`SG|z{W9;TKW6OciM&j z0E#ZHuP(19k4h)ND0#otXrUv_1=V0|bg=?F@0t zXYw6u*fbB>qU%TT5tCh#&ht%;2~h*EX$j~t)O9@%YVt1`YLxIn(2PU?rXD-Jv zr0Jj98jM!Ec1YwTdz*$m05uxIE%hgcMPE7>WN;74q!I|vu^nl*=P&nLbZ2m2er(hh zw_iMeD-wQelbzMR=6;0go^$17+PUm|jw`SDQL4=w+(#YataE>(&21+lQW%ixdB!>X z>xW6ddph!`JGNsW^U}J%ff_Z$dMwuxMz9vRW?UWF9gnX-DA*!;)`71@X=Ql~+Be$e zy1;^MTPiwG||f@-hg{6897?pA}Rhfmd{m2R!%kwTr`OrcnuanHBwO|iDM zw6|4TQdEFce-QefluI?`%#o`F+xH`plrPhFy=?qI_;IUzHP;4{sXTGrG%0e7hjQ&~ z@sr$g4;{TJ?P9EtH~4|zoi_HzQq~rG>sjH5$sM>*V0i%;B<vQUupb$)SeNWPu6W_vDRdoF&<`%QbjIp znEwFFHyq|NIl$x^*zoP{nW{}PO>Z8VAx94I4=~JqaL0~$;-6{ZeNpcJ0MV_@^_*mU z`v6%8>N&=Kqlz|qjwW8AcWb3zD?;z9Z2~xEb|oSm+a9F)jw`j$H8;F_8NS^u+}==* zTV}Kjk&jS%1C!KZsQ7cj){$ygQ))VFeq>;IFbN1($vFgM3lW%78BBYcb~)Y7FuO)E&pD>} z_fBmO#F5MWlWz@+xsT5T4aDKMZ5{KTaoG9_r{Gvu!MZ%RQ%7lcs7Q)qa~aC@0wmF4WZ{!6-X_j|{PdZ1j4gggEkRRQMBZJo+jdOZUoz&7z519T#N*i=C z{_WU(>=Dj#r1QtMSMmM6p=II+({7`-w0+7$UcV6nK?)cXg*h3|UMUS|dk2N|Z9l=@ z9*b;9~%Fr1*>D3mppP z-Wjy<8EAx(TuJ_~8P5Z$Zaoh*4^TS2GSW>>e=g$VPaay8+vNmpy>XQ|Jo|U6cg9^l zWrj#(^5jz@G)ta6fBjX>_-59}#PGe%l+qnZVgZ03A}Q{B*2S)$sa+XX8_RhX6$RDj zRA%+t>x0{^JrR8fbzM^9NVi*vRLsi3gaqy0Pp7G>=f%3`_B@FtzMVFqJeiHQlvo#z z2_0}V)L_=Gs|ze~hT3Fok%-6%#~(LBX__{HCZT?iNpP?$t{P_y%O9pd`M(ei3&@va zQo~f#A4!@xCT}g&7mq(7>+S1L(>~F0bfI22WVgX!tUhe@>smTj!#jfOByvZ89_0%9 zeZsTz{>DRtla5xK;x7qL6!Bdvd2J%H$c&y`k?qLK0l`150nMSQapFl%p&h)-CB$tX zEiP0KrVVOG;td)*h+~beE!D8HEQfS>JeK$Mt|9)_V`{-KmPp^`+xL_Y{{UTU*+FS_ zr!1EllWK;>eqG%&j>FonA?9sq-XXG!UAb#}R=rn{xqEravkZOht&!854@!Qip!uk8 zt>&2-$->XW1^g<6J{M7CCC$3rD=8a%vNquL;MTp?rKo7yJS(UcTpRwU9b?QA4zCxx3Kl_8l5kEp4&*0t7rF?W4$Yj0=erd@_r zkpBR)!RI}*T+FtxOKQgIIU|!`^8?MpHVz5gxcmvt5+*NQNu;&=Q^$E6lgIwXGO}`T z2Pd~)D|<$3TYD)Q8J%V%?epT=s0X@&I@TtWZ(`B3aotXn`F+aC7;j;m^XplfjpgLZ zs@jBc`7-TNWyaB*fHBm5W~8G-$9Gp&7g9}iHJq0h5vYlfN&BU5d~<=CXj|3J$!TkwOo;acJc!cKq_eNw27=Ex@|W4+G~ji&A2i#$1T(z zPaIO{8Zw@Zp=#IHs%+!B^BG1{YQ_|L^Zd!hYFzjqRytc7ythDeODi;IfhjK9!@@EdwA_t6|mSm$O%0|4mytYt$0I!}F3(-IgHaL5C9Txg zz-(pC)HwNDc6~Uk$#hvSJUUWCA%%Enako2(^{ne34dUwJ##mZjHz{d?oO@$Aq9AJB zUFsT4ZMu6&qYwW8ElX_~>^9@yueDe3hOllvBl&uRTeYjkj~c@p60M9dB)2@{ze>B| zt9WfSi9G!l$(gOgD@{2G8n4Q6_>tDKEhC3T@e|%h4A!X0@*u{{=Q#(A1A+O`eMz>a z-^B~fKTc_u)m9Ob^E4~9nXoWA_WBC(O-oGCbW6$P((k-Pjj+osSNEo6+{Cu%^YbX| z21xY4uJgs$Uuc26nb@0$21RKG*oS;KLV4!69~b?PPYlTwy~NBoaCzJG#abx%qxR(1 z;qfPm?PoKr_c6$AnKrSI2>HpA(=I+!$gc*}?we23<_jB1B7#PE$Q=jg&3eb}L95xz z;{8h1WxAPd?qr!(O}<^bHUkA9^dtu7oQ^BU^$Un^{3dLrwuRJB<{7sUE3PrLoc+*w z$E|l!jgiAs;yJ6G*ESKXkt*ED8IeM_3Ui+Rwa*!31-Ap{9yzX)#}5^Vw%g^h$pAnB z`-NGsG3(Ro#d8prnDt=2^IDjaysWXO%D$j~jXowNS<6N_OanE8(pbx%FpG9W8IzD-H$`+ zYB-`KLWO9r|~wqAPh+v+r3WIaU52OcPM7sUh=9mTsHTxFB|+ zC-PcPk%yYu=lFWmuQKm(Ns*mV7{8ased=)mejNFJ+p+~iB&!HruDe|2g8u*wDoWQ& z^E!>ZC}Yk&jT!`=f=LmVb4IHl00WLQ^r+>9ie;qyJ${r#8bSWIkM8dK)B>+?(YEc~ z4=`5ZTgz@n(f)s0v!}qx z5muCq#GK)rinUjGuRRaxsdA88C%an|AIpYmTrnyijnR| z8;g0AvhGF%A6yzdE9H@wXYjE#7dI08<8xzzz3N~T zu?&jb{vVY`6n<%C$FRkD`kUWd3B9nmU%JE)KDBIKF3_Srqa!s^AgRgD-u{(5cL6&*@DH$dMhP-0ze9&G;#u z;bdM2T5ZLdn;eeS=f4YIYWr3wDGv7#Y-z5DqeZTD!>@yk}?yc)?Z9 zYmxZomi{03W366BkVkPOAZ{QH>_`Bfvd&0>031p|#Ya zzK_dEr(84uj!y#(&~j^u@~!SP+hw=4^5(ZfC1pFj_R0B=&~ZhXq()hs4coq6+}Ba? zm&KNT81dbm<@9RS`}VQP{oZmnW4=2670g)`k|o9i0g_K@wI!n5M$Ga?yN)m$1dpvs zyBfLl&yHrB$KMUE8%c)hM!B_VZL-^0m>dNMIOm?V;#VIFW zJ9x9NKXAgq>S@v0@n8m6Ej1(hsxcj940D!L`_^6opovv+WU-bEoPf?dF zf0?eP$SfDh`^L;}7-0O$bHV!hVz}Rk7SN}P?xsMjw+v=dc`u%X`<}m1TT@qNaxyNi zcNS1~w?GG4SkVovcxG862Q9Y+ew9qwF}Z0KzVHC&8Av7 z;|SwuP#BI>dgIo;55SVGo`DoiZ13f$+E8%ZQ$vbI+Qkb9JibcV2uj$fU7`J?_4xbH!}K9N& zZ6+a>@>@f?IKbt`2*Jl}9G>*LkCkpwyVEXgZ<-s)rni|!O3N9Hh8;!^U**jvp{iYK z_sexYtqs?hp?A$AHNug{B=!Jt=}WEnl1*;uV!E1Z{{XP5ir7sc-5PG=1-fK&{zXY? zsA+auexq-Hq_5hpVj>3IBuK{Nh6ku_1ypa;mh5sr5xh@%7Ks*+HEU~#D~5ofF(~c2h9=ALl6%?HzS^B;-`i@ z%S%hkJ4M|a0dY3+40E5)lgAuWG%pcP2AMNQ9ER0TnCgRcXfc2Z z2P@BE#cN9PYTh53IsVSNjl6H<+imkBc$u?-*aYB=_CD3b={l{?hu!0a)nZ|WSxMO; zKf*^tN$P1IBdW2!x^E26sm*IWn%+o%e370?kGY&0~5620*F)GXKK zj!82VVOXl$w^1oSLyVr7scg9FcZa}Mz8$$(E-dv((%7_L=_#9wiBBMu&J{rik-^~9 z$3dGyh3;XxlSjIc7KAxhjh6@bN8ZToo-3xh@V<-UiwGvvwasoBEVd*v*}BX2fVjXa z-h;R~$F~)S_9%50lGZ7|b7K=ZR&2>0bJuX>^y$Z1g)5cH_c`wmd`TK@&)IdIHsanJ zWhAw{Vm~zS0LMbS_TshtDQzE$9`jU_O;s0eu!#usgpGsA^$UP8j<}}$FYx4=ozyF@ zBrc7gDi{G-A?NtB!BdQ2j-2MbFIDiw(C9KnrpTpj**8Hed3j9y%n0X?$kLRZ>^p0z z!+4{^us)#-KiU3m#i>yow(tA37|B8o4svsk@;hxh=HkwKYpqg7Xd;Wuh8SFp@6dzC zWx=jX!jETnd#AwKg~iUTHOz@55w6Ho@D-$U(OV;d{nOA2^{b03%|67(ai`pQH$W_^ zBf{ih9(sO8i87-dOs^N(TwU2(Nu=IZR8QPsRU58=`r5&+hj8rL&%-1I1sDSF(AVO4lQj5qJReS8R~E z8QK{e1pRof&f871)M6Gl5!+lXzY<8utYQS54Cf$yDvykOA8PiiJ)E}l#())uLRL(F zc@>8|_XekM+{n@wL(yeu+R|;)F-4l#va62RI4VAr`@I&%bdl|4k#=R9?H_oLsOo;T zsiSG1*h>_XL}6=ytkGxXW%b~Zo_@8{MWNW*+uSgPt;ND&rq~^E)PlIr;wZ4yjuzRb zu=3$+gmB!dmibhDeXDkTN;lDD^DPx*UId`>yz})3+LjLr>2PanA{C8g8(L^(!C*U{ z-80lxyS+Z%NZD;JAiRZ`sR6dj83f~yc7cytq$3|lmenF@A)5N%?Ee5fjl4E<*8`{@ zjaif8Bs!JUaZ4;WcKdK-oN}kvaXC5f%{DP(CZQyATr@HTE14JfY`um?c|NqWX;%JB zsx2(87DO(Nu?8rkxW_o4I%-QIY4&*ChX@UYiEz^ zSI`Kx9d6NkS2!H|Q}o{oTbn5MTur&YWQ~WI4}PHW_|sbxsimXIr)rlT zUE^Fu93(bkI7Jxm#drQ1@N{x3EuN^Y9D^xt;3y}aSoQom*8!ktt)(fIbtvPFjwFmk za=(exVT8fEx4>8H(%o&$jI+l z?2tB~jxH}RHu6=#Wx&rE$8W7|YdY=J_Dc*lws%mr3l&6W&rmw$e+tcmOI>NU-Dvk# zcdUHqgc*&A&s<=QzNB$d`-`c|>%KS^^Z9V;`f^DbU?lR2u>|*JKc*`#{{U9jt!_x0 zPlcno8-f~U4mz?OBg7MFSFxLmTd3t&ng0NHIYn@LoD6ZA=Dbtli1ip_wTd~Qx${fO zASlB*>ATa^de)7$u-YxuazirRE;clB4p@IW%JDUn+TyC)*|o0aX$gRgk8)38id{7= zD>CM)(c4?bUiuq|-M@GWaJ+kcYhy{5P1L4%TKd#Nsu@Em9%es;4Dt1@W5ZVW){rH< zTBWMS7?+OW_dM9a&kKdg;}s^MdkxLs+3qH`n{#eqYarbgeX;#13$BMxt6Ny=xADNz zT3M@MM6E8~NXBva)tNj5o*kY?j{8Tsk7nK`a$BkX?$cas+H7!`RtveV{$h%gCek^; zBir(;m-e@i+Ou2VVIw$Pl4A$!f^$ydIx8J+*GSWRnKbz~$s-qGCgvRQ0RFhowOsJ# zzi9WYscWik0F_u2We047!CK(QhBdDhMZ4^`S2pmHB{tDB?LPPi8TYLVcw50YHtQYL z)0uuo5NEcU)~`F$yn8o?E~819Tt>hyWMa%Y``jOXmE3r9#uhP6<*mY8D-6cCZNT%K6WD&W zq60%%o5YWzU8RTGzTEMH0hSgB+~oZIKU&+1UDbq1_J+1tq)=I-EW2B}^&=I%W#Zd- zCh}*N-ARR8%QJ0}`RR_81p4NeaeZrVYo@8WnTZ8%hSXng=@{?7>$fmTF0i^-b8i_rE+&?Cm7B!MQZ7x*7kX#w~bv-?pAxq zoSr%y01vNEQCYqyy)tRDOC_`uJ7CDFM&{37yU9G&a+ABUm*P)|7sfWccZHcytFMx9 zS-AOvjC1ZrPfFzf0MPGj*_%{ocQ4GM)ti5|Hx4PYcvd@?Yst3TNX1NPES)jaC;V$m z`v*%21kxKgRmOjG`C`L79y`&{zEhFZ?Jq9XBZa)nHXkfv60T27uQ=)LT)&Jg-$2sK z%)&hU!=IRw$KhV3{)a7>+J4LuF=wa2Zm+1?!{@O1-y@UDebRWy9Wh)D ztZE9E>rv9uTwv=PbA-d5*1_3UzMnYZ6Oh<9~3$>4KZa;~Ob3)4dk zFe@sSnYeF2bKCmUEg<_<$c(gcoPy2$!A_bc0IMv7sQE@Qob>$Z);3Vw>T#_13k+lu zU(ts_ihB^5y!te8SuCwONfvg45#5q2H|?<7PRzFQH_UK%0lKELXycu}_QV(=7-juV z57wi&f*Yxkp;nDo<_jtPYBzQ$ZOpsmY;GI5ZhG@gg6HhNc0KIgw3dp<{{TOkxlaf9 zSpNW?l_TEBBwv?mXOIUhJJWj(Cr9C35*f7n>$~Xu)wNOkxN;dXPs}|XREZf)A%YeM_MB)&sn zbOQ$*(Ql+R>0*;3ZC%7L+H?G~O|pXO(WH3cl0eA8#?9FWtvK1s0%yygY3J_rKjhK4 zZi4DEj=`1Dwr6h62R@Zlk1?3-lWOsn>MH%cq|;n1lS6Q}`?-)I`LUk;KRU6f8+(&9 zsT#-f;DtHdd8yDk6m7;}*sJ%w6Z+CeEOC}e17W$z8OOCumM~lZ%AusjG8=72cV_m= zHqDgAetd3I{b_j>rHapK8IDgTO^kRP{NGxoZ#4FjoukeQ3FC$%nzi=1;kRXy6=?Tk zdbdx)p9!W zd2=$I+4)wA|HZe=@E0!Tc1QOx!r&{q38h5M{=PM%e` zg;`r6epXS}HClVMl>E6=W$I{2e5*a&9&)Fs29w;=OI(t5RvfR)bAnp~^ZY3Ut1APw zm9fAlIsB@-NXj>V7Z}AVy5)KI=BDhC^1!Iyc1(7_qOAmQcsqX_3Mr36>jzdRe=Wv- zl-=G_^a|L?$9khPT&hXsy9AJYpmnQpNMv25TRo3;`q!S>({7`~23}Zv+-98&ep3Gc zc=y~YIW5Tnee;}EsKIceM#q{zb6r?Ek+ho^AxYiWY2*C$qB#qxUc8gjr8#ZY z+wXu0+%B1T0y+~Iwfo@x3AQ?b<`ka&81w^Lch z(XkUJ4GF>dhJ8BMiu_IRr2Z@LQr|a?{{Xjb?U_i1HDA8Xv<-@SkM@RZd-h-Wi+%Ag zMb#kHuBN`48;>*RQTw!Ez|Jv@js<9Zark*-1)aXBr@`7ThpO^kOmS zNvR!=o9^u7(AEHQHm93bD^~nrwE`M+-?Ab&u``90Tp2>0O?oqr9IME+g^u zk}S+wu3j;;xC`w-PfAkro^Pd*`PWQW?DCyLT(pW2G-N z7i{zo16AoEB^`C|G z*O|V>wdFuVD8M{3e|sk+d;0-Tp(mU8{{UOE*L+iXabmJ8H&YpqI)ME0+ym>A$8NQa z98D>2uOlCL)asj?cHf(`ZLX8ykAtoJUE)cs?>^9B@>%@YzvYqR1buo_L%K#!!|hfL z1I1BX+*ym5;{}~sFEaZiX)LcMW{#vD=o~8<+mgPN21++1B;%@IOp0LF?=at1wzKGpKCj-s`H7EQ9^C@sM^5pHeGJCa7gN9WJdx28n3 zFgAUn<6&KrXa4}yYE-gic?MWAfO#FM%EC7-{lWLUX00KQ%JYdPM_sw=j8^=nCS2C+ zmh*1T;rB=PtJ%C4cX2(Hte#r!cos4MDnSZATJctOx0RR7k+9k4oY%E@PTg;5QOrVgAr*8EJ8@`8w zNo{cr-lH5+E852H71)n6ViWhc>w(x*5@_pt4jM&;l>EH>pnvu1NT2Q&R$oX-e26-nP`&KT2Z?jaIHp-;Vzr1X_CNfSj$0q`s z*o}{5(XLy=bFA8vS+d%|VUVHBfD!{>k;p%nrB#>VRCn`SHP-nWQRcxG8CF>FlOTWZ z4uwb=9D|XA&iJ#=v$lcZlgZ3pe9%TnF~(R0Ip_;|b>h1%Q{qHdUKX>HO}tgL+HK^v zloK{Hg*$*80y#WpvXky<5uO{@wHqA*-p*Ow1) zntM$j&vze?2EaMnh0Z;2dg8Rc5qN^zUePAfbqmQPhTXjQ?cIt+Bfmm}JUBQUaNX-C z!~Xyf?R*t?sawhBTdc&Ykq~K6j&M#gN%tLnxuo_qiQZbxXW{{G9rIizo%A9naGPEN ze&nf>jxabQ71ZiF<&TCfCbiL{i%=2mh+JJD628&S;4$C%_Z7r=TgOY{gpnch^=s=D zRwAoR~qT8)ZYGm*Q0 z_(Ni`lFC5U8|0r z21a;2`qPw$6@AM;4}3Epi5@Lh;^Ou>%y_ttHrp9FAd*fSpGx*$4}3_tHc{BeaI>i$c9_RC1aK`^2HeE z<_Dbp4MvQ+7H_p{FA?en-p*UdudUpPfE!UqV5gz{Y1)^GZY(Y#wY9&uZ9?3x>v>;m zl;@{EGasc-X?LdG*s4Q&Xu7rWB|OC|9#2ij)6%niI@;Z=>v5{v*y@r-#7Fj9b!~?r z208u}=iJfC9%hcGe{pGVHRD5co_SoLQdvC)I@Zfywyoi-h+1oixz0~a>`-TG))bI(>E-oauzMcsoZ!9I$3=sAEt~mU_&2u_Oi5|{x zFgV+vEFFb+@%60>ty56Gw`BWhk9y-{ISY>4Pf7%?Rl2)tOQ@NT@4?=(bMtoK^y^w5 z+c3`?EY};FFhN2F)b%9OG#v+2zK_ebx>*TsRw)#-W2gX;QFwz*lTNUIHW?jVh>^Uk z;QA6c;;U9C*tMu@R`TgE!oOx{m;`AOHD<<1$s?TBo{gyKHrJ5Gx|*)x)$QACeESdO z&0uJ8u9%UuHt@?cpcRRi(C&O6sRr}&Yq5;)<8Xy)K% zF}XSC?wr=Ah~z#!@ZH9hePcUCISa943oDV2x<(G}q!IL|&=;9~^eql$j!3T>)VhWQ z!-4DpUjG0}p>KOOj~v$V$qdR=fMj-A8GqS0z|T?*Qopyl&|!wwIHislhQ*dr%H$~H z<~au$?OE_kdEzHA`HKauxC~ct`SNgirF{zA+|(}arLafciKJ#O%tq3^k3BK#T;8j# zyfzZ7%ck8lz=a`*lkool^;U+bV;$D9AZzK`8(2XbQ*!6BWBSuuLtSdlI9E|N?8iP^ zzyKh1%#DHh8jD;Ohdps>*S7J<(8C(A+@4hVBLn!k&17GAyG?0Q*UO!57c3VowXxTp z{{V(-xH^89qJL+-#q<(xW*CYA5_zzo6<5*QH$6G*7bYa!$zCP~fVFId zON)DbN)}Q+SDQG;Jn%hpkHVa7)D1rl_?k@{Qk%(}QnWr<4A$}(&OOLIGupZ-{wm&G zh0dV2K>$_zWNRs;4|J|o1wB--9($CZLiiZ@iNnVln85FW{VT1}KjL+F9p9F%8jukLVLqqx z^shhEblb}(U~OTAS(KR4AsT_~Mle0Aq43m+Z4}UbvTJska9t&DlfO=tG29N{K(me? z5>GYE7l|71(SHm3A8OfO562#xE}`c<%;6-m|ogUTd3mhD+(Ajx@lP zn|AL`Sk;vARrTJ3C7HalxFL$hKFEGh4nuEVxz9?p`+?bMe+~5u{U#=BhglovP|L~B zJqNGpS#x+g??Ti}lYeQfksYnI9xxAXna|@{-VD`s&+H{>H7O*H;1$G236Y*u5uT$M z`cmrpwy`Fh?y@vk1zDa?nSB`UJm;k==uas&so(`$g}J`gAhU+-9lmNyA&mQlQ=IhU z9M>%_i*aq{`B7Y4MZ@`v42+5oPNR(Vs~_9 zf=F%N<}`wD-OGS*na*=n9rPwg!v6pk#g3KZ9d6#vX1+<4jE_p; z@2;XSMR2VoQ(8DNhfvuh;NW|M_*Y5e+kfnT7wQ)3#ldjc*|%#I$vk`3EscfFqj2&0 z2`r=MWdts8Gr%YG>t3u?qK`IC<{ymgjQX67vO*(`S;+x#4@`OtRumS|vdJFiWh{2D zQaL^Aq47=n%cxv5ghsM$NkWXOuUuo>6^FVNlobve_?tg?dVyL*&rywV)4uOINf{Su zAA98)$J4DO7hYA;{{RqU*mF|Db@m&HRZ}Z)GD`j6p!LV}sN;cJ=y`0)s7KDjZ*Q-? zOWZknntFZJrMxWC+qKlpz^U^Jap}{izh0GL{6!Ifu+!~Zc5s9iVm`Hx4ULE0=GUB;C&=pL|u#DHg}(+>ILgoaEMR zs+Cra%#E~zxsL>AwODxJWHKzQvJc?T2mI!vR?3NUP@WGZf~$PXoOB9moxl=AS-xU< z&rm+J*}#qklXuPNdeg0dmLhud%IE8h(Wtp@RJ?<8a*MgU&UY%Eq@UsIPL5U<%gVB`B}g5|6qyNXLonO}9nHIiIQ;mbqgGhiTNoHPA9|MI z1D}y_zk6z?_@qKO{}yO)e{w9!+{S1I-P*myfb zF5Z9o)X`D1s%TbO;6%@+g@QwGs zI+oqcE%zC6GBSGAi5ts*nTG6i-PWsAt}{DvL}lB!sLwUxo*>k;okPbu&b6w?9o3xB zOJ!*?FU!3n$!>UVgbaF*O7-uE)>l_P9GR_eCbNz;Cgq`re9aa0y-1iR}9iXYmEB^p|{b^j&sq_c!7Yx26_&ITPZ<{rTWyQ>HfmzfayT|)P zAHux1;U~f=HP*D%ZsuD%SngF!Qrj2%Qm-TqdUnnadeHct`&P&C1Hl)1Rj!iOGhQ~y z9p89V1Te?B$2D`uUl}3Md@JCT(SFV&vqhSCN^%MfyI5zrEOGCg_6RjcUE$AyY2kl} zGHV)r=h^Kg3`M#o6l8E02d7hyrFl<{;r{@HkK(QD5ZkrC+OPbR8XuhWUB^DXYuhx> ziL-d4K>pIw?d?UBh!!w%(nLl>GlAH84oI&y_(w1NCO;STO=jW6!&t{8zGO?aU4hsb z1L`tyK{_+ed}E|r_+!O))=K=_Vs?4@A&%Hu|;Za;tC^FSl4WE zs0ym1jAOT2tph_3K=Bi6eh`yT!$s#qB)b@G^2QGtJn@db>*7sTRhLnldVcab7-fLm z2RvYP`uDH8JVz48plS@Qx&F@hP;;EA9X+ez8_0HCvpamMPTZfHgTSrn`I$>ig?W}# z*z3EDk3o_8R4Z&1w?=dQ?0l**L>Fv)#o4v-#^J!JC7D*+ZrL|%%K=-h2t^lxT6PWl zy`W);>U(ou%i&mUr?<1XlXQ^Efn^b&)7u&6*A?ViY>~;X+M`OzzEnjjyPZiR7#+@i zYu_~w0$+GJ<@;5uO%2i{t8;A`lHYk8scg@Hfe?#B8^+jQ-FYDnpP;UBvyqP zmE?`KhC$ms!3L|eO(c7~>5D1HV8`kHH7J%K^CLzCoH88nI`pPSmd_UJ$R!Zqs}qjUYuf;t}P}QQcx73*2HJg^VVm@?SV;LPl?NInj!;@aT%E;enWDRWToDt>r-pPE(6sUWt!`{(akbfhd4(CnGUt)NJ$hF~srU}kZ9SV#y0E@n z0GBqU>GsYh_p+*{l_AyEkhROfLg9Z1L2^IG~P(_2FG zTF$V>*ncf!Dy(sjo9S3dU7Dh>(=N2#Z%*>{OG`V8c`)fHB0Tj6aQweo?JqndsCf5M zxRUPHD_hAns!wil4x|7(ToL?3q3O_9J$o&k)DfcFT8o!#wbU%z5r=L&kJh~#OBOm_ zp0hRd5?jX#DV7OKvven}2s??$>}plUidr_44uuSIUrlpwN6()FcAOa>~t<5R8~}=$zye*P7!zXW{Fp+SWLuST3Al-C1OX z2V>Kd?V8!}9<_a>K(@qp%pho0yHSSQOTxE_RhbgoxX@Z3)EK`+`G^Zj6-W@B^y(FA86hwEJ=TE(WF zXrF7;KF@W;QHdg8jM(RC1E*ipnx0bn8eS&wMURN|s4dJZ9FQL|9w%tnkFCX4U ze=`{w=RB?|UYZ7mo{g$3GRd`>X0>dRxgtP+pXJ4DYC50x&7v6AJAJ1aD%bFLb{8Zl{8N2aS>8(%S%Sb)2f zk6iF^>6)6x;?CJ5hIEEV%3%nQ<~);=if8uTuc298X?GK?#hieF4ACoX=Q~Du9=RRs zF|DJ!gfgo`B9nmNoa3*(0BbLT?XOZZWh9#;J61B=T0`nRYL2C&HLNl!Tu64Er3`$l zdIl9;ygjLDcfNDo+xd41n3^JHRrVu-rmxsoYT8bjZ!|3&%_ODNslylg8UVwNLb57I zeqTlQ_VuYQW@(}GBaY*0w#Ec)B|-daU;9`4F%fQ9$t0(F62u#yUYN~8b3Lx8S*_;s zd$4C4N&HVrYQeEyU2fjpBYRn{B9t~+OXW{qFlz7HZ)MOYZBNMDtj@APjHE<50=Xcb z`2wk5cwztxLG->$T|r9~Xys9iVE!PC($5{tdxfm2jO}1##{=4|mfg!bP=``mS(M)_ za;cMX`5ANQ4?umzbXrEAHRx75w|veMXxoA6bJyOvT{~5~ZALi!z|D|=J03CCwTMP)D9Pb^3FPdk~SQ;|)_) z)Ad;`=7z@RH2vPdrU?`r9qNAXJ?e?_q_X|qiM3%}`=gs4VdUcnud(k~*V--9T}2}5 z7gG6PG+=_IJDv`Ho|R`#_>HRR7m<0^R=Ti-$XM=FIy#*4b`ZplxXApgDKgY_DeBNK znIw%h-JyJz^GQ}7gXOM%?(uaEJ+0(7k*`IYoHx_4{KhIxZtqaCx@inoLP&DlhS{{A zjtNogPSs$yhfI}WYfFjI zyw5N@A(4OG&ObhDJuMY)WRht%u0B&2@qPoKsQf_%#L*FFacwM;C{PT0NcPF^??YnT zWwyV09s1jSf*&NGmQ|N&=Z-<*tj`t3pQ%Y4G9R1_6&qJQI@d3Gp=ugr*0Wqp%?zwi zLn0H-dV)I)9=&r?-PqjQHY18pC642R#_ZCt8?i;KO(&f)$WqaO4);4yW2VvGx@%t) z>XF$rHuq7xT#P7rQv*Dl790xVVb||3^l6?OSN+os@XZ+*AKvu?`PGH-BAW=(T`(=e zu-Z=Tt?7}TgQpY~ZArXD+LK=_e`MVm8FL$La(ZwFADwJ?CgbdKLv<#fCF910a_Ut2 z{KZH-RvaERXy&?x8J5F*TLN;xk4&8B*18QJ$2K;$8*ca*{bAk26N8T|;T?=7U8RcV&-ZWb}M%1+xx zc?5-V&TC6S)AapDIR4cip2~QZIoXU}#y#HV9|!MS>}#4{o=cw(jV^(j1Q+uPjC|QH_~kj+ucp%5-|{bsLypAn#I+8 zWovC`A-Y>Q)ecKbms9K5;QqB|P4P4~^ZAz=c#<9X#DjLwI}o@AxsQmREwIt_+l%F} zS-g}oq)>(4a&wNSkSX*H&1rl^qu%IuLL2LNCTzCoR4{A~2;=m}73Y5w{6P)fj4eIT@{KM(raxXpfbAT`U)#C%d@Q+TpEkBxZ?c7?LrcyNsTl z2P3C7lPMzAkDMcyhK!yzpVyky_=g?hU(I(IjvuwkWKF!ZL(>PQPpxxz(aWgVnB#9P zi-j_00fGLey^J^pjLM)LE*`ctIWw$`&T$;}NR-5c_h+!(Fc-y$( zXCt8Go|I@xGvvC&+nDc65*bcwLe|OkI47DpBiSA|i3SR(&It8B)lW{ehT`N$b0qM_ zr!qKPlm73&rC1Qdb8#xeAdVFqlg#TOUte=XjV*LqOJB0GvhMTokVhbU{-&CdEvtEp zHfH33*LQAd)|YK@67XSYhQ*M5(lSp!ol9@1%3Gf)w(thPaqm;JCuL$=3l+L!=18j& zjl}1YeX8AxjW*@3FiQDs6gMW4Elxphc!775&H&FtijI9|YsDU7!dXx7s6(Ed)_c2! zlh}@HSalm#mNrF~cFl}%AswgZ|WK~tEl6tj79wGpRe{}-GFPbPtQq!!lwHTU>IE|H z2ayq#Qb$wCJaJElQIQ-gS-WmtNIU^Ys3taev20bJE%@_9CH*>KPe#df@OtJby|Gv0`g)ySIMUGY>(<3>PX}cTJ#o0-mAd$*tu#vV6>bVVv~MSGte)-d^GZoyQ$LF`9HX`v!h} z-+Swdk|CQ$nX$Qn7-7_RtmF$uXGy3=ti#Qbut*p<#T5HUmE-wWzH$aQ_oAqsPq1Q; zuH*A<#|RH^Z^ouVului?I2%bG)c}{wa4>fqlHKu6a>6~MZtlePuRQA0b3i|p3gMUB zb-<@FSLCR5U=Pj7>HO<2NEZohw(3ZlPgNW+?fF&c?o}dHW!=x-@A%WW$)ixo&pmr* z6%w#21bB+gpnXEp6e7O^s~$DsXY{lb*RF zwR(TVpB@hYcv9<9Sme2uF|yty20-pd83Uc8sjrtlEcoL4;x@Z)s9s4K0wqY{jS5F^ zfy#mIdCz>0O3qeABOm?~eOA}Q)9Cj4mBbo-+`?(q50~a2_Q)CA-yJ_H>$Gp#pIo}p zB-AdoEhgJbc#X%~mf*^TI-DpRp1+qhz%(w;wPW)b=Nx5?eO3E0>sH#w!L2UIWQFb_ zX(DI~25hSm*i+jKIX^;go&;hx`em_%M}-p98ehiZ=MTU~BziwA~6s-9fMfePxwrbPr_Q^9-(;;U;Pjf-(-=3HCq z7cBy)`A5u11djMT{#EV=MR+w^i^(L~(kh^hxEUQu9X+eb@BaX0+k3rDuC!fwqqE*x zD2!X$Gw6<_a4~>L&2&0mo#Ld_EcAU!;#su4J%saL{{R*94puHnJ9F399eY)17dk&1 z%C>$I)udmRPqIu`AH+f&SHUAwSyh;@!#3<5K^=c8`%B`Vk8Gi~yzu-jD{7ZoY_A%G z`BNys0^h<(9CiAN_|{1v5+*b6pWXP_P31PwW8M=_C1KaVY@B2V$ zB>9shupN(XX{s6ng>3M1>;C}Oq8Re*7@fHsAG@Dw=y66}OICJv_g5;-=4}q4K>3)Q z@$HKC?Kj4rAikSRjw}1At|2P1B9fsPech@!$gdBywi_edPCUhIsUvSazxvheS~j%0 zc8vD1#|PSs%X1a((kG7qf}ykbPIJ<;dxF)MrH1>>x>gGu&^eM(EBwve{dlCfzWZcw z!nX0O+c0EOcTC^j!8jQ76$YB{+{^^GK2(f$s6WTw>rQPs%g32MRBV6;U&pmRV@nk7 zUP-`aLP#4|2b!DvZs9EP_H!dHRKh=xpVO%3n{X~7nolcii@OYSji;?PcfLi9qh2{3?)n9Dl}pmV?B0a5apUBg!p2QVqKg90EAxbM-vcj}2+}(9;dRyB`t8 zPT|}0>s0)DZ?3#eXC#oUa=d5DaM{TRo)06ObBK2L#pSln4#(cIjCUQq zK3b_uO9DD84-s5GqSkAtnYRUOw+^G+dmQzq_@h<6yVm@xb+=fV7z8u}i!Q-}Sk?_UFsjm5oCYm`|$kNI-sbklk-MSj*dzH|# zkn0v2TW&|UiNfuLQyn|8{{ZW9YW9n&UPp5T(|MCDEAt{8wh26e`BZ789}QkfZ)|uMWfKt2f<$Ib<>b#GHfd zI_DVXsOtU)ZF*Q%9Z@VwtH~|Hp#-Vm4CDpJPCC~ccV(xw{{Yx+wQ|i1U=UpLJ@Jlt zI6XxhhUcP5scK$h8+DRMQ33M@?-Y!Xep8Nv-nTv-YcaNoMJHrU+nLSl5t>IRl*XPc-il-`ks*qp(}3-^%kP*%z3ualqZr>(Zr% z?HUP4(X4NkKw+GWpZ2lOQhFM*{{RTw9w=CDw7GuCsRBgS(m3)@Tosd!-Hl00Q!m51 zuiI`nHOH6aCf1C{^D}iPJr5nLTFTnu8y`Mvh~$ll^2(610(u7ZkGC>5-h(nYHwiJ+~2`-JPT6+~?^AU`C{=(D|16!?7#)b5ZHgteTgZGtCPoWkprWu=FSOtI@?J zqRxwj^|-_d1a|Lnf<9E-YWwec^C>hV1PNv z?rN<5AClp&B$EFCO}g^ecu7f8Mo-;1>z`a!MTdwi&fr#Ukz}Z7{{H~tJu6DvP}6lQ zcZF6xyEtbo3b()0=}T}cO>?PQT1Re?+(xqvqEjYg^~ci(t#Y&YiKNt}Ym0kXq}_uf zZd~KI3P<=?O>w78_PcDRx6TP+AzT$5de(isk)ZoKSzF1tWA7^a(pn%mySXgvbx9@j zCWaDmm7Kp^<#v(%X|d`y6T3$YQ#5LTd4!LcAK}k)?^?RI*=4!iZ>GizH$qvRz3V#n z!!XHquOu>UQ@SK{+2yhH`ciw3(2nOzYdcGHfZfKhFmbi^07iPRTyi)$=~nM_>&;Hp zW`;%iPU#DwJHIN1Ei+Jpbz2m;nm9;4V>v3HT#kN*mt3Apn|1Rpp@voYM%CH~^f<>f zgf~sT)U>^RY2~+?86o+1M1g~+u>SxiwJ&wcok*RRQoMVBPdz(*2XFJmSJNe1Nh6Np z7MZelH}`=b=ZdqhYSyc#w8Gvf_}T&k`>;6V3atjO)WPx_Su#l+*7C0GD=b;Vbm{&z ztEBi2?$$GK#?eV5ddRy^9)pkYtUnHT&qltzk|u4zRfCvZe&n9H3;k=T(_y!Pe8}14 zhaWEK9f9w_>?%h09GVrY%O%9~THD;?04(dcpzn{zwR9d5(3sVyY~fR>$o38m5~Ml5oUI(lG>N5C_(|h4EWYb#W{)IP)Yj1LT)ZgQq{8 zT(Bsc1HTb+zSf#wynq`vRQ(=M@ls`~a{$aFs$#aOo0EJ%h5fR=Hg|m;D4`0I-MeXAuTR$@&n2*wp%!a6I zncYv`I5-%`y-bl5l$kzOQGvz)pxVi0sja=rn|D)^e~TE;Ps*eZvUX=&$$_^ccWyKI zQ%DIkxW3yvM-MXKl~CVY{&gE%Ze>DwCnZ>NJ*w7?c5JVN+d?v-P8Y6v@ldV1Ur#iV zuJ5ytFoDG;$1Czj6WV+jPx-#c#a>Hh%gt!qs*rMk&*%N|Yxk@DxzPxu-KUF0^*Dw2@WDRksDscLT{F_ovu8 z-33+Pj-w;%TlQ8qej@P1{{UvV5UslIiWwW`wv#>Yj`^hi&W2FZd5jx7RCCgctF4W>W{@czSA{wC6?aRzSAmg+ z)*}jY_YZvff-4&(v0X~mR+C;_EOC{RUYS#YinuMKv_?0vm}K3BjnL#{q0dYY)}{$> zp@?LjKpp=8)qvYT?Uv`Kr>#MIt;2VA-g}0Phb+hD$Mp894sA$7DD?Nh}|aN8x2I_@gj+%wOn zK9wnj-o<#MQi`vZ^6&vTyCbus+-r1$FDi& zr_5tfN{)Eo=7q6o9zM8Y22XmDAkPao%#2yGG21+1oLecCER7%C!u9u}Q#XPWSM%fE4eR4bTQBEXu+Msm#fjr~BD<{Lc zO~#3-TtOP2?B^bIMVtLw5_b>Bt#SIDM)SzgfZxL04z%d*e8PCzxa9hptt-e;RaI~g zTppDqKO-FHp4&!gEyU4<@oVAT_m6Z~ZSD1GwD@zmprXDnuG-sILvUiWC$==C>aaa9CX3OOWdfZ zbCE^+Fphh9WNU@a??KdXYeT`lE7ZIpsYiRJ-brV8gJRBu=3MpbQ0l%I);uw7Yc`={ zbz=?T-vdsAG7M)ueF*f$Rfa$t{&}$BR35(FYHYfeXlmNM*1N7teX3nab8&ShW|6R1 zo|zc>SJU4FhMTE;IMUYHzS#||l1CJhKo&({at=EFHS^!Ye}x*4#T)5kvXTpUEYL|j zlB*J<*mpl)t$j1#FA3ZDC&Lz+U4rh4IDjo6JESL)PuG*|2%%^xd7RY0wD*VXptyxr z^5W{%-ZhOEmMTc}=bkIed{Ob6#NHwCKB@LKyVL&B10&gphWKDmN$cnjEI-1%b6)rn zrr-QUhhE2(<^J+$B2A)a86nR&_dIio>Fv``)PTLSlFsfco(!;&i7;?SPI(xhowhtn zUGavs@YmtKgKwqBBv$v(Z=T@CxrC>pWc1+l>PY(2ei;0BUk@9I_30$JhT)8+T<(}R zaz}jeUAM>Y99j5F!jf93X1u;r6e^@{T<~A$IT`ge^S-TTZ)ag=AiQa=CI@_2+vMXN z^WK29&dXEr%sxHw&atX)TM+g}-qk~X@=n9?AZHyouMWJuhB?~RT1JxGg=qldMmgkT zwR#PvgQ$-WY8tFI`>gC@VJxM<3GMagit>8|Httt(JD9fTJoD>aG`BOU5#^Kf64Gb*cmwg{n(=)e z?n@i1IiqnDi6GiY`u?@+3%1r6RyOnFo0n|o3`adb&T3={YDglIIOd7G;R`r(5FdBH zPp8tGb#V{cgCj^5Soj#@JmRit`g(nWYlV_;GB*htrq<^f=Ohp@+-9H%<}668zFFKd zIQ*(hDPBsiKJPka+%UxC@%5-gF{G-d@5}P@x31tj9Q~jHOrSd8-_<6c|84VW5ISa zKDi9B-A@BLo#nnzr>McsIKZw?#|>|z__E!W6^2P7-s>3Kyq4>au6l7@w}A9}eMasT znrW69IV_{)Blx-L#W`#dz0T75^ID6-(tWXRn;4hPYkl#`=ei!p0CeM@%azc4VR|Jp z8;jcrVmnN6O7ZR|vkrRak?mVrWu?rzF08`gqm#{8gzF~Y5l(Tm{v2`Avn_QEN;{b3 zy1q@SaTu0AHCP;ueUEWiJqoeVXxh^1*HK#A%wbuNnIjns2>S5bxjDh@>0Lj=(I%&; zNWw^=+!zUbt-%NflgRWSpT$2&zTB`16I3Se=Aa)oT;)0^Cbe|8rL41>2&2@QicB<{>O>RRhAZHyq_TswR zt!6z^(&Nd#n%8nR3O3fxGCOD1yw2l5o5EHwubE_xBeKWkNL$S~7$1gBcApNC4MRy) zGfy_4r}uHbHW9Spjyq>Pe@-f8+^)JBdR@)OhO|j!)h#5{H1+0D8ktSgW6)rpam8iJ z;b|@A(=MSm5w4)iapgP<2a+3*8)+ksgmdpwEc&!pP{(m~bz=>)?`Z9m9p6&JmG51n z>9UV5DK20>aPv?$H?TaDk6-YicPU2WU%|2K@OjN7)~~yBY(>u<`OjSSuG%ZeRi-xi<>w7;@iR-0QrsgPfP>f9;T|<+RbaMDqLI{W9cGB z!MHt_sO!yIv$?*4+ilrfj4st?z!H1=dr=#@}**~jT7OB z?XSd%8chz;R2ISa;-S#=i*oYqiI;x?Wau;Lj`cRI(cfu|8&YPG*f5IXA)I?-iqz8D zNhMSEnBGY+q%r%2M;Z3_qp3G5-)L6aTOx^>gJH5c#(Iu9s@7f|j>xojvc@*KcEj?d z^x)Q|{;{yKtc?!S!sj5L?+pI{D#q0{D~oZuZ?m&wmW+a1(?3C0yOq#y{36#4deN*i z1_S5A4WsA@sit@|m@{{4A!vBYoRN-|4X&@2UoGTUJx=3NNv+AF7~AY7<1h0wNJbRr zCmjj)p(~O?nv`i{xg?W*=3&^W$*T&YC`%P(lRKG{l|P1R4-#Hmyb!Ex+om}xM%)Uy zrRvecXNYZ7l>i@?tmg+J(_NuzRpwo!H%XqQ2?og5Y<;DV# zbM@mCa)OIHtxnp-Liv(?o=Gt4zCG*uRt?6PV`&VF74@Xk^SUlj1I{pgbB;YL23NeF zP(d_suFseFlN19p9X{Z+GNquQnI)VI1E z(Y?YdgkR#vae;~!n-voVUmNHiAGM0rVz`npRwXIDfH=rK3FF_7dWTefHu6t0!q!V! zWEq-?bJzfQQS2(r#_LppA%;uMIhIizlcY-MFnQqhIG}Mldu>`B zMWktARFOsku-sVx0C?l2b$VUCk`mrIr->C*DN*-;>(uer*NWt{trkmkjlS5;k(mR6 zI3E3n8T@Lz(noiCzhk(%nRnv`5@Q5<9P`2Spj+;Gh5E+UGfQtIHx{s+stkZK6W8va z%CR*qNTM~uq;gGefmq9yCp=)O7(az_nw{mEvaYB7sc&uf)<{r?at22o$6lV5a^qaL zgH5w&ZRDOgz$jfET}M&4WPd6IZD`t^oC!3SQ%M_1l@O{8gWO=}HAVvk!IT9}jQEdv z!x7JH)mwiR+W3a&$z3ufxl$Enjwam4kVf3&wOgI6pt6oRt)}yvKfF@Pjp{mZeujbh z6|VF<7^9J`Ie+2;O{(YLJt{3XM!d9+KkWJBf<-tn+cLb+{R0dWT5WNoYEnlXy_Myg z?c}ZMdCl%ODIcMvn_km&6y9XKlHSjW4cj9$r~TznJ$qA$HZVRWSnGO>Q61*53jrxwd?j2m@mWaOg*;T-Tn+d^qV7#_M?@k(|i!$eS6r`!q z`D691zlgV|Q1LbCX&&Ruxoxau$pekN_rL@4u6tG0zq9V_V~od{!2HZhD04nF}=HOqPI<+m^! z^V>g<^r$CUEr!=^%!dc~vsSDgJDZqey2`|)Wx)Bi_s6XYO^;BMQ}Yr%$+g!x$MJQc zZX~uZu*>M^I7H%7`;9BnPI6(g|v)WIQ`WXHZe+1TGH1KYh?TpNEj zIRJk~AnhLGtxqspTbUBu`ADj*!k!L3v|d~^w(-K!F@`of7Xt%5PCe>t)suXZG;#TC zPb=HKRc0?ED+b0eKf8)f<9aIVa!>NdaZb#8gIvQk$ICX}cM?ZhTc>B|Zg|K!z#itB zw$a^By`$UQ;Pw3~TZ>OEzFq$SHZV!g=SZ(Yu!*sPgLX1NImUhHr(Ih<{H{+N^F>ae zeQj}S(XY&Mt;jgyqe%W=nV4i`^GdC?*!}K$5l%8GM|Q~e^sYX-ogoUZnylVp?IW58 z&hmWA*CUQiHKu9K$#Kv5utY+PJ-Y_LkBuBzt{6&ih@sj0Q!r0hU%j!@H>CB%E=_ddar%9pA+5TJqz> z+Vb+mN2AzWDS{Lj3%eaj=RUZu*TH@dwD7HhrJaSXqirZ!Bmk8h4a5wZIs)!_$B%U1 zAN*a=%C4VhrP#CQ>{8tT^Y;Ytjt|q3RsR5Gj{`|-;!S4e;hH;*H~kJ+w)K74B)7IY zeQVl0rd964rgCfM-;Q1*)I1;YPg_klRJgVN(nU8uO9k8t<6+0J1o!098r9gz`1A2q zz9;zRMu+9ow8GZbtDJ`*{O_E1BfnrPkBIp)EStz&XFL&#u47p9)lNA$?rXI8LE+68 z#5Y=`+U(mcbgM?VjxxXNU#HFO)AJODcAv7f>p|k}S(fRew-zk(9FVSo!8xm1=j{vP zFNnH~dRK-l=Cf&J-yfAH@7)(XGjss;JvqS5a(@RkJ3F0AQ_*fDlGfYAHva%+OPCvL z!u*iFn_GZ>opD{qfUo>3@LEk$XVjZey<#ndii*z@ggIW{DQtB01GNLyo|WP+5o#Jg z!t0Cch+&HLER2#xIr6}LxNPA1lhfL~qe{}R{uO*9)wOGz&8Jw6MYX8=(7O|cEu3^Y z=LEN$`o(_!ThV&ej#{kN!PqGx^AHt?y!Ez zZm+eO)p7s>md6}_PADY#n_uxg=Zr6w;`&dtNwHzyxA<2eem`32yc6*H>&8D0b*qbb zEn4E*Whia|S1O|{s(HbzzXNzP{t{n_c6waxExzdtl8uFmD&vF($n_x@iS zgkQCMk+UH=UBl+<-nXNvjJMRhmkV>WHr?33ByfI}71jR$*+PXogMHAwg+%i#5%j~a zI6bO3Kys5h`HG}&Q{NTQrHHw!;mh23qQ}mGZX;O+=$P#f`F(5DbhU3VM3P4oaLQ#= zJODHIN6=>(^shDWewhZR;vMEixAJ3WP{5MJ@Dvf#*FM$WM)1WFsq-d{^SPDzVb4SA zeQG6SR87qzRJzmrT+>5uZGNi9%G~E@$mxOnT+^>LYs;Bc-ZTZWk|N_gel=ggx;6Fx z0Ee1;Q|12vXUmI)AAUYF$m^P#b0mgD`$Tc%?ms8q`s4Z3txDfQ81)&2!!Oul#_g*i zW0C9!_|<(@?(<2xnmHhj84&WM@;L52arji%Y|@S2YK^n+`RiRtRS+w?H<;+M7dz=h^ zlUy!?qD?I9j4d7r*-0hWYW2Yfu5bq)mC{*w0dw{vfz?()Iaaxbub~eX+VkxhDZn&C|E1L0u*Nt=6%Azig5}xw1J^DqIc&6ZzLK z@Y}-*E^jX-k|^O+Duv_PV{Z6v{{Twvbgv0Vt-`k#7t&orZxV}gt^S}B$pfb+xu9kJ zH$t`5^k`#|EUqqNlX5y`Hx>RY5_!f3JM+@7_*%)~)$SyYAG17zVJGGQVC~0z)r~L0 zve}s7fFs8of4ed#U}g01a<%bu?rNfg(RBcVV7-@qyNYlG5ip;;#v6 z7e+YYo;H!(GZvQs@yW-pd<@p#gy4c5LOnYAIW8W>RibB)8;5b9#W-2VV{cg{E+{{TwrbY_L4StFVU6GnWs--#HW;C17Uf5NAsM^mX?MPX?&`Fey+ zbq?rSG94l#s5$la{Hi|>B$u0HXxDB*CSFKALtu__YL1F85?Pwzrt>2oBrJDE%kAG8 ztqU39@gYd=n{?6jgBwA|xHTiyn_3ms<>l&mQ%B~soJ)|LWaJOS^RA;#*Y6b?HHOac z$CAw>ZG8U#bsMLz1oo_3+X!rJ9&0Eevyqem5-uZA=shc%vDBZ#(Jidk7gnBYVMvd3 zZIhq60T|@tBZ`}K8s5iIulRl~c5^g#>E}}^V?oy~5=S3d= z^|CZu? zS)}_ow@|OSNrasKgw@O2nA!+rj(;)o3P-zgfO=y*)hjJu>^h8#GRX=|og{=Zany{A zesyY34eA#*vCSK4jSBwqBaAd>oDjd`RP-ILXa4|ZE!Ds+D@C~MCp(n$&(gHD7-Z3G z&z9dLpDy4y{VEGP3#$m8dA6%FWMj9zLwBpn@UXgQq+^xIJ6q~8#(n5og}Rd;4@s-r zhK^|b-@HVPv=9b!pXpOiXmp~{>I>!hgAq7f<%hVD_K+~{3XkM}on3+{ zVz=7axGFgP=gOVJ;#>fT7qj~ES=ZPDLN8#4yvcJIilSC_441;Co(8-?5VG0QjkKcz;YeN3CL6t4A>`pIVb zxL+?R{{ZXFRK4*FL28#U+sPgzJ5f#)4*YvomGjB{k`bWt?jvC&WJshGInPe#ry{G` z#}rn}=Xst|{Kt{TM@mI*bJA-v>LL8=Wi5ou{{AsgNJ$4emV+RlTzNJU?fe^z93o50-ZG&~Z>pqqWw?TbPz0Rf{NWf$M=& zZ3lkk_VI1)lsn;=P4lV9JC#2Qu@8zRZEiVQOLEg3ZXtH({GRoXHk_6aH~dYlCEJB? zigyn{2d}PazwnPVc9F?s>2PG|vPJ=4$2c?wjP0&A>UKmr&&^Y4J&O1lW<@C}YWqp$ubQy+v8jCYl==8rJG-ctaBE@ZvoBjEw&P zPL&RkcGh~tmrRXrfPc#=WgEEX13iCEE3NSN#2+HrRBvL=SjOinxb8AJ=}b-ZDjyi@ zCq`wwzSHg_h=CDhP3hQUXv+2PS(e&ez16>*vRx|)6}pnG>(o}hwcdSTEXwy%)ywh(-EhKEXz{db!;)Sr0JQ`iB(@3n7#!!hDF$RA9 zh6q1Oexaw^$D-S`(%f2F!zj#Fq!nh8s}spX*)7sGla7FobKKTHh#GxN#>us2*gTViZv)7M;#S?t6}hj^~go(7Z!uY}fJbywg{K6o`|aRk=}twC91wI42dt z-FVs^J6G0i8y$&yuOT&p+C2Wqhm`?d5^ zADNYQs4LJ9rDt0+Dlj{pw;s5_{A){3f;g^r<)me8!v_lBkGg%wtxDWOrMvr0#^zrv zGK{LOI321vWmf6(n8(YsVsF{t(CJbM5{nqM1@jw|vYS8?d~u;Z^7& zZ9NU!tb4>`vpEZldg7+j?^@dTcIJ(gWmta+{{RD31S}(8EURQ-?fw&1E!CNP-!FWM zaf8r`jrR>Y6RBXT*b z^D=G01Ey%T^aDcHILwORNC5up5=YjwjKV|>v@c)^r%YKMWZrJw2|tVX(S7@<~`gKo+@OuZQs0BNXY71odvJjrD+R= z8@BP)dH(?Qest-s8s6eXUBOYfIL_fqL{TIbh|@6n-*?^&+5D=*>G7}1vBs^CNyqZ4 z_IE|sYq1|g_o{C+DEXV|$3s&5%82HHObg|-i^kkGGxZ(m*3w;R(kYSF>3V$i6CLso zMgCsg)v4d@kjSd>vbQ~Oa(!xbLLe7XHNzRLl~*}aAI1M7 z2buDLoMBtAqF}eOK4Kds1%fX;^U|l#dOZqpkldGMIK~EWX#r^+b~hui9V#i{HV^m4 z)FDcPoxYVcafOkJvoKMdf1g?wfn{JAnc6uyX6kX0e;TWIBP;D$Iv$6htB)IQZgSi5 ze!Tva%c8FeoGU(lX6@6EXnK>d%{Jr85$@PBFu-%pdk)oUXC_u*)tF=3(x{;kGZCG? z?EW<*68xX-e=Jn$QZGm&61M3TGtUN!&Aa{MFF7D{MH-ZSaTV8;p>kQ6dT>2W22USddZ(veHPmt}jh2k@$6B3T$znPv$prPTPgA4Kmc+5Ds_x}+v}5k~=AqU!=ym-v zYkxLqqqtqH(YcO5JK&B-rABt4`=Do>j)H`j4jFfG$Ya`*u)PYt6!>eSctguu8#v>d z5Kv3YIR~>I=ia&kimQ#IZ~G&u{{SYk#;C~H+D_rl21j1CBV0*yZr^7mWMDwvI241K z>~TId_|K?a>Ux%e;e8KK)HQoq3?^yNM{NnmExRBbbr~b4O7fWg6l&UTov&-YGP7?o z%@$8A+-^56N`QBaJ3NDo-v39gp<5iEfrY{1=i zH_#qW9D`jaz^?-9#?^dHrP%2@i#xhS9r-Hpvi|@QwlT@CcJK#@?!0l~NN=yKjg7(H z9T;R1q=HAWs)%ZQ-|#QPTBfn%y9=uuIV6WpxmLQBu&WU7ocHIZGwokV>UY*UZRAs4 zNd>%&!WddoF}c5mbJUZLm2XGz<&KEA4`&L(*V7qhDn9gta)0{O=U=pi%z7Mt8@hP> z$m7)40h<^-^Pb&*Djl~cc6PtmHZkjeYIq}Ct)(~p*4ll2dRL72&&IYoM~$wvElS;G zdk2=<**}YJ3WvezliYgOrg)cMn&#%}!^46NLs_ zz07|EuO`;ETx;yhB(n@Rl1l-#NbEQqRFBm1Kln>y)4mhy8hE!=^JPiI+4;!NDtPy= zFR?`=@9aKYb{zAM#=A?1f$;tDZ!dIdQQOAP9E^7;<0CwiTOK34{?e8?ggbV|sga$&=CNmyk+#Mk=E&h|qWTbQ zcp7sbi6JYxGls(|lYw5NsM*@+%_Xx)vo-?;LQdW@*Qaw{b?};Xe;LE}#c3_!8Ds|q zm!ThCPvu^zs_Ev>MY_Gxt!^%+v5*-c7gol=Nki=4LRWwBTTc z80r52)}kZWrk3{b$1+B&%nslP;YKO;vBPyL#EikFJP5{Jk70rDQap1;p_K_-1!4zU z$MG!f4w&1)wP*o&1^~BzpsqTGnt# z)@;6P)`cNn2n+x{$UQ!l&v-c-Q?`!W%pjGd^A*c&+IM#+w|;BAyw$Dm^|ftbC7)^l z?yfO1fwXh@b?a8FLS0HWFiD|mvF=l{HYI^V+s8cmXZly7cy{_T16)aYc(JM#NRf7z zIX@}w)O9t^+eIJQt>KNNnPm*aVGLtl*(V%-^{PD&#H$Xlw&F&QYZZ27+(^%E+GpH{7Jgh^sCz&iSA-pSVa`YHnWk&SohDVrPJj5Tnt02Kl;pe&$#}5tD(@W?fgBVtTS$~mf^uNG~0^x2P4QmGHCfVwC z%_5^b(6Xei9LCYH&Oqaw*HfqXixENQ#~sA;<(4*InN$v?y>VHd7Wj2*uM4J!N?Bx9 z6FiZPz&PVSTGrDhv+(mxZ#j}Hl?92BKX|^?4_9C&(tLBL_^KAQh+Wy-Ln%iM8OZ~> zoOJrt`&}drY)K^2-g#qm5pmDgrg2zWh5R~}vj~Z#w`dplkz@BH5y36%P_Daor}&r2 zlFn}<1;Gk-3=i*fjP%6?EzY@Nyzl_yKpemI>q%=gktM?hmK8j4)Pd_;Qr~~Xv-i=o zj;**!k27!|UWf6nPTy3RDn$&FNi3k4)_k(UIpa9|v)Zj#v&|OSnY_jMq-1}W{Pp~( zDAx1s<$c%I_e&hD^1kB10rVfzu2^2#B$7uXKGx+(JGdP(yni~#lT(`8?%ho^Sj2n4 zIP5V>x~JHY%+|3p=ZP>z?!8E&*I-?Sf498t_N7?PK#7#0Y;?fMs#?a9!p=8oKh{3n z=k8QCx0V-oYb3vDw_U+O10Wvw&o!f{2rcc}IA{Ap?(-3x6=B;Rly%Ta^fENd6kE3v zN9RQ!NeJ2vZCuH3akuPOT>uRo%t5pC>@oV*O`W_mZcpArkWL4G!jJ65N%phI+>N+B zN4;M`>D1ZOyooKg#~Up0oX7_&lkJ~sg|*K*<`}0{+Nw!G#b9f8D?X*>Tg!8{G89Pb zv=Tb>C-bWj85voA(0s&EjyG=lno8uFv3TMeN!l4L$&EkNt~TWQ{uQ9UF0s@lg!wW^ zpyA_L3FE2ft#Q{=z105zXt-4@tFS0sDfhtd?rG3PWsHJW{<^g$ zr>EIVyX`(}0g$evlihKeo}h>>b(rlWP`3sb+zOBjWAp9nPm@tgkfU|1%;dXd1!IzW zbNKY84-i`2Tr}4fHrKKL01uad-S{B-R(7Ltr_Vo_ZCVIh<_yjA4xO=zS7FPk4zY6D zj-WI4XxA82Q-ViMYdx(l9#uu}3-q{$lX0ec@pDo+l@HIp>Z#T%<&1t66t+;{p^I=f8DX1J0w z=W+>Ql1H!j)^(<_ac=D<^^{i31GbF}Q*0&+?^o zE>SLS)$X0KBL+Xb3_qE!pHJ~UwX^Mq{Ypj%Qkhi)uN`~WHD=Z~_b~mI;%On6Za#D- zA{(9#f1O{^A%++(E!y#;5;HVrM_d3;PjgTa*y;4|5m;Z}!zH|GftUjmrc{zSIPF&M zG)*5OPc}#vY=fCW+6Qr-1#@-+*G;x}^HxoxZuDKvf!B`pVA|YYs3|maL$@le5mx?{ zR_Yt-bsih=y}q3TO%?6s!aD@SvPHCKkb57;rE2c}&Q;qKO)8SC*xk5$l|16S!E_YS zk)wtew_oCoOL=5BKX)W|uB$^YYp0mwc*Jpy$l@m5@1J4bq?aD2Uk%Kc^M_Wm+xONs zBq;0Gnq+zpofnvsLjGeGFytmeAcCU~S4Wj=9f6Ry6DQB#D04 zr`%;q?U0hHKBpaNa{;tkIdu6guP&@UPbL70ms*C@h{sW|2n&?fF*>-keZ; zA*V;;JB>=#+VD$w!^|djI0KKA6OX`ms`|aiRV9efH!lv z9GdJrS92we%r~-I$jH%zRk#oG4{Y=F;~m9f{7LaPm~@z;J|Kd{_Jxuqi!C5Mn{u$l zR7hu?C8vYZNv{?gi6v=RTQIkl7{<_g9ppYS$?wH-cXoO_nkH z&Pm2I)YqbDdJNi%-4@p@E^O8j903V<&~uVT&_|{K8Lk83b)Dq;ER5E=ZPmN{%OpF} zLc=_^Mn|Vy{{T+9Z04Eaz94&bzGd>-J+iSt&KZ$;$0MottlO)5MAf5f8Re0rjPLW& zQM}Cd0Fi;}YHfNc7T@g+3dbV8!U~?f#Z%K_{?)#XSf#XNoX9(j`qytuoV`kZFY#UV z?}s$~F7ip5#?DEuZ0&asE-7Rqe1LV!ZC_r3xl5LLBT&*SwsLU4FCP7?bH{BR&C)Dt z+afHAU$0#C{c8esW5C+D7%ay$M4Q+mxsgWQ&5l7nyw#m1U6<?syeL%OYUCF9y9(0AI%VQYE2ePF2golp02e9FAM_Op3x#3;e*P{*XQ zTxBuk?%;Z7rD#}rZ8jZ7+~ADk9qMnXMAophQpmDpmy*PupHF&i$L@cJ4Y!Q-Bd;}b z;&RsNzHZfzI0p^?0N1MOyXn{6GG>kV)r6 zuen=pLtqiKRF@EW=PFkV&IeQJ{OPT4BoUVCy;yot)NyQ_ux4%BPDTM8mXa+6ME+!s zFu!+#xEZJ;Wpz`vkLy>O;F#7nQ6jHWc_$r4YIkEw`;p0}Lkk?J`GCd=AC)H0D6Z1m zqvVjskZBek~VB_wC zO^LU6`AE)vY3g0`_f|f zu^6OgJC&I6p5Okuh_(xE%LeQ2YPKD_pKsN07WWN2NM#*9gkL zdAPv!t1+QuWc5A&0LGFlb+o(k+Eiz2I<5-nPmiZoI9^)O955)6R#UA-sV|N^TVxf}RupOT*kXWDODzzV(HOx&ULu`x4 z&hJX{FWRG8^1MA^r}@mXODSov-+6YOqyGBipGxVx2de8)c)P?O+Fxjf8Lvcod`zRu z5de8!GINkm`NsqB#uxav@vBn1*F~%{XT}fgsTsxS8W)E&PYM0I zT$W8r`uSOGtfP}3V`2PkLC>M|IIc$NyxB`1nRjO^>FJN9de`k!{gW=MrnR@(+V2c5 z9z0~IBr34>=kUdOj+bn+Uq=*}RgsZ!Gsz?hX_a&657}`wt4{*li}vztSnktprCp?g z31=O`vGwbW*1gw{d_^COv^@$9K0n_?jd^raa-bmZ#yDNLBPXdf+}r7*-U!#r`K{v- zkC*sB0CE0BLaha~w-*m0!rK9NW3^R4rajb^De|q z<_*EY2ajyF26LL5!(K77_^yy!>e?BPQPboy6q*wyyfO@OkJE6;;PO70u9_M2-xO%< z(A-(-Hstb9iBKN6T6*UtVQw|@|LiptXB@<>+dWrWNI{h2tWG0TY7Gzv-Qx#OOmwcwYxhg8*G;%M4GIzq_1xKW%hKT7DLXDvn&=;{>5i`rCYMw3~7{7n|iVSE_lbidAGxXzr+(wAbAmB8(;ga zo(*~>jLmSY7{S&7V!pH0W4DswR}9L}3x|$ObYRMPADvY3Y*#b* zPf%FeCRkH(4<;LLsLxz=#Z*FCoPUAz__f)sRz=zwu;CwW4l~ECb&sJm+RDrJ7PHe$ z&)J0TJpTZhS0oTf#(3?t+!m-+z04ffi{ePe3)W-Kw_;>q4-p!ZoPDcD4sH#sO zT?k022N8lCm!NpSBM_H}P}a3{=|hld5WwG?wcopy`O=1S$Yq zq4oW1p3xnAC#+l}J;aySN_HcUDWqeJ4a17-^sf)i;)^!DjL9|O8!<1;VPX6#M{lJ) z3cEG*Ni{1wcu^o*J9uL)J9&lVAMh^2@T>6OYFF|{3e5$@qHz9Xfn;9be8)fjs-+@&ysWmM(P_~!t3m=_pA?pzR;7)PC;4lCj)ap{y)zkhf z-*`sm>8$1ZJ*;PJlb1O?j~wJ@71HY86|ME6E-&M?VRaBQ%6SE`-1Xzvt#aNHxVY0U zBeafKFCma`4|x~wfyf{Q0|aB%y6+l%I?()Qqbkn~_V)r!<{WH|_~RsUdi15U7h4&+ z7sP!IcqX`;baCY2ital{bM5YHtkdp{w{uM$#jVAi!v@+9%ssfTGQapsb*AXnwzlyp zw=!Yc(et!-Q@ad72fyiEUx0i&4vD9=q?Zcp(vl{QEGbjY2+wL-Uqa)1oo&XX-(uTL2>>C0>Hy-XL*kawTg>}1x0tvKvv3E{jI4egw}X-FYD=_=J9fGA zzIHo{zZoAvKyvplH1M=IXk$fVyAcdvpK6*J)R^(LdHyEB&*xby5Y-jqw~<*u$Yp%C zKc0TIrQ!bo4^69FeVJ}yX;wY#g|Yc&sT57*%l4_2q=iU4hi%`0E63wd+1yDyxM(fr z5tEK{{EmN0yQb+3xAH`-9BjD_xZ`i@inFBnaw8?cc8V5Y3dpi;EZOPOjZrQ|dF~^N zd+bPdp#?xKgX`^3*lPCo7A$0&Yh#dpRzCHct?91@pw{r;d5z{A7C8EQ9Mi_BFt$rP z$0AHf-Q{GAA70dMJ9QTB?QSoj@(hzkMnJ~ga&zAXopBhD^kie5|>s=Zt zqAK1?FwWLj-TCyW?sN$(E%vvQ@^nmRXgt&c+SW)FW12A_9n_87(p@Z#Y~Q{Sx{MYF znivq>u=3dze6~@7K*1uRXw+`|Lv9%1k4lox!s6}%S)`d%5ah2~%hnp=&eeRb6;49q znvgCS4ZNSb8x;pAB;bSTQQpNJuxDt?NUOMyFm3kf{c8>NDI}StXm*k~Bm64mw!8j@ zH$!G3+)FE=-g{?vT4`JsWFLb>JB{><$q ztkJ5rL%Ai4hwKBo`P2}2^4&GS`;cy3flR=nGYSKq*e+<2LG&``Pr$0{h zj~|(98nZ~dae|CK^L8NCm5#9(5yu~$=1I)OWg{c`(ix>^G&c8mSR@SDeW3u!^);a; zva=QPqW#jZ%v6)jV9#*cf`7-=^lINCta%a;bI|tVkIt{@cN%@Aqek(}Bp)VBn@_%K zwXj^ff8y&IHC8szOy44?l%VI2o8`&r>zcJ~dMCKu^D69R8%_)7)Kyz6Z64<7q+7;~ z{I*ad+RCl|(dYToQ$lNth^`@%bE|Q+`g&wkhf`fOcCa!mHxq_b$=$;A#}zs8V#{o+ zBKh7*76`4%liYgNP364WR0|-EX(Sm1T{msy@Ny1)YOLDrwT;@w)^_(>lzh(t47v2% z(vDk(o14$B-93WGXR1jIYy0B^5{%!79edY5tWT(4Uq`z7?N(3XS0rca(AI)!(_a{+ z7IH&w%-f|Th65Z75y|@h0Q#+e!Z~MjyG7;HGe*UkCE64(W&m@~=|P*^!|@G`)Y@!k z?Fkx2fHKO*5;ycerE*%M#j3^SUTPLW?wiX+EQIH?0(x>QvDKE!%GP^J$py!p8A%FN zi0y{QABB01&w=gl8sBtw*0Mp6tkE-+P)Q#*O#0;3kqK>~cH2URdtE}^wOHEdZATwy zU8s5BZ9RRDHN$*I@QmIZ@aoL^h4su(hAkih-488hX_6KraTw>*=~$@7G%VaO z&N)1azvCDh!(W;_a--%>%6Z88=Bq^Uug-T8I%oM-o?1_pE|*eiW=iNQRW;2-;YmfYFsqo zOG1kH$YQ6rdXbiH%y(0-&A-bySqB19)Dz$O(#te=zbi`|7|s*d{{XHjvRJfHC@L9q zyoKmbbNbX1Y5xFdkyxnnBRiG0@;?fdxq9_1Lh)JjaNoj5f2gTsyi|+$kgv>t5Amjj zW<<)T%g4&NIiNE{%o%ra!Ok(B)JS$Df=J)yXwFxRV*u25f9Q7X*-hO5ZbKeVLwmJBY4HZN*zB1B`VQ zdGGDxk8FFRj4wO-5)X4w$9W9U;9<6%*eloR>r(eCs1TdgnSNFo-P3L;xrt?)Z|?q4 zgU8(;UjG0=O%n+vT*x|SjGCI=l%0$6mIoL(!KRxIViwcYVr5qQq<}WyAM^ccy4!-K zcCxbe6=9@p%ExGKbFluk3(Nb)ZN+&UuN={CtX@chSyaxvx5_ytnKP)sZ=2i>wQf?f zNB0zN?~G=u&u**HnN$J*?0%IlT53LG3v{Y-l72CO#gU(M{DAW(6Bly#z$v(*J_36ru z-!7Rh2d825_o(f@Gq;??_+!Koox}{<60AE8yc6$Tc`^rAUWIta0|KR%ebOrr;vYAB z=D7Kp)5~Me{6+C2UAdAIqxer!n`Fw*=SUSwbGUMP*B9Y$4EWo_UljE(5LoCzZFLRj z$-2BiST+t1B;ij_rF&DVNd119IH#j|lMtY=Af7!wv~q~$F161a-|mhbKg0G+Kp~#t z-OzK?06OERJ$ms)$NVP$0K;+Nm}I~kj8i^NIU}AuInVfX(;q3fZ99+YQKb3ZyLJap ztsa7V9%4K>;_Hj)HSZE@mO2zVOpW9+L>w}ajr<;*U;~nCC*Zfk`~LtEU0iso(^_kJ zE~J_e#uFn*yN2c<;0%y4{zZ2m9qrdq_*1Pa?q*1Xfzuq1^UY7-Umf^oPVoMhrdjJ+ zPWa$e*t4n-an5=S=dO99L7oTkPfyjfPZr%SuWvY-Sqm)N2HD3z>yA10tgj5|@!#tf zR_$`O{{U!{iHL2=MoOFxbDzSykJ>lK*1k3Id^T3B(m|#xLe9&L%uY!k?C>y8KWA9{=;w^Z<^mTXhB8NN^~Fdd>FqPZo+O6BRlHFoi?Cs&vqJ0iJbHKjRgvRw z2l$eI59&p=<1`I#A~mqGUD5)lIKk`K3hgyray=iz*Sd>&ZT2``Nh3$fM#{Nm$>)!L zdFHtffPWR__>-pU5??z10BA!enD)^o)rupHp>y|+diSeZ6>}Hhr^8tot@JO5*G=P#8)#;j2&`{ZW)zH`eS)5( z^~p4~6C(K2eXhU4CtHnMO}(xc#AgQKLa;28W}`b^ePk=>Y!#Q;Zx0Kg2TJV}Xvf%X|*;weN=f zUmdlLw08}vNS5rSh-DcEBq3gy?q<|Vp}x&UYfTXS)-0uBsY8vemSq2)%Om&RCD6+f1h=##JbPh$<_T8z?P!wW`=Vu^!!mkpocz{dlVoL6UPWC34c5w=r!Tn5KsUU%@u zW`g#1^CVY|a0WhJN&Z#nK+P4Zmn$dyv|XHFaycJ`K}qOn&2tC#O}S<*aL(JK*|ehi zlixm_t2%u?)Y-IZU&&U^#W)M?^s84Iq-_jn(e9FA^EN(Ezt1$(wUED?97@rQE3==M zA6}XLXbWgTW#In+wb;pd4XXJzB~DD6R52t0?@aM(S?d~I0w>g_L`6 zJ@Zput}-X9s$Rx>(;xE2}K-QMApkS#newSwgUxlG5k5>*0>!SKQ8{_-)xL`5r#i8!N>Hj zn!{R=t)+=op^+RI_{z8g?y%{{JpOf3COev*E!1YUyS2K4Nwzl|V%oBde|Ud;>0Nh) zd{aKBKiggjE#5+Y>{}9CaCpuGeLo>wriZ8MSNe1?*;`x8u*}9#CH?bmKArK?kIJuj zZflJlWLYDTSy-%q1Ld!5ob<&+wl+J{ac`+5yT@v_-@?+C{{UFP{{Rs0pXJ)EXu?aq zbs>&MwetyQjhGGC$=saaAFr)b@P*yA_JJk6#ln59p9GiP`?5a*4nXPJu2@5Bty(m2 zn@#q|4DRJ}Mmfpr)YKHMW3uq~h@$ZI)zq(UuO+J-$siyS!yS4Y`qQqwX{l!F^3L8% zarf8k?4}cfcs~BVr|2s`MAvO(iEZ^Q*Ucg@F{jR2G5jog8rZw=&5+XkyB+YM`;jRv zjP&WAhqX^qjOczQ-RrRb0HkTL#~fpG8`ylrW7Cn>9^mz^hr^yGzP5-<K?A9zZ<%Z7LbHjY!!$~foYjTSXq_VG)yzLl50q#u&Sk8-9@dmSD_BMy? zdt?gg>A6>FKQf*&5BS$h7K(16j%Jaq=7i!y5!$%tp!}+f__k|R%&@GGh0o4642};< z(9t|!V(|%8WQimPF)U|j?07U=xmuE1=`rco@!V`#T^BxLj2wI8t!_N9t-kHi{OUez za+&&iS3iG$Bv;n|0B4VSu-mZ@%t0sCuCRoK6Bdum7$Jus{XqR_CeHeobsMPdY?trI zt%bs@|lM8VCu?u zFSy{IDz3uK7Bx6x{@jczDOF*}Zr!~(t!ZuJg5B8`X!j1MfZ68*+PQ00cqEb=qTgu8 z?%7A)^dDaNuA5cyh4!2l6C`Z|Mi8lws?iiY7rj(Zg#Kv_pJzT?kpnm z(&bxn@BzxH?}5^>ueNHc+m#QVzcQ%c{uLIPHLjgvkrlXse(PhLWBh7|r&Dr0QbxU2 zk&&6c@WwYE@@m$*e;%NVERZC4Og3b0G1DJjmCxH&;xB zZl-Y4F4bOlb~K~~cx>kL{Kk#lcJ9D%Kpwqw_*1WLqqpUwW4LE%k9J4rS#5sSlgz4F zVcJv#{xWS5Eo*&*c zavi@m%qtJ3D!S?lsUpcBS%(ToDnB}PrJvhnU!2HUdMFF;pGrEDw#IGT@;vC$N#w^X zY}n%%_xe;fo^&@Y8b+-odB%R}AK+?jS_atrm&|C+&@T}E#pvZQ`WbyBUIQF}6% znJBcD{U!}-ZycX@dWhUh>CJZ7_#xlY@fiX&|sWyEtv%;B?~{JxztPzfQ9?(!4>llnesIMU<+?L1(pdOg3uq=?fbdPT;n21iaD*Ve8-b+@cH0$ zBmV%eQ$n!8AMRF2*_fy$@(3Jesp<@mMzeh){#N@74TpI-+q;f?S6?5+H5M4T(q1zY z22YpfU^^Z$_=@MWn>&kZyNjuA*^s8y+;;@`=lp9<$HjY@qh*pzuEk_t9RC1-scPcY zmo*=X7Mi$ywrl(K18NPbr`y)DqA*{}Hp#q+zFmi~_r*F0RneL|$)UJx0lfT&j-7i| zjV8+W&sJuc;g`<)&5Wrz$4=Z;MIjaMEw7=UYhInqxR3X{mmPY0dsbbRjj7n`63ume z4BlrdRBZqr*~M>a0U+}vEoUUmaguhF^x8XpE1$a48%wp8NLCw&Rm6!9{8`m4^(_MG z8>YUJ835e^Ha=|pxd)64cjTJ!ZxUNxS!lj=meNMoaqrwtH~IsQ^Tm3HGm;cs#rwq0IV5%j*DLXOPIMLfONix;A2Aj`luxySlB2qf$MUYqXEjF8A=fRo z#S2KjUL(qd8P8h8ieVMfuguKqS#p?sXE`7JYSi%zk}P=JCdgE_e;-ft&1XkoQR2Lg zXx1BuipY$l$Vkg$o;`gJ*19?zolIR;=j|8F?6~tAIVW>x)YW@5ic7T@5=rET0ht#i zSH1^&j(e4oHC02lL6lY<$-vLOK3hpFZVYX+cLd{*PpI{)>2Yat3$WA6{;;<@Mpy5D z`s+g0bx75Guo^xyyMjN)sO;wq-8jxV;-<7lnM$iNZ5;XlDn~19TEUezv}zm-fuER) z5HwulpyMZ@pxo?Hw?8q)aq|j1-eTBSrJb9nh`u#c3Y%p51qq|hV=gc3WcWJ z`--p2@{m4n)7qQoM)w6{`9hyx&{273HKpi^;@zQX6gmc661}PsMunBrNS`c{M<4M3 zF}Lei?=D*9+C@;MQ)a~I*yEi3d8|uo$sk5u*^Ka1{{R+h{-0#?TeOanh}E`+-GCdO zKDo*VeCE-m%>ri?kqn%+yW^!EN3U?T=eT!B55qM<;f%{*vV7!f%G*xGEn)+h^ooE zYYeXJ@Ox6*Tr4rSO{{QKQ*Xbtjh5t=JFUR*>$QjUsH}F!0({d{d#lRvIYMDSNBUC@N?UNRMzQ(H&0xS)akFDSsQoDo_7ynMY@hFs6lfb z++J)d3Xn!g&mxxC#$;bRaz^BUGxf%Q8cjJj#*r#*Y?2T4{6AWC#j{#I=gVifKAmak z9H@?EA29o>ry#FTDj9$l-!|psl1hM}{b?ne&gDtnj&n&UXNZ+woq#0u$okf8Tr?|* zu>1En%fSPhY}ZAlSljrr0nf^QwB4pb^9+BUl+y>9hW-)!L)MO(4lK1IWc=H+k3&U5 zBaroNv{dRd>yYMgv6!mo?+?zNS8vM2SB&xL?NsH}?exgJ%ZWUgiNdpxGI|fsrBt@@ zO|Gf0Tj(t1VSu}gF%h+?=8qcus^g3nz)zZbbYwQ_Y)QscwG$9^$ z`%3A)Ce<_>dp#5xEN>(cT*iy@gZu=Z%aO^i2-SQOulzjMJj?4TE#yOlc^7;V{{XZb z?veV6`uA14mrbymTYG1`xs5Xv0m6Bw(9!`^MJ&X;(`StPWPgM|YF zC6wUv(~k7@8s5jB_^j&AEN0ZLWVMz{a3XeqMzWwJ2KVdN(-o5i#KPrSWnm(pm9vkV ztzPj*#Qj^wHa4(dNeqzKMv+1lHtY%j{C^s+;lU=W;u{!a^8Ch`cC3eLx%cf-Rl6TY z{2#yY?A{%34G%N>R$E~%s|m?0TZi09AU8ca;;eij_+6v?Hq>>SjXLmO&A6;1yis<}HrB>&QM9c)P_OB)rvhT_$fW zH96W_sYvDpf4;zvUYYMze#D-useaJ@8^6&l?_<*%{{UWD-7V~5h#Q#O2k#tbX~%4z zYVv;^c#Fk99Q;KEm-cI0O$wKW&?6*P>Uz5~^UuHFE4=s}@OxJ9SBZ6-i|EKji)0f5 zyJuo}Vc!6Lx%958>E1|WRc-S*%aAfj7 zP)8qt^vMxVnLIKX3vgs$_#dGCYtBnFZWR2xmmqfnx+%uSawM7+mM<^+pdH?Zn?11d z6?5|_Jmd4Jn2qcAw)Hvf_*8dOJKi$An@u9fI5m;%7-15_5tE zF1&Dusl+5SIY%DVQ{R>9EnIP*B{PZ|2vFk=qUc}}Sq`37(oHBVBC)LP5uTwGhnv+qVSz=8SD zC**Se7=q(c)bB1MlHFPnyflug&60DB@J~Ift(M4N+S}bUd#84e1KrvT@#O5W48LbqEdxLBV9qYclF_y(@T9V8LOa?@Gdd63*nRL3*H zw5uGQxgU1}wm%x)@YU++cm7Sxl5j$`;`6z2?bqv$E0JrMn*CH!T!QU3rfQWY+!Iv<#NAHY{dqCp(i@xtoXOB=R!ryBv_SF%|AP+y2zExEkYbc?B>KqZzKzRf$FobHl5Zu~(cj;52j zqcYND@!Jsdow{vOsYONHEvk$zZjf4F5su%Agi6)LgxqeW4 z;-c{)HQXOPyG^*~%vLJN*Qc#ku#WL#lgVKxpd;q|d8&w{%Ja0&THjEEbjqZ~DB~-R zoocKXOQ`7UBFQw389Ncz9QXXIO7h0);aR@S<#-wBp!?OSW7(l>ju`&{c5=m+k?Jak z(9P1WW|1})RVoXRM?>2c9-$+#XylQ2#y}lUuhOK3&}?Q^Z!>^{rar$~isCfA-5jkf zcM-;ZXogSHrtBLaS?*C8VT=_)g4h`q4YS=qjU;WB$s{{tHFHRsAfV0mpt5jXM^C7$ zmwGx!I{l9G&JB;eg>lDEbMHml7crMHx=Frh)f4DHXM_NgsaCJMfEmh8vp*g!0C z$I`Ts1%wQ;Hs+Or@-h$%^O03^v7Cmp`zTR(lL@frMD9s{p@rfg=F4M8%^cHTh52? zjiBTFXt>LlQ^4V7j$4ODUzBaeN3YhhHQh!_HOzB1ADx*UX}8G6XCR_9y9f<_JG z`505b?=T*owT~{Dbn%9B43WvvagD!Inz)c%MQ*Cmte6~S`kzxt478WG5$U;Ax0>=& zWy6g5YyHwad8ppj=HeD<$lKQpdLM3or54&<)YnnTA>$chk}uur20sqfPgycq%);JA zWo)+Me(Ck329>6nCY5fo2J=_U0i9Is4bRJ;QR!NjI@buRG%@e_04i0w@;}d7an9X?tvn(sML1J-?k7~)e))oZvqgGhVrLx?WU@?w^{{XL5E-&OZ=gKpp z$U!?>Zhfh%0y@njU0AInd9CB~o2CHySDtfP6Keilvdt86$jk|1m?)<{hPYWSuC8ys zZ#h*P8#eGg22ZD2sd6Q}4H}kcm}P>UyM|BcOi zZgiCUMn87}nQ^#x&Tuj7S&(Y6+3JfO<&xT@o0i}h_bcb9+zvM}^_oYz0%DVI{y^$V>+XdXEtR8^8q#N&&ed;=Zfy8j%jLnM~L1_ zh7TeYO0y+aqL>Se0h?70`0aL!8wuip;CK_iK_f>DbW(jVZ`x+^c|bfGSN! z60TX5LdUgJ1o{(-j@g31@+f1tg(v#c=FrWDp29T*r>P#N6zqKYUAaAR=}r+Y#*iJ{ zeKAcD>;+pn2cE!xjS9sVK2nhebygpFkF7gZwfimODl2&^epesHPC-7MY8dUAkz01% zzk6@#Qhl+aY;JD6FJ0!E+%7uQNV5H*SgetN+1r7iao(+5UeB!0_KTTXSpWk)a64k4 zORw~P6mH2m?0aC+SV6d*%*-=}3-XbVdMtryxcFd@vnw|_%CYPXX^G?(s}J5o^8)7> zarFLmUfy|vG<&wj&BC$ck9xHgw)l4WjOxPyv4DMt(w3=-maSyBo@5?#D$E8Kesli- z>Z?qj+1Fu<6Ui7I#!vXwI~^%}sOM%@-H<-H_VRs#g`J!nQi~vpuJ#&#%*sqYjT#Y6;8&4$qQTF+yZLqeH( zhep?G`hMiOlV|Y6;BFs7-lEerJ)%#v0VG)3VwH32(0_$zT3y}UzU!%HoltEE?VraT zaqm~kLvbGFa~U0vT>k)0w6z-YA-U7n?Z0S(Nc@ud*^iieA9{YMzh{a_*LNThyZCAw z2NqKSmfC%@*008}>YKc_-p%rb>67_THfF^n!WBpzcQ7H2dV@?0Ap6QgbmP!ekXWnU zF4ovr@13~89Ac-rPv0t&^MTi|9MWhC!cVi#LbmQQcMn<_KZxVk9=x7;7^OiBbF)YZ zZrB;mwL@~nkgnxXfuHCpGLtPue$bu*?k5>vyfM=i9P>#j*(9GaIb)CMP+LT?-EDop zcQ^!Pe-H7gz|YE8aOVt1J!xu9#?NE+Qe7FCso;Uup_VfgJ4-7o4p?>T(AA`q2j?yC z$K9%TQ5hY!_Wea4bCD}+8Z7EQBVa`KqQf4VbqdFXsOiJ=hPl8@cV08Y<^Uc#?i|hgs}NQ zRs`|*eifr@7nTqLKfE#XXFWc&c$ZE7*zo1;x|Ua(2?k;~b;_QHo@<`?KYuOn!u=*` znE9&-P|kj4RAQk1Aa|}GQ)?1@Nbqi@;`nV_Pt?D&<+WyUB8JJx>GGU@b+Mu8(&+kR z7V}+AbkVLn>2bZ!B(ZKapmY_&)vx|ySvGO4=U1A_f}XSZBeX{zfn z=vrmf+>0YEylo)}0XP7j_422M{9$jTc>3P^Qq!Zabd>rA?iNNz2V5fH$O8RPnUR}-fAr&93tn|W(zbv3+q z@%dLOr~PVm+E0HpQuc({$$u_ z*spECj@ZD!uRzd#5ZYMi>u+-+-XjBz(T%u0yVY!o8h$o-X3EFRxz+69!P=mcCgvQR z1q9>ruQl;!?NfPqeGF9xex-Pe z4VYG9%EbNcfb-9DT><|80DYy}71d9EAwse)F}bQlt0xo=60K*3@_0OL70$RCXn z+z$-+@!{!w6@R1X_Y$;|$7jA`r}t>=*}@!ijw^sL#v3ZTv()-yiuC^g+R3h8;zVn7 z>E=Ug7*d1f!5^*&HRagbDc;SHI*v14kl4lEFm+pB%9T|mfS(c9E|m>gYA+W$W4@wFZxZQ=Zw1JbA5RBtf*N{pO(!g=;Yi0 zIbolF#*Z;OY+kv!RQt^vNI1Y4s#>0*Bz89rw(-j(XmF(GBOcW}(X7tR&iMxJdbL&7 zqBCiCDI583_IF~~>M(esGPoQrnNw!y!8_Bp)lFCeE<0J#eBcAon=@vJ-gHQHV z{{TnbmRA9`ul4-6&2-S*N2Tf4w)ZVG!BKy7enSZ$l0ZGqdiKY?V=I>u_J`uw+Wz7> zt=?HxaE#0Y#52%!!Sp_r(C9j^{3A&ULw%_&ypsO*-f%EfbpU6R_2_-8knrA(9p z&PGvrD!mku>CbBGu6z&upEBG-HN4E&V$dp)Ub)AZQ)BjTJ_AWG*CtK4 zAGeYg`wX)V7C;kd9AupI_UbFl{2O(3EwnN;Hu1cSV_|ZS=R#MgRv_c)UW=q^k>1qWqesrXuqW+|t!~F@k|Ve$A9!P&AIh~YHCM9>_FJZZEMyi? zGy0!@(xJ7yx3`UCSVg^xMk6I8-i?g)2dC%wQ>3%|Y-V^it+_k5Cq=B;SMF{{;|Z^= zFpAA_vuvmbA76UMz3~I-(p&D5MR}V9EA88lKxw))l#s@^cK1l?x#e5}Pt(8QS07ck zzi`qdQb@lmHaJ7v{xv}@QMsqzL#ad~Fk8sd4Z=;MdC$Lkp{VJRJMDxv$(t~lq;8I<%Q2d( zbrz-TeOaLMd_7UrZ{qDv>2982XV8D_(MD?O6p&gjZ+3&^{IhKvHL zdVO*0RdpDyCB?*SsT!TKF;lR8K>q;iQK(5Z%(1e~<+NaoWR2q-@%?FqyB97}NnrN} z=PAJi)hOVQMI%Wh&bi1!I%DZe=iDso`<>YwfWwjP?^0Oml0GI|d#KbL1(b9@QA`w_ zg(KYmAIBM+ZE9>xGY*@Yo;<^*yPN6ebekE*IF4!4-E~e+%{g`Q#GUSLCcnS?{SEK? z-23%@J>&5@Jsy}lhQV=Vw=u(6^ke8LcQh(+f zx1kXRi6hxdobNOit43@_LVWnRsNLmZbe>x9UEWT1LN@v-cUe2U9isr((hOmU`=s%J zuG$5yJQ98kzIWoGRVZ>>Kv1!7e)&c^=2JfN!OeMu))kWWf+BjJptg)u26+cCbK+5Z zg8^7<1GOh>%$+qoL7OHn7|78EA!8~md3uOfWpG)F017i#>q?yVbdlh4{=Y|dbwy%bc4@@39q*^pRx z1c4-}(nO{@43gp9j2SG_Rrc;$15Rt|Jxxy$hRn59ux$Vmcxmk`GMt-Eqnj24$=_XD z;aniqRf0K^HyZ?s+d9y(ijCU|=L9r$_1ZFww(+V^@t|&!r zR~8wMNATn?yQHuV`7&UMDrq$L(fHMZV3L5{5C~>*L3gJ2_}7bc>cZp_YvM4l00v~T zuQglRUL9fo&h3(3bbDdMAjsO zJ9uc*25;%iBTMRF28V28E}Mq@_57or?RNB}z`4>+=Ed202bvgJg3F-PpVVBv7ifcn=5UkC?HgcB6@71aWY1lR&4qG5j80G%iQ2^;+g~)7-X8I7%7S)P+Nr(R13r0eJR^Q;s zB}vkM+8Yt(;$JZ&a#B&)jGa!QPydE3tvpkFe~ob|(5S9|pEPYP-sJwBbMKgLMD`2W z;OTjfmWlwa1{-S|Qw+H}b45g=>@5@m_9$fd4`+zs;tLa+1Hr=O)PD@LrAJ<06ep*P z@lOgEH%3L;Y;97*|4kzp9pmz4+j5fqu8MmuXUO8YtEn?_A~nO2xmejXuKLQQFE*wR zGPxnxAv=sZz68(D47D&NeS-}C^^Jdks#Z8m?#z6)J!663&Pp%GpIubm3+N;l>0x}~ zzbi?lBJ9l_Q(vFtHMcb9AVhm0$qd<1CuP|i%vnTs&HCt8VfIb6@Vm`wMdvh^x`R>A zMk~=m;|eby19FSLlSC2%sge#rz1nEdj|a0T?m?Pt*9hQxc@<62@bIv@=rUuKDcD^2 zJ+{PH0#+iF@l)vBX;c2p)p?`tAKA`QhRf9C(W6CSeGP$B!s8Pc~yR7%40b8h#mb)P>)xMmhLrTcoCcc5nRO93Ulj6e;etUeg zRIOX*2=^g40o7_Df7+_t*$2hAc5I%^N!S$j_$MN9PF&+aVtP+Rg{vHr(zR~4$?&lG z^^`%|9^;`WhvYoN(^SZRdpdHu9@OVf63nsB^LGwL#IatsM!oYdri4RbiO=Tr)bkJs zmFPu-cG#}1uJt$Q$nJDdaTcNJ#%^t)V(zx0v{t4qOkr6u>f%>^&L1Se*$Z8#=Dc-!Z+?OH9i@MXr{<(`_~J;BZp2i8#Ki?8jD58a9gXlSKeMbzwa*RU zm6c|EhPW^Jc>`>JGt5o#+FrMUdNMq`|HIMq6?R`d$6Jz7n6ofnBx(p+5YyCKoxDT) zA(9;6q9$7>`Gp0$*CN!<+oA}vbUfz!Q+8v@==}Pp>2S3bd3G|7u)n|fj?Y{zM8eBf z|628*jqmaqXY=#zi)`kl$i3zoHlDJ}8xbl_6iuhH4!kOE2rc9|?WN0_c6^h1skxh= z?8aOP8DW@-1wWOb%LzD+k6t3Fe0ci#Nl`(s#6chk;E^u3Z53PAXK=o?_cw4nb!nXRyBa1g1ONq*?p*GW+iN9~ZC*7;vzovy=clg!oQiGK6PGA5~v@V{`xW zYie!I0AjP=FN zo*vUvNCTzGixB7Y;=hC@O;hUcecYe+tj*^VGWWc$Pke?nKQ5T!nwz}T&P=$iiptQcQ0*%)ke)M&Bdr083Ag<%fmgRWT-5DCy zSXj#Vrs$_YU$LZbp&jTdAH9dS6Bh?cXUg>*VB-pMiH+FbV@YUWXRnBa_L7#;&Cyq{ zU~`=)t&CB&X|9tEldNk91Y3@QEgSf4Up3pNoA|kV^eJb&W5D($_Mu7WVHMi=mdRD} zUBjYbW-%;q$fh+8FD*ltwDFwjWfo%*ur~r%A?cv;_9GK4g|%gV07JFFCMi;4TEcJblAmd3HKu&L;gZgTR&F*4}|iOGA=M zipYAr)4?chwPYxbva#?N9_2T>qrLsXYM%O>2HDyu!0~8w?!OPcSMzH5Zfu=0GkRU? z^R-m0@%ZF(*TGK$Xeu1#j5$Ww_G<`gHVlDeI#G%m<-Q7HTV({*PEJFHcV*#HL(`t4 z{v&o(G2qOXv`8jOz5%~=xAQ7e3O}vA9^o643}}08b%!G?rL@pZ2ctvD*gJNzV;Jfh zf##(3kGVBwxhQJx$PV0jmcC&_`_+f%P!U|)sy&I zv^TorJ$t?A7?n1?D$ri0%%uy30Jtd+xUK%Kb3MrYvR<(1F`F{9$i<3WtkqAKgULx*akHF@(gFI*~;??{$|pVyn% zQ>%H})p-J?FqbSXA4_Dho+xi}?^J!PJyh-I?`%XYJS={=Sa@iQkP`O5mZ{t6G$g4{ ztiU=OVAI@GTO%+G8)Ex)9uoSt4VI)HDgHU>>J!!7#&uY~@XZzsm9oOH3HvVb+3zgW zdSJg!P9>5vJ!o2UY@f;6I#g_rdBSpfzc7&+IQRvhgXs*fW@D<~*M#wb~D~YzvI@QApuVQp8*5;}BubBfkIqDS1d;y99b%-_x`UBX@0) z;&3}1i}jNHadTCkQpZSQCe)WRuUFSk4Txsrg0YA$G(MzN0BKOzN^8q2eNA{XzPxOU zj`zA<_)L+LQz~VlBB3d~rLLCuvGG_8vbumDbpXwCqpO{lNu+~weS~k+Nb0u;<(2JH zHo13EN{QJcv?y5y9t&tJ8vIMH6WlDdbzIJ|AB@FAv&j@9HV`jZf0gMm^rRR4 zbBP;7y!!TWPTb&_G_)UU1$)L*Wyclg{mR#z=R=#T-PJ$^r+>*VW9NcUg~BuUue=1E zk{!D(;bT#Tk;YDqiGJ02VIf-Kn|e~(T3ji%d!GJ-`yFGkbXGYJ9l~<0WN>enVB(F| zNBIOq*tHX{^zunKL~~(JOZ|m|%W9-^qWS{Wo(@fti9v9l#E`Aa(A6(GBAwTZmW%R& z!$rSvq_;|B_mVKW#O!^wLxBL5(fazWBMZwKrHfKQHxziT{@s17tcI*(km?5!c za$Jt_92qfPQJy(6AFfWLjkJ1icJwRZ#~<`kX1H1WA;*LAN_m33zZG3poPMm>oB=#Z zSj_*ukjQZiUdIxw1}i7zM0>&_M)}&XJ9BlgUR~+~Fg;Hj=0t=Y{{sQug*`XPJeJ19 zd4`6@06qztipwIWRJX*>TF>t=IYr9;rLuu+0|sQ^LXv_iJp-#B!39HlR&Z||pEY!b zx}~!s#dKS1A>=SE@e`|3)S*AaQkCTXN}K)yBcd&taFU**ey~=(=jo6&*2QooB(w-+ zoLytzv>BKs)z&OCCL)7Bx(*eq&;B`yrm%e4Wy|h}7*~AUuop8-G*N$Kr_}}2^~F8V zt75rTY9J|>CLNfUgjeAxg4~HX%6MkAV=2TH=^O4jAnh5ey5{c;O@h`Ycl2CYd7H4< z620(^SUM(2>^ojZk+mrv5G$<8=F^Y82#x}XZZre8#eKNsq6O~i2kNXze|;O|+c{F7 zWCc&iJs)Af;i7UmlRPtQr8E0P6g#7(v=(3yKFTYPH330o`)`bTEFqbq?~k^z>x_hX zzbK7HOrnY6Mr^W|TQc@ZW4u^7@0V9_#%zeEQUWMjzr93Wluyjbl`&UFicHHUvva}e zB}4o3#3Cvb8Q)mmAQ} z<88Ob;i@8I7k%NmAFjBF| zTIfq+)5qlrs-?pbJFkd4v|<}Je}%NNqrsRP%+}ABU%R#|(N6j9O|(zK&EA7|C!7@a z-$228S8-`wU#1@MEiqQPIEkJ4C22baQeow{ylj2(2iNB6!2SSP2eDYbp*BSJr+DNo zf^uz=UQYZWc~V`!Y=|?99yNO?BTzg0l_c;CTTy$rC*LE3l5{#SDqyTTe8vm-s&jw% z`+oc65WM*6L);@yxC)M!-OF#7uaD>)Z>tLZ=@wh zCBM+0)Z{a2wIegA=Duq3(A9qZv%>gIOsLOaFz86pM(~TZbAQfz84tDKow_#eXj}9x zN`!joF+Mn$qY)pc_jgBpZIMqS@lQ85x*5Va%!RH9{jS2g!K$@=|Gs-@jgb1VO}e>{ z047AzahLJ@bJ8YPucuwfhQ62DzCPqTs6t^ug!*VA@trRc%-a=ve)rBUR-NEYD&0E6 z-DIpy!Ncjn`UmPg?bpGB<23daZbe4zoXicBU^(^lv@DmkZB^dh%lbCCO%qCb-T-Yc zpGU7{+O7xiPj<1)0-47Vg+xHrC0=Sw%Vzw?$=tZCph^szFK!BBgmKKa7<+0ftIp?h2wy@D%Gd5Fl>WV-wgN$W1p}?Il!hF)zG=k8r^y2| zMH%e45tfq)%*ol&<s{ra!Lr(2;>O1XYsUlP!WCA?Jf{@n5PhNbKae@!EZ=_=L1v|=K^ zg7ZqwN!~6U(sFF7Ad$G?eX4t0zo_0C>i6TeV=KQ!{(w-QvcFB*8?^@L+R>*+dW8|r z=`!LrEldmqogCipOb-DG6$*pZK+iC+jt-&ge%})_PlO2KqU70K(_qaIa$z+$RqJdn z%;xNMc*gIv{c7b`0Q$;7%vucvEi+n`IZ{tgWG#2Id_m16b4bImAzOV%FW-%S!Jtg< zP|~rLWE-sDhfXHUiYwW8H5LJw?{zSf6A?KAOFB&EG(Iu?!%5r>KQAuivRw1@={E6% ztKC^oMf@D%zg93VW9*sDFUMxqxZso8(T+*aw_CBkH4I<0mAH}sB*Dvtn(8D!V zpnsgw!t3iBEL^@cKCsN}{N;-8cyP8+q+-uOV#|?lKkkT)mMurd%bd+`uQ;0FlM&r@{n)P78OMnnet_O41+4-`WBZ?fR-<1`PqAha#R$%{l~{J?}! z_Mg5y$e+HE9HY`t#XUB##psTk1Yc2^XuSW>8{*}Y5nNT0Rp4oiE*A&}#m*##OlNaX zH&RR<9Jm$2CcK}rDwn3Z9i_c^o-{>7b~Cx5BIF8xzC^~={`thkdn7Lb=qP9EiTsbv6ZL2w=(8)rpHV#W7Lo+?Q54FW>B ztYwj*AxMVlB|pVZy3ig*r~BI0B*)ku(K&;-?@4FG?Jno%2&5$Iw&vDR$gz@4)>_?$ z=Xs6HKkeloK^B)Me$j`{=WTItb(>ID)?e!{%&UV5LW?YdbdRwZu=AzY!8tuwuV15V zSrg^7Y;;8M51c)6$r1xz&cq;sEtMS(G>ICx3oPG8i(4TUy6zoZ^@XD*LmvOLTYVpC zRQ05aBDz$mHhf!n~Y4g z>5R2rpDX=mm%gXE=>)^laF)elZngp!cb)#9%q}u5A|ev!_wVwk9;8krJL6XZ_sXD8 z8X6SlLS|l;*%yui&GnFOr$B|157BNCR^`D>m;OA}a<4}qogtzKc<6@N(n-<^xUAaY zf$@0pC!yjO98XEi`hi}*+#SjHEb!e-x*y?+5d6mjGsZp@i(L~l;NN}uapgf*WWJ<@ z3p6=1kzFZY@ed8Z>}0wBZM5NAeoA_I+CS9hdStT2FjpgS;!+h?@}q{l-;fn*Xy~%|xwp|G>t&A7b|=Z51mjBy zt;;j>;6!l)-v)UG)2|Y5;VKM@?7;Ae)$qL0px}1!+UjNp?CP6n6JAa#6HcgxQ%rpe zrQd-A5Gn5mkC_GjCt_4A2Pt3@$2#6#Ba$5rg)93?C#BpHZQX zyAaC0uOZE3X-u@jZ%eU|6x}8$VllVNTaOLf8?o#4-KcOCUCTMi9}#}Z!ryF`^Im(t zd=P+N=JN!Ne&GWq(oyJ2%dp3jLB##S9L~)H6q1*W?d)>#>&LtoJu-Up3-PS` zIz-Rv&a_;p`TkjDo_!$~BS+UetEr4cu^wbAy8&kVH<7KxaW`b^4D& zFZ}F$^cL9m4}ialK(Vdvgz~4tBrEZ$G5seI6Z6|22*UurWdGrG6|fM%>UNCOJ!waW zV+R(-UbL`4wf{xs&%=+eYbdYvmWOKr#^6n)lp0?)XmYWd>{TUX*q+>YRM%E7;@{~O z-XXatGANj{H1g>@${+A(MF*!-pJPr^{hz*Mq5bKIa~x^f2=muAd4d_N75t%f?6*-@ z^*C#T{F!t75h+N&={xzZ8GQ#dL;O1=bCj!2e$&+^)(&^zu5JAwT&8+PWQK1Xbk)jeO=bPnza77o6`9<2FHjT|zoA6WqhIi{$ zrBY^TWdYlSviTEt?hov+GginO-7Y^QBB28ZP8;>dXkyCS9~%G84d9flAyK09xPZPs zB&q`hq-tmljI=hep~IoN>+^l^-e-7>{hlw~qBfi=40KtpX9qn`v&AmqCRde(4lVj> z$M*#eJFEv&kl`gkzP!;cfBe`7DkiJNCLu}T_s^ad!_pIX3}=|6whqrxadry_$T+zs=DEE@xcXY^oDOp=;$fmOHE z3%4BETM6M*qCKh%KJjW6mI}A!waE@I8ud8Tt)3J5XDFM!%Nf(J3jf0R5_(`UHY@Pg z$Yv%A+w4JW$X=T){LIpddHqy4A>?RfzKQ#YTW@i~>AOt^f7zv?-2TZ`ytbi2Q`G8+)M)EBV{bE+%8xkb2)diKDu4Fq z^SwML!kttN<9tM_+_nA?)7E3ZQFmU^JyW-^16QHY=SxNyRW4NPcS}(+;Ae{xrkB%^ zEASd^L;jic>D}y?O_R`PfX35JSe&mSRvoARN>J>WTpaIGW+XQu4In0=;oZjp=H7%& zS;Y)AN2+p2G1C@CS53==y+Jp+<06@%C3RC1yR`l*#z;ObZ(DaWV3g0wn8i7wD4#Js zk78=LirSC_g+@xBS4uKm{5GQfcbFeri`6Wit*?O>lcx=~xpb=uWogxa z^dG-^$B2qk`r=R=oQ-Yt+)hv)EZM~75{u}D9q2l$iO>r(dYnM6W$nrn!N$nTs-i zUk5T*@ox>EW%42j-)$&}z$MP~5;qsc%`+Bln&k#EL_x`iPy64ReGYiVG|tk%U^jRs z*Y<5~L(4w!ck6eBA?Aja`VNB93jW@w+|bR_LTU|nxsb-W%7W~_){!cWPD3Ju%&;I` zM>dU?lt6V6uFO;)zSyilU6!&1hly*nJ`zB&MN3fSXy!;r`Kzk2tp=;GcphD&MDa9} z3$F_x1c>Zc&r^dVY)6b~i!=JAnKu<94-3MNMilKz?_;4IlM<7|ExK?F-oFOJOGt3W zw4n^59~bZNb~Uec+GQWhJ_EEBB9G{T2BrGHHZZktgFMFbYj9ynh`l|-;(osILnFhv#I@j!t27hU(HESO)jC zMb^Qc0ID$WX4u7-|Il>8`e^+LyeX8U__9uDwL-4$;5v;nJib3iKv5#|*9XgI4_8=z zv*9w?+++JSmjV#Fmn3k!^u?&eUNiuvzEB^#O#VTe{6?ALfz1%CPOl1dm{^<+YQpF$ zh>J>W#gxZRM1?!mr#z=<%_(BTgA$vG(6eB4Gvm6}-ymhxV9gI>Hf{n$U2#PLSa3*j z9F>;o7wobk@6jm%s&LXJs1#`HQuPE91JqBTjKO% z$w35|gZifET-5CTV3$(QgNs`irl*opN8!ePRW-mApM-U=Yr;c|f1KDNNgm1s9%+Q& z=+Y}|%6Kv!k$L=i*MBN@t05W99;=x0) zhliI-U%t>$)iE;BAfsDbNNE{rZZwI_#WR=xQ2`1-9*)Y2>crCYjJz(#1?v@yv}UL!;GKyE1287i+)^$C=(UT4>7Po^xF+KZQ2+At=jY zSzqjA!CqgVnE$>!(9p=5n9B6`5Z;|U-HqPBp!Ea8lyf_Eac1BTtyM+98^uu>4?=6Q z0XSZ@)yJ^_88+mSj>!I&AN8{|PW ziojQtZzz<>rFv_C(^D4hqq4fwLCvX-O`GCieOh(U(%(R86N zWepY?+1#{7`Q@bquz{EM(d88;UReW0tyxAZ@kzSCkPywV_|*l!ZYs253-Rm<(*;no6ohYOrD1 zCH3c76Y9+`U#u>Psx;{<9b!rlc*jI3+I>|rrL3ng1kDVJ)s2_%x}quzJAF!=grt@P zX8%HH*;``v$ztegPP`ALYKmxVFev_Lie$7e$4O;YFilDaURmB&`JtD!c5F^+xU#dg z9i{??pFmLuzGLi-L zuFvZjQ=PS41^3cq{Xg(42=wrE-`G)v zY|07mB4}D+OB$H6%Tk(a!}ezM;c0in*Y=Z(5p_Pjv5djchPfU#LrQ1*Sz1UGOm=Ca ze0PR74LuN4?HP`qiGk8%;m*dJW(9A)KIp3J7#!wb7d&@2Ap3ufu<{fU{CbmI_#%P0 zodMolwzar6q=zl!clpDKJt(E02;L8agMTAGhGvm)47;1CDItjX<@^Wf+tjgSH~T+U zJ`Ki}%XGQu1Y)&rR$cG42g7i%yd*bm?XK7dJsyR+$aif9^wm?Z8uf?&d5&{r>b|@kv+OVbhvBd204U zFb2EfOaMT~SD+RXYLnDYJbFtR)qY)12*v&JZ;3jNkg!@z%gkPKy9I3J5=fRMCBH8xAhY%pBU*RT9RJU-y_+$TH98a^Vuy@X3-%8OL?I!56d*Ywi z7}xUiOZ0lYmEK32c<0#BzU%-CogdWjwOG3<{*9*h3k#>q%U*&Pn6#rZt<5h{Sd znqd3cyGYU8*_`wo>8y~1b2NLDwRTdC2mcR;;me87Pw%|lc`l!mdD$iw+SiG+34u+1 z(vwrmQ<1Q@cP#%PD+erHMu*9vE>>=(CTPZ5jG)?tiRc5R4FQfY-&nx3`S)zb&g0a+ z-$LFOYkLH&Rp-+a_Bt34IElA1+T1a;1KF@xGn(3YYe6dEM1BLk;G<-3)XJ<4yG3WB5U7eok zJ+RZ7Vs45&z151CHbf553Q#UITDc<~Z^HkY5kpT<@j{V#n?hN=Y(hR-3ZkR(=0!nk zCxk0~wSM_$%46pU)=4khQ{_l<6H_HnYG@gj?TM?#1eLfsJUMb>aNwN~XyC24payhGejc< zCM9I?@|*8lxLUw}IN6-a@GFThzn|ZCG4kl~MCl|Otr~GJlRf7p@*|M%BKHOS@4nuMJs@S;q zKr7B_Q6&3(Qx&@%SGopY8$rpYEWT#TNKdmT@e_idI#6XLO0i;1_un*^KR(VEqpnZx3jZNk`=tyjKy$8d^5Mh|PFW@toK^ynk^7d=^^}<*$Sr`^sBR=I~w!nRu@)|6aHu#aN#Mjd- zZ^cDk=N7N3YGTCcHJ=(8|3$2sBFQ$kM-535#;eVG;9o~h<~ zPMv^z8K9klv_GKTrS_YWvg$#vVQr6GzW;}VWA;6O3@nDi6sR{FvUYrPQnX#5K@f!m zS%Y)lt@HSclN7C`wcdEqeKB@iSB)0vGxQ}DCe&{*3pz!$4Z}2i*`Gg zG3?k92srHZqT0e)11B%tiG^!SS!6!2@gf{in*cf07^-g}Afy=q5IVfmnj9Z3XpGK8 z@G!N;MMKy5*zuRGN<>B-;o;usD&bXe{{jcL7->#G=~HzR5R$!jfM_fP(FKsSG1oXpsX}VJo{|_pa{XeF_!AepvAx&I=3#YaD%mhzXcWl zWy=9=;y*8D>z_?GgbuhO4sk@g_rEk zkiqf6|73A&$S)X=-=BTXwkUM!P3Whu z5vig!KEj?P*&=m1W>=%;q_lFuEpR}tN_5$D#!*We4>1Mp_&oto`k zx!2}D#nZ*$HQ!{>g#?YWHjeGl&Wy-4Y0;yJV!J@`y--h|`I1b37f){iQ%hdq3Le~@ z=ImX9FQ%hKZZ75XUEl0~av5R{HVW2iS#DNK%0P0je1`;M>l@=FB)&#DTAzz-s~Tia zsG6(X>UQ+p*DodOb{i7>=^&dk6=<)b;V=IcoeF{FZhNYZZyG!0@T{)w=jr3%j$ws* z9al@bzed-R`#+%jt5s>UwT^N1W>=FZ~9wiZ8&ElaPp^8I7{ReL6&V@eteed->6`sAu zkedGPM@DSbyz;msvpN=Zk@Eq+A)!PPoB1c z^W9=O$p_TmX^c37pi7pGXLpdEO41vk)!T)!Zw`IG=i~#V$;p18Sv7dqPD)p@SKO!s z#P(U!Dy(tjzZ~hu)nm{K`nEWtTrF>dBWxO5GB>!YUu}58d?f!Ml@fnImHmv@6F3u0x19|WfhKT;<2XWStxHKaIWA>qX=$HWPZ z$h=NM-miOvLrtt=MlfQ@g+49bm`&lm@9Y2X_$Zppws$jBuEX%+Ub_REOEa#JJ`3c1 zh3<2=ooVzB$r7sGAu+G7gzuIiXQD{zySIdL!nCWGnxB=Lr6^&%Qq-9~b!y|Sb5gBTys zSF~^hMFB}B?PwKCe?_7K*{Nid;}9&}im=(Wo60$O+z57cS>?$-x8mtU6S*ahS)1H_ z%dWg_kSrKTjdF@67t}jl!?ZsN4uQ(3V)yq)qYddsW1QG(AfK#@t(a=(jT7ShMif^} zC1{i6`2&Tz#w1l-(}7Sc{|ffY8j`-B+}ZnR?}!mFG;{@vpyUY#?aZXFq)-i;Gp>#6 z5gA^#82+zTKnzVJHQS^vexUKN+hQX68`<`=2k&S>qvXY++nq`j#pv@g@|OMHxJFmv zHhQ9)yP5Z`^35<9q<+y=k?{bOz%e#sG>B+#`5;#nVT-j{Ad4&<=XDaFT7gfdl~N#I zl6+Rc9sw_J0(GCBM++7P=DyQl?%6}S0fs<_^3Ipw?v?U4o?BdFpEwIHM8 z>(<9|lC2?7*5cGlKa}`}&g8fcwM>e?>?0g}50XH=rsSgDRc@j65B&HhB76tvh8u6!gdOp@m3xA6R-z~|oVp@93o7b&$JT0AI)MN&CZcm28g$;e2MF-^-`zaO#+@Yp zUR_vF6!aVzFGEwg537Z2!_|v9n`iC}V4bXyr+YGBWT6klrta%AuD+y1(3PK2MTLX% z+H}V1qLZmGtq1YnKItC|U}d7M>?Z{Ds@~ezs)P{v?~atiGpudnY-IIZl| z&$jG7oqbWy$I8cBbl_BssB4H> zuHCh6C?5l8XP1QIpe1fD$rCRtEGq{))K_WSG*@}4``eG1a>bTc)|IaP=^z%2=TsRk z`Krd(`0(mL#$~2HZr0{`o1|aqr!<01w^q(i-})wymu2m6%fD(9w6*k66GbsA9-&-e z*Shk-qaoXv02dLds5QO)eO6N#Ki87o$}=2`+u+YMCRU^4Y{vKdj9V8KsOnRSYu_hk zk4~JB!n#Ob8EkY42kNXu0Ag=PAi2!U_g>rKUCf_f z1VG9z^C3`90n?kuQsM}9Q36ov6FUQ(ujQFsM38H!Y=U{0u;;HzS%~-vp!$u5RaLXW z4WmJJByFAtBg!RaDrCm{|KSMpDo6%%1cdQU`pT4mmKYb{N_k#&2$(aZf@yud6nRlq z_B+4njKYTps7oK;VMFVaXlrY*hT+!@+q%&T*#0`Auy}F@y=__F!U4^qnj(KX(Q;*5 zdswf57(aB#HDQHs(v9-(yBg>0*qhJjiO4$iQ%?)WQxhwPyIUPk!{j=MzZ3BYase~D z@}rmM8Bz!@GlIa0lPl=0q{2gT9(T#j`;6*G=ScTZsh&K)3~z!_+9(t6)f(kz#NbaY z9K!XA{W|e2s_DwT8_Aft>!>gBCnY939{y%-X%&rLa9QM8`A(=H-@}Pv0n2llHG;d0 z#0;LU$~Pvw zFMy6|{GgC2UxNcqHdE|#`?I+hOWMvM9mv{q2gj?)V>DWs+SdEbNN!@@n}?}Rr4w+Z z{TL}aTW+0QE$^%|FKY@f>4DYY&qUz->Wi@AUb2^b68u?}b->pg8LpbBdURS1LQg`u zBg$S4@Q^I3t$;g3N_o^FFI7_VS65#FjSgpxB^xFISiXHXb}bl|^gw~QGd#(LEgQde zJ?~(qH=5kM)!_P+5bLf_kh|+A$aKmy1C^rL>wF#8m`N<9I92#7dSd_CE4gRg1T04u zWc?p&2>z8U2M2zhqScyVuTRyOs^((?TNq2?5{7+W!^t9&C4Y5?l< zct(>!ghhMAD^pSOp$ms+wEpvX@;DanB%eu~a=NX|9MIdX-G;fMJd74iL}TXZ2&^Iq z0;BsJ<+|v}NA3cSE$iX5o?wwSTWe|T{d~as3k&q!&RWrk> z3}*B56lgVyO?%6)NfDs$J|16;CW8d){(3y}Pq^RMlCTROsCj+djp}@Ur;Xh%$kDb1 z?n%m6^R@qZ`|&Ouu~O@gC(5L~F-B?~O6YL9?K8g1TXo}R93_yrJK?RRxQi=6lJ&e~ zH6CYn7id=DhA-S2S52BN&|+y;_7xPqV@k$1L~c9~Gu9Vk5*yJEx~Tl^pDBNgDteRT zD2rdecI48N6!Xb3h;Ma`=3nH>nh)7^9Kg+G^v6Bd#|^}J-2fZU8OTi_%09LdL=dg)f{|sAxfIHyEMOekI`oRQ;PJylOFmX^ z$)^{CCFaXn&vz(g)t-;YjeQ0%3g+-9%AqQf%&u!rVd>NwWYpoj3{WL~d)j-m4ex#e zH}(FsrZM?wtI!l%UDqfFaVOGMwM=|78fbIk-e{unxAJn40X=s1k`<(Da^pl{(_PPp zvTNh4vniU52Nru(BFYa>D=P##7eU#)pnJzveyOK>oOI+|aS~0VyvJX8OQ!TqOB}^q zz8CQbwj@_Gv(f%kyo?0cD3fBB7mVFB07_+AlV09*og;Fdpzay)lF~L~H)?(=VZ8ED|DAy1Up zgEpitVlbYOyb!8m|9)N}1&hNT$0$1gv2azJOSeR*x#Mm`b{*ije7@1S>ULz&fQ4z9 z407=CTJ2W*nDX~3)`t-I#V+{y-!8&ilw_+9o&N6yKLU*jZ*jS?10!3o$}jL1iJUsV zFt$eaK28nqUUB^=zAj4$I=5VH`)>o71CAWM-c0d?+*v016$c2EqFs| zeA$2fO&rA5`n4!pB{wceXZa_L3I`YY?~UT#%oP8lGTdq6>lMm1tYNmQ<*)r1nC+Q! zvSUJ-UL?QjkHt;268+)0&pkN3$+Gb%0sa%3a7fwj26W0bq&!o4V)#Mek<<^X5-a5a zX0Iiy=6XA8Cu6_lr!mWl9YyO2pq;P$Vp~EU*uJ97z8e)vv8rJ{1SwggCQg0eBljl( zD56%n8R1&E5Ip@U^=yI9XpWa{6W1LzLsU?QbFnv2Ha4j(rC#59 z42uRBT5`LH6Bqs&$R!c!-Vc`J%r%u8(rio|ox98;AH4hW^%@i(a-lchYcz3)8YzsZ z)B@tyt-yTnnmF!Sf0`N#J`sW?*)OnEOG|c1ZN0jVqKE%;JTfDPLf6n8rK%@lcMb38 zJr-ys!*JG?VzzTrl%=<5odUBS4IgGU<(LHAb5i;N$BW=w$%%Z>M0>?>Ti5> zV{=}jXhHKm#^#GI{z@Ai$utcnU&ONRtm=pbW}lvwfS<-rAQ3)m7p7m6F}ixjYvLbj zKR85piH3NNC#SNXR|Yb^>Ma{Ue*vrJmZ=1lOkr~iiT7dG>G_6fv1D!GJ326i^^EFx zipKGFY?9I$&Qt#~D}bcsW_s3@C4)5av!Ot2@YqKRnw`}}R{LohAx0jt*sF@B0HM|< zR3>8HZ(;O59LJ!1g%Y9pp|o^En_X(f|7#(o#OtWbD#r<~PCq8j$6Tb6d!8EORejVk zAKOB-+GCTJBstSlRpU%M#|0hBWe(~1bIgM#rXR;>&T=*64_m!_U$&uYY>1X~sZ*kc zk^Tzn+QO0%b=7@KjDNg3v`xU8R`1KXmByF90em!`Uh{KAbB@$-w+`%2%2fMW10|7F z+JW65=d(i_bka6}F+$AcZDy7#|M1)zR)5zGJRX}>*lo)c(Ri#cligc&-tA4Y1NaX| z!DawI`0ziRRL7Cl$wTr7ibx9k*_=kY-(8+@1x3QDa;u`rxeK%~4?kyyI~~}3T%T`< z?RH_>{R-ny*nA-*BbN9JO?hRQ!Qn0TFY=C4Y)kdj^|jXomv!PYlPyw$(XGfV<#^;w zKzLJJj)d<(w=h%yAaDR5rT1r?_?gl^VAFDziiil&#KZ=MG~NmsRHa+%#=H8_1IJAh{Oqib^$NYnxzg3Dt?O$ag+ zR?#hAw^$}28C9Mnu0P`H+HHAz%gRuz8?SYoZtat;niFl}-+WtkH7_|YYb@JpsZCtj zgama`FcOhkO4jY@KqY~GRlg7bWszQ9y}_Is>W5!Vudj%JgTqB~ynmLEDhyE>@2kE} z(ZqFh{B-@4d0OcW2))fqqJ{^D&=e0usn03Jc% zzILvE)syYXtD1ewY2jh}PU3U1LS&y^#C92>SR-OPT{6c_Qw7GYBh1Z`1-{ZfNGFqu z!|@icrrR-%rjRQ06r}lO{rEina4WK(M!KFr%Nn!HjH|RLbUn$>YMJz_%PS?0;>Ybu z-*IrQ=HO?pIOqCRgO5{%SR>PHTTuID(vcbRqmm+^9DK(s!Bc_B;0ob2e-+-xr~RJ8 zQJOg-e=rMh&l+-1B|#*QelcFV;!hZOn(s}IO>5}%yDNnu?a%}=0sK3D=>T=l2DyI` zc)I@c$&X2S9&I&`+OE8)k~cW)Q~~XZ)*GDixyi)W7ST?`L2I6H!{__lR z-x>C(bsrMmcymd(vqg?K)Pj`;HD{4ul5?DnPaW%W%S2xmC)#c=W4BoHB{ImdiQBp$ z&RG8dD&o9rbM`spk(YhXp3$jB3dxQJ2cQ@k`d3snIpuSP*3-(=r1_DVT&Y!Wm-4AJ z9Yt)P?H*fsiol}-pDlqL{cSQdHGJsBZ6VE^G9M?L~C}{TMa+28{{f%o}$LCozySXotyn~-w%aTzw zs0bH&oB@m)xzsiHVdm4aJ5yBACj|ta0+=?zd1s#;jQ}GNa%D zxDI&R&!@QJtWRQnWmM`CFkPQJah`bTgY>HQ=&FA9=`oNo(yi*uS5ljHTjwBT=M_*l zmvFgPJw9)0sERi%S}KO~!XHq*!&J*7O2A0W6;9v}VtUn^yL)xBMosG~uIUeEs4OnG zESuZqRmzew9;KCQmSVao8u@ChtCB$;y-BM!^6q72z}k0h1CPX1A~@uMK5WAyZ8;g* zf4Y6?tOcwp1c91DRE7Q!I#i}oxv4yCn0=$zDCCNnRYZZeZ6xO%Mmef5-+68scC>g4 z$>>cz%Lg$=t@9nlanR$oDQme#yw|hGAo*2>-dXxE{5sOu-LhPHUnyx0FL8^2#y+Jq1|%7?eA062ibP+;YD4BIsOOh~@+|ak8=bw{;&wQ^lyYq;e!M$MU{h z1M?oet1+f%omF=j@B(LsU!m{#)rj*gzVu_au5-vf{{H~|dY)31x|g3&j&~cCqxTJ+ z<366X9-XK~9n-AezS>D7gP)~Uaq{lvf#i{%f6w)*_WOLz!H#?SpTo6CjSWX%hByny zYaz>R^6~PXc|O$`y^`iq>aDf;!Axy6UTK;aWn=fd7{yp7!9yBoLWIOPt6CKnvR^9sNaQ>7TSWg>`6` z%hcgXig}L=s!@<*?(@~N#s@riqg#|<{?Q&gvCup?+6UNLf417QDUF0nZWQ1iG5K+f zcdlplefV2*3u#*Qt@J9>JfCU|LuNjK0LKh^lb#2?dC$dPiPL;V@r?JIWVf^2BY|20nY_KzVO%2g9WXQe>d=o6jPBY%BP3*3WOg(48+EBoaLXHR zcFqAgKTdrGZE3nQeX`sFv3ZzMAEEkI9nZ=K%A+6^B=tGzU5|sbdAvb=bXk@geLme} ze>s38HyB>z=kckybv0s|Z<$%QNfFp`zM1vyR_)A_!pv0}V_m%c?@{_y2)}YBZQGhM zbGv{?QJT7bXxaAs#X-WKyUhjcPkVh7!YJ)ycm=v+a{x*8!R)-AJL0RQ!^ZndVSApv zM_kZ+$szf!6!KUeiaj&MM;a~M3Uj?&02(p?q{XLF)~Rdd!58nX{L6qFkC{rIIrJmm zxZfSy$d?u<*AqT zBx4x-06hg=`vKc{Z%v-*Bf49AnHCVHSk+3%NF9gqU}m@Vy&>*yt=j8OZ{G%JT*e@g zfc`At1J4GR!oDJo#@5xfOBtrMw#iF`k+&V+-W+s1_Q0=1)BIDT_?p?IouJhsP^w(@ zOmnvkGsm@a)Twhwtqvbfx44eh7+T%rfttc*jHxB@-Bcn7EBSaWwZM=Rlv z48!4gov$O*7T0bC-K^VQGuQ6pY3ts)>wSH6{{RfFzL#>kfGxZ{=l9;*#s^-XD5k?b z#*kx@Yo)bb3LT@@+mbmP9FOHu$E!nsxZ1lHZE|=zPu664m~P@+GM^iq_FSAX@6TcNWsLKfEP&mdt~mFh?Bzbv4(9ZD+PsY2mp0Ly07s555TFl|Rs) zl>zu~r)ifAmhh^{E?7H7v6SaI-O&CONSk&#s5CWuIMu#IUSkT|Ng2j}$*sQ)>3XH! zr6G^z(@-kKhYIT0`I!4-@ioWzcfj{IdUolxON&V3`I#9ZrVeu~t(eK@$M2}`k(1s{{V_KkL(MWnj3qD z+`eYO#DGt4UX{^V>g{J5TwZx5KseZPdUe3*_|-eDMqNrqFsr06`4pD4;=q==!PR!F}u=2tJNx(Vv zsch#zY5n4aRl_Mc=Z{gvS)jPc&I8sGlI`R41&OmH-=|n?OcmDuuO*fNsdK9t?X(62qvjhZ%QW?{T-7{RRPXkwpypDdZ>v7Re(eK}@{ zWN($n0|WETWv%b`A>n8cMqZW_xGyT)-yvZ1^w>RmE1@eqD2n2Wt{IL4Jz^h zr_?c5;HJ(+p7;j{o%(-k~^iiiZ$F+NPRrZ01-9X(k8eC!p_xP-xNIK!4I0+(?53e9nqJImx3})~2&_8p(yuCBWo= zvMRl^q~<9$d45niae%-5V@pt7jfr)6Ea566UGj8SJ45?(>*-O?tVkPkTls3ov+l|D z0~}LfylZ8WH7fD>WbT!Y0rto>oj$c|4bsPXF!QGhk%GH*enouovcU!m6EbPt-Lr4rjJ-3!y{@4gKFvfBMw~wz0~LakZ0!QcG zSM3leZL$}PNZC2y923_)>GdY(SEqP_#tD`Qu4MD0VY_ng0AnGJ4nW82QN!YUsP!dl zTfMgOwl+L#xAQ+vwTmUC=BK2i+sdr?Etv=*K>i*(=N)s9YEKRLPh5-6zLL(~FY;O<+iBoG|g$Jz26>WY;JR(l#gT5u1n%rZ<(T0nobm%Lja?mPf?tD z4A-1$zA(Of=Y6H9AYzA$Cc|8qRi^Mu! zzv27KIjven+Et~3MNc(>qT%$?M0T*e+oJXPfdF^z4r<|Z zo>nxquLehH;!Atm+ck>H&Ng_AkHl@ee;DddJoMmK595Clf5KONd3O!HlUu~&%#t`Z zvhFwsZ)}s+wKeaE&YmBV@t1RxuzcA>2m7ix#bfCj_1f59U0JkINwaj)Lmv!D=rj3> z?1k)d$m4a`j+1`S&ly{c`Hk}ORE((nb5a8)k9X!t2JbF1S_vB&&!`7E@8~N|U3>l# z?-XhGT9hlk+(&6}V~CcLFivD6xf%LkR9_hH?e#5c;_kvmy@5iZF<}D_?`PMsHKwL! z8xJxMEVHt)&m-o>O=OYe&9y=KhDR9y_pM1IklP*7?p085Px%#2;Dayj*s1jczI#(z zk#4MxI5Z(Y*%j6!2_?;(yhFcYj7I zWp>=eNHe$7(A6N^xNjO1+RAn@AmnxKDo7+T+cKzKvS8;J#s^QIP}d)sb03HZMk8$ zjp1V^=%U)q?boGN)2vqRR$no9Nzk_$J--@OV{MmWVTjqYw6G)&{i~tV;7xteKS`yy;@bfjiZg4GC-0wKkEm#rAYTQ^zpVOLnmCZ z$IVl->|+xJRcx+3eg2*57Kle9h|2_L`2pw;r}C+zsP@s1@Ul z8Ft9BDI<4r+L+@VM3T}tt~Ri5ag1~AO4i#;0vHfE$UKUvaI#LJWNsHFPDV5DS{C!4 zHC49l>N5QY`830+Drx0oT%G>_FDf{uBxlWRZdY!g^s5ux>=FE`IL2|w{{TEw+^dCe znPgLj3^?Mm8rY#Nqf9n!D!JqPqpwra1~)N(mJC|Q+vaLn9e10Py^k>%89YcSxBYlUyAt*j|@jT0}kcK~kd{vS$nBFIKS zBmw~kf$dG6ecvl8<+_kM(^h3>#zOAu4>W0g08~2;-hDCFxc>kgd^Nb&HEDG#UlMB? zKba6ljt1Wta8B1$^*O=DGm7k2<_-6NU)G`+-_-p70CuQeN0E5D;ZMXZYr@xhdGQ9H zt6I3g`$`C|7zP*{vDX}*rUpBCCYh?+{4F}Rm#JxbX0>&_e7ScCA&lcK^A3M1_n(cQ z2Jb#3!mVMfURm62SiZ{4e$Ou4;E)K%Ufpm#E5mI*9UlYu;#*yA81Aj~SWV5!20m1P zfwg*M79t958*4I}5 z0EBYl9R$M`r80KnTO)9YSa`#gMC{{Vzj!dHo@SkGsm!*KFJbck6~Jd_{~ ztH(~&x$!sll<@j^QsONaQn+nO;xqPViVeXVI2*D!{6#HO4fH)5!|~o*=oXOPvdwiI zAtsf04&V%)-A^?o<)k-uEgj4&Exf?123^R&b|d_2i?H~Tz8&yyhv3zx)SCNLL|JbQ zr^yVD)6B*I=hND#{4DWw)*dX^bRA1l7jt>-HKfJx2;(Y>eE|m)UhGyR_@(imPw*z0 ztJy(tlWNwmByd|O!y~pjANEJh_*ag2SN4zbAA~ILEn|}2 z@2&hL@Xv^KkL^3HGCP~L3zu@+WWnQd=LGcR*Ax3m{5!YQv?;ZP+iO0P7zq?Hs8&*N zN$JoYrkd3W_AdMr{h{>_h&r&+@3i<U&p){0;c6XYiL()-EqCTIxxy5*VUGw9I$zAU7a($*%9>_l`f|WB$z3 z>YiFzwbQO+-WlU7DF-BX;18kCdZ?hW^2CVCD?4s2xUt;bPpw#%^B|5*xFuhZ20Dp(BD%4i8U)|f=#|)CmbV5Xkq_m8C zFR9OJhvqeIrKu*5RFS7Kc`-AR!ZpA}=b-7wrB#tE#ml5ECJ=muzFrRklTfykNtvUT zIU{u?Bti(m^dlS|zm-G#$1D4?%DK+d$?5G?5fiS+#^BvJIbMRfpB%~N+*zzEBTS*d zYyrl7f6q$jCr!J*)(6@K)7aN5;?o`0vt|ozD4Y=8dGx9!_dEXp0c$#gSudGmXCzRl zLoAb#B$)huY}Zd7v81N00zI5}GCLM87~3Gv8UB^Q>6)~*`ebWsBonk_I|7pGJwlQO zee0srJY98bHhi0X#Z?EIgBU!X$L8zau#|3GWuet;I_8?ODTh#+&f&`fWI!2uV>rmE zw4GvYJy9NO9a0gLt=cA=`#G)T+qW>b<$n8s z!9B5xq2VU}&c2(>x4ee~XbmFBrv&2xPDgL>uJ23KE!WHYBKgyD%)vId(;l@Pw$QF; zxtHMkk0|}B7LwHlf6<=YDx88cN7tXqlf+RhlKGm2znZ(h*Czu6cE&4i(k(ta_HCC| zs?1(okipv=sol;GUv4V5h%QB)tSquaByu?(Uy@ar`wWqfO{{XBf zZ>QJO)0)xIG|M;E;<}pR=`IwrZQNOKN#GInG}M_!ur~9?&_g^h$gQ2B@)tdL_pXn_ z+RU0$6Z6|61DQ@2U>uC|{HveW^{o>@FuY(}s~?mrZfP6;0M=>|;v0bv+b)!OHw5`8 zV$M15kHUsjVs{r>)G%yzk!6LsQh8JEYPxuK)uwB!bz2iZ%*h)5?7vcR(0?ky(!51! zcPH;ImflFnQeiP19DPqu0kgEVUuXE2h z{*_T<=qHl9<9k-y99a2fK9zq@nP!!@x0P@o?lx92*PQhIYObT@;CXU+jK6pflRvFo z(^^YFB)Endp^<(<{{X}6ao^gAv7*(rl(#unhvie9>T(-C;QQ3qT4eG_ts0o4L59KS zimxTaR~IU6*{zClL4E-l?fO=vcP!T1MBiwBq5FOwzl~LwK|PGevuKsMW|6++j;Hdf z7m>|xAKE@vlQ`jUnf3nw>sLW#J4bPh^NfN<0H;cj>Iz|wP1~|g6ach?q0PZ*bU**jgntYeAvcl5G61SME)Uoy^t!oh7KudY4<-~bnyNZg(v$)hEzM5~g86jYz zIJSjIzK4U)y)o`hc@DLv#cwRpx7qF!%tvfw;E}~f(@AujcVV9dk~qaE@&&uWs} z#CO**7+Pue%-&y@w|5_3=j-oOE+uPrXOnA3(2R7)wkWwgrQJgM2;CV0RgiL+`-j)x zHD2!NCwTIzi=CWuPhL+n)^wZ%Vsp0(=%CemSl043`JEjJQN~B(KqfYO3t3)4=R$bv z)9|W#j*}gwpPA+|t9{>}A-#<{c3XL*Uof{k=Zep{mN=r5Gc3&`5)ht;9cepUH#4TQ zjPv%GPVbvxJw5a5^r(^KXp%vYFnByObNsz2*XbN79Fut^TO=P(sq0yfuE6klVlx{% zVLAC+4z(95+6#L+$$qj(3Q2|vPI2q`Rcl*8_L$vOqgdN__eOnbhUKQ4cM8fsi;d&k z>FG^}S+zHkKupTZf?H?H`R1i+%Im4P7*BN^am^>qlI5a1Nc7EGK`pa1e=p2-rVq@B zd*t!Y=~!~#t;!Zjzk0tnJS+FBt$Nei?Ntr1<)jjBc{BVVpXX0ddldCWiWHTaJ(nDS zq<~u_^XXaEdgl9>>}HWH?ic1oP#bXdHPTyJ!>vvBi;p@#n`k~_VxCq>Q`M2O;%wYlFU53t`W*UH)Qn!hSDtW zl0{&y%syY3kiTA)&+A&nx?M)1%IZiYC3c|<#~;Lceul1Sz9F?T`ErS2o=5p($0bM5 zYsoUfkZl`Rp5y7#s{Bj%AK_mMX~}tE zd3hww3lxe%JeHFO8RsMe*PI&Ona?B3{5N49tE<~u-dN3XYq+~QqcLNHh1#dLOIK+06D6+P_Lcx=0)4o_7zDG-*YZ)L8p;|{{VWXwVQfzxtk-`993}uRnG1S`A$DN zcAF~4D}1lJf%4<0=TuIwQ&c-5ZQbRcP;gJRL`ybKcMwX0pOl}ugJ4lc*Ibb(zC#FZI>s3K8sBAFWc=k1J z-Nn-|Rb9i97~}eMpgCGayZa@w3en7$Q837LZb#I1ra?E^rN$p?jjD6Xk5NpL+{DqU zw(`S2Cm8nUpURqytU|ta-;7C9$**Rq0YzyOUdS z6MVQW$jIsKRu^21K;JVfDI=bE=|$AA+t{;QN#(B?EPW43qjPT#=~-1nNsKTD6)Up~ zmSDSBWi93|-nnB*d4Fox4f3l=j1UhES@zm`&dSop-!~&1gO9?s8VD^RLXhFf+nnPf zjR}vDU8ao`?o=NpM?3@VO;W_hLq{Ux0olG~?N*XV;#ZBKS1po`2SHKcBvr&{vS*y9 z`QtT1*5j@%-Qz(aMc|R1dF{u*u+L9+*D0PHUMYv}TS;8Dj&VPh(RTNn$@UZ9M=v$8IV+SrQ4( zU74i*BkAu++!fhIC)s+^eA}30?+0kly+f?WBzlBQ-N*rc@B~$>*527)lqt?bWAHT% zHDowohuIb(+BJt&~7v+PTCX(97B z9#7r$sU4Xc7z=^H6#oE~0^&yLoG`|H>Io)k4^C8P9=ul!k+Czk%-P)DnLRzf15US0 z$GSHBbI1PxUZIXpv@wV**<{OUDlg4$if}}oIXrWYxgPb|d|mi+H^naq%ccFg zYe?jgCHX#m*f{`>G6@;_*N^-Q_%-8S1AJ0Gb-1z86`3w%l0_!*7w%&m=Q#AoHBP|S zL+Cl>Se8bScSp6bicaj~8TwbtUJ}%G9d3URX+L1Q)b6!|<$1gR0C=PmjOQIr4srk- z*VT5%1dQhcY0vrXT+hTGiMkiVNF#?=)FZQ!>vCGJm${hZIl$ln>TnH8xhVPY_*2Ed z4m>k8uBoUtm#6AV>GlUJBi%Rg1p_$alh11GKWEQ@w;$SVsd$4=w3^XXUImehFn*)t z2Oo=ibk9Zj0dl_?d|#<+8s*w**IIrBoEQOP1fQHB>Ba|7uQlzfw!#SG{oHY`7YF6_ z$NvDRRax6m1s?NFjy6R%84` z74*WKp4Ibrhx}Ekcu-6In|*a*=Kv%zHa7r%T>UF|!*JhxZ}^F6Z>#E84L#BFn&7A_ z96)E}UV}L7J?OJSXBB;O=E|%$CVzNva8y^W=~`Zrp9HTwKX0o?aj5H{H1O<$0s|eqXu|{{XJ5?f(Er!!tJ> zM^o%+v)p~Ic5@uCu{*rC`^%G&L^iE0*3GSgyP5O%N4;of>`0c|?L5t;h#ZnSb6sb{ zojOAW-NL~%tr#1;wB4~gvF-q@-8%LgO+H9&2l~O40B1gf>0KYgE9q^ttwE!>lGMp3 zl_*#H;EaLv;809nrlj`qJ-n;?*)F7TVP$XKf$94FYozfGrrKSPh32u5p=%pemR8`r zH%3M$KHvqxu1ebJqjqJHl~wlw>KVB7^z^B&oo56o+VdU;e)r*1t@SU^v8-O*U+Q-g zTwFZ|I0OYA_+E2(Ym!mm9lM%6AHMkJmVkym4om|{8%0OWB zmA6c)7;g7pZ>@4(FS%FoAC>1bE5@!)JL9EPbs>h3?i=Md87d|Lhf(Zr4AYuuT#=IH}M8L?<`5D%@Uozyh#St^gQ67@UGg+QnT>o@7fk^vdNW+ zOXGq%k6QCsyi(KYHn9si=X*&Vi|h)e4@GaG2dAxcR(?NA{Q+jU@?w=323Ck{DbqRa z*N)ZCDt328MqSRT&t15@f=RBfAD1h>M$b-p!00$96|)wvr^byW*DG|fsX;Eo!Swby zt}f5U7MDgFS!1!Zja(33a~xpy+;jB*0PEF@36j$Nq_>hB%Krd$UvzEy@;UEQ%YDkZ z*WT;;U7d_DM+%d1k+tF}yS{VIf0b@{BU7`Te3iGkvsPWZ|-dSl6Pkv2YQ}UMD{%n_QuxoMz@OI zSz64GJ8N$92?L=cjCJ)ntxHQq)*3rYh}j^M3X6mLt~!oRYo2XJ`r_H9v$pdg+FyKf zoUvXy554$S_lB?TFDz|M+RbZoHh*?TB#3ke7{JfJB9_LN=v%z-f7vhANG40L%o&;E z`J)~2k6(J|Y^-Iqe0hRE-!M`*Rr;RvY12cd#5ZMGpA6*g1Fcw;Njn1!(Xy{4qHO*L z>qey9v2$ zUot(oKDqvak1<%b#@gVt#hwV(FO)8N`r@FNN40jy&l`>kf^k%0p5bp|+6R}MA1|DN z-xYFQL82`Yg`4L9e7t~Y8CvevDK`19F!_2O6jf`6v$l)NGc;tjRItwPVOmq`2*YVz ztiuENkKvlj@eph0NLlwrncI~Cm;V5*LIRD&+Pg=YB9C@JZiRln)X@th0lsJITLU}) z01A%lL{kptBXbNlJg}i4^%a_=2cu{~U(9Ib08dj5bH(_uXpMDKU#_CUKWRv&J8?pII3~n9% zoF4saHd|{pxcfTnlW^UKT6WnBq)*%uewD8<~a-h0PC## z`-P4O<4_lP$sqmVQ=wa;q+&*yB;6113Bi*ej&b;k$h`YQYhGM`EJ}Gl!o#uYOBSUq z+>$`vS&lMC?uq$Vo=>eyaXPyBaqlVsId5uSf?j3oO(ya?v{j5?m0(+(1E1I0yf^lQ z{kNg;R<7C~h3r>Q)U4QvuF9DriN^(FjD7Ms%M-MA&u-K9pZJe?@W0?Tsj6DsNVk{R zu(WV;$YjcrJqS(Q`q#+56w*$KVGNQh3+sr~%H-hfJcZ}b5n9rP%&Jtjhf#a`U3_7e zQ5R2nsUiXhkI#ZEk9FDZcscD}qwpjC3JE@=;w002b7WM^*!xeB;j&= zo`b^m9dg!twX<2Fl0+P-;IST^2OU2uW$uS>;)@1Ze7Nou<|!2O5$s3xuBS#eGF2VV z&|OTXs|+`mcM-{BaDr=jp>oM89zh2^zs@^D{h@gtmn0G0G*Q3K4^}ui&TGa$V6Tf( z_?y65u7i5b_RT$*#xeIC5FC97+TPsf*1dXP5zSUcIXXry4JgQrCzL1%^Yf|6z%zpi;i10mu2x0 ztgL2LhU4t&*ufx@Ir+0y%0!wpHP02_Uig9)wV7dDWuuqo+k=uaDnA+c;_fS3h4PuA z*j5(|cln)gtAaQj^H{f@IFiyhWU>2HY}V|oXN_1zlg7+r9rKatTTg=93}tnp@i?<4jD`O%^1EQHCU({o(Ibyg`0-p9$Yd6k^sp zQysfS2_<7vbCI5aboLmj^qWhV?&ZFk-qaXdb|idn?fCvx&);d2XjWQ`5zQpFH}CSo z&UVK9u)}xYWAOH_nCfD3?GXoZsoF;z<1}Af8~IhF$zsAF_}TyfV4m3bqQzti-@alG z%24O`WK`zvX!L8OGi|h#0WuN>>>Q88R;d{4abRbT;Q7I%Wn3l)-R6^1WrkJY235x$ z$Gs)PvN&(vHtaCR@p@G&&oSBAmvdmSAoTXCM6$G>I^$?626Irux!(i(xf$pxL@En6 z8CA{+#?nnHDvPbVwub6Qr#w&u@voUL-{p=-HDVigk%sM~Xc*a?Vyi$$pXP4)Gq)$x z{CicD62i=5Wo^Gsl)+zdC$ckTjI0P5JboYHNoNd)-UG1&HpN1yzl>Q_nppYh-JW;vd~CDl=^}z_Ti=Z2Qi=zO^;K%Oacx z&Ub`gmA$CDTLESjS3=*#!k$3`{{YwNS~gY;mvH%uC$FGzNBR7!jBKqF1ZCZU!Rin6 ztq64)3nNI(%%=f>;17C-p?VTeI$CNnM(u`EjQS7r#a`3pYopH4tHQsp`Sq;XFIMjR z&X)`Fft+W7>MLR#8&l=&5#u6Gho5Rg)OM+2v%#`s=0^QfJ^JRPj?CQKFPFP$z&l6X zYSmn6exUb3&$}&4t>u?<t^kPkzXRxS*2wio8x*BpaMXjTbXu&cNn5$V|dXzDom4zqtgGB&(yx%;C4 z4@^^uD=5wv9Y^?@W9kcMEHSdS=^JQa_fKBF-~DQm?(7JZHWl;f{zX@)?9dV=x!OZ* z1CE(r{{U53i2@!~nMWA)_o(e7jsqBUW4vH8j`bwcBxEjk6+9O2*NQXV~BKJ}Zaq?X#kHUyUCK-dm8o_f{cB$G-cl%AN&Q9Evxo8;WXu17UH0w}G@ z$!yD&+^xHwr#{q+7urK)F;yK-bBdlzB|sZ)dB@;+sN|7ic4ch)6OW;yz&TM6aVM5K zec^`16x(?eF5}Vp1kp;tc^_Eo8ttEl?W2`s1ZpNj%9p=Ocmb z>;C}js4jH-OU85<``{M$l-V( z1J5Mlxg9s-D*R3H#*?S$FEz%SYaiQh?h5&TCJLl}ypx`B(z{Jk#vM}1NUkGShIA-Z z*KlBaV!Si}_Zcf7uZ zNrE7DlHD>-PC9|@UoHGgI)eCrOqW`>)E7{i7JS|#d57j8{Kvl?Fb*s0tC<9Fvq{R5 zHh?-;%^$SaiEX@7@gi$@=DD|BCLsfv5aEw3Hjhqv{VM#4)Z{)M>bD*gc(qF%Py04W z50>oGVORsgGK^##=bkbvf5l%Bbw3bz)*0_LL-svCKQesLysezS2Ohw4j8_11%jLT- zmWO`ae@^u-h$e?p5Zkjz(haE;L+>%;0D98YI-Zx|{{W6tLE-&U&r;PSyo%=B#cvYZ z6$<3_+&g2R(!AwutbeoC;@MPE?R|Gm9v8YEi zoy02*^pQhogDe{)01t7~k?l?|xi3Sn@%Qa#uBVIdzp<`-y)HRbZHXRQ$g9^Usa9;B zc>^6P=f{7Ewtgh=7lpMbB#-ycB!yi0jFKu4z>efLdiz(Hc!R+gmV-}gr}9Rm13)Aj zcI4pXcELRV08W+YU$qB@?EWA8HSqS0Zq}^O$O`RDF~V}=x6E^s*MU^D74$qdd0zHL zk)&psn=Z}N{{Wv#t!^aqe6KN=lDQr8)~0zG%#5-W+Pz5w6)d1x{?%f_TXc!V$Cn^yAVymbryMZ+dsCLqNpDy- z)mabmjO;x|DwHmk_X?7)%(*NAaCtcA+NRo;v@FdWaa>6r=4kPiW$F*LI66q`tMfM8 z1}ltXpIVMf&oMq|PU3#*kIUYiV%V~68+?`oFgYKc3gERX+>+_b4>NWfoPM>+_<~q% zJVUj&P5ZS_RQ#$cFi*|jkzU9IrXk9#))VD012Ja*v!{9@GN1ZWZDZA%XalY zrCfI=O2t-@LTqUSoc0GN*OOLF%pw(Bw(t4ryP)*OI@ETy%CDc4^T2k%KaEcftSN80 zJ7$s4XFrMW-nHD%m~#mkw>89%l~Ik{DEfB%Yf{oyx%pw4mS)17KQoW%RqYO+4XkrC zF4r7~Qg(-K*!oghYDU?lR*!6qGm-xQERU$DE1Rjc7l<`aEv*^+sCib2n`l0Ow_nz` zd^RlfpD677H#XJ|R#{{WL+H--E)b*Ab+Y`8Ibc5VSf^D8&?9-iW-lG~RV zo$taw7Cwb}7MEwG$8{al+oZXdb4o*h52AzD72DkSTkN-wZ>PcbKRRIZLvVOtMs~*B zbR_Xy4ukO)JqJ;-zM6RqmeL7PVq9-v#P4q0b^up@W#a397i)_($oo#xNs2BG4sc1& z2frq{pXhwGKZ|RTDwO3J6*Ac9HZX{8h1GZi` z!+T@BX5(# zgY###JDM60>d3oXy9RUfWMq$ARMATx+xJA5z-IhBx`9IS11pg;5$~*_R6yO?jgG_wxDAcx-mhv7B(*HNiE)C* zj%tncLg=(HyZdcDY9XfHTH7*{<+lt=5X^Y&DLaOiB6#GDfn_~#OP&rXw{01=Eb6jJ z56lSX^QyY8qb8pi+ZwcNrP#R3CmjBMl@6D63AOVhNdn9P!*Ri+_X524FDy-!K&&to z4^E&DQ<{#}=%S&FMGQII%~!@E=bjuHyL5kf%N*)>Nhf8#VxyS-H(*u zX0s&PVP%ze#=gCcNTON0)v&n|O|^!0vlEl-DjV6F8&;Z0m@iPuAJyG6*1`V4*J>r>PW+2ps6 zYb*}WBYyA)z{mG~p7htU@}}Cmnm(bko_mbdP|W^o`Gd)jh5?u6L(`}|J%>YDk!rBn zSb$kY!zn4ffL#72lz{S2+mlba)_-S+_QfXMH&TM)O``@h`IjfJ8E`Y(t$gRLTS;=m z$$hQ2YOonnF_3HR8}$DGgvY~|+HS8KU0GaPw0D6)W!Ojr}%yOiJuJhKZLru zu)F(2+IVu-ccnf{n9n1T#zLGhIOjgq(MD!9Bh>R<15I5zTZsO`(Yr`XNh$f|&kc^) z$ThbCRAm8nff+Vog_aHyh(Ifp||q)7AJv(+C8#PGtc4Dz4uYDlT^0|Wo2b;#zh}9dgSw1 zUj;rKTKo?9XK!mXcJ~^_uzt~dD}Y3OeoXL3&B+{&gSBoO_+0GIl<|TK1|S}tde;?A zS<@Y^BKUIZ+SAJyO(Mp{iaU-$;A0;2x0W|LJ)9;xcDQBvKtYnAXFWRA%S}~pY@?1i zaW^5PR^R6H*dCQ??#dl1^=7$~$k;wd>NC`EIsB^~wC!`IcMDA-;xpt0*a^rO zV~&0M)RAje_E0s#-dnQ90XdL-!12#NrDx7d%-0yR$y~XNvh$xpdVMO0k)PtJX0X!a zxV#A@tfnwahTO#Pdj5jAo6TZ-vjcsSYm3-1mPRqNFQ!K)1o~H^Y914~*R38kn$}e= z8_Ky&*cj+AGtaGY+NXt~(!4;i&3KkqP_9IwOGX>hJRE&9_}4`?b5B+p42veG9NLAu zM+%anCt)L!K5lr=UOBA)03Z07N0)C8l)Ssm1hEW6#{^@zKJ|0LS17(DxD!ursIxeB zyI9Jp9-tn3^u=fVW@P@|m7|&FR@zYPO{9)F?oaqvL`;qoSJmdfxF$&L)us+AFRg*CwJC$R0;O+avo-vGmRiS%pZ~cul%e1PT z?HB+LLFx3Z(le5>8>q zNR{~*AcOMNXl7WJ#Zo-1WsY)AbDFPX3A$~kY;sA)K>l?jGi>=;fo8`}1xCb~6?U%W zKR<3MYD|YuY;7lvW>y@K3wnQAnRg**)G&>{=wXBS;;da-ZdiQh%EnFzY~&gu!&(0E zRh48fxEyW3`p^nj5(sty*y97gYS-}XoyFw8xS4H4XD(TJ9C~-CUDc zBj1B2eSH?3`i|s_Y;s2`51fxSzT@{uGc$9?%uH5D3c-aX^bujgXRK3<(5|x%A?;>|$%YMCzXYv|y~c$;0KnRpHT?rL=lTS6JMxh<}na<17QBLnfl z9@TeGEwQ89$6OG93{_b~&vPS5^2lZ_m2RH6tq7$6DM8l06UfbmVbC!=0nd7qNa{2w zjt$c^&9q>!&lN^lnrO$DaLm!sn0*n{Lawl(5OhI2E6+JdqgI85SI1GZFKD zoX`(V3lZF0F^zVHjx&N(@ZIx@eYA2m?5^cekU+*Ny{!I9h4UG+{q8b;pVqF6&C9eY zV8fBVq5!s4DWB5RPm+Tr%vSrLu>Sx(YPsJq+{~=X+gRgiB7=IcGNh~f#w27ZV1FNKYC5Uf z-+77apPHmR#aN`3T*s9Qk(OLzlhc|>K#FBj%_il^Is3m_C5~%==%?kzO5}~l+dp5@ zqPUE$rrD!b{vDpbr2r&Xi7O0n$ATO9aZ%51WGr`Y$me+Aant$KD7$4`?i)sN+#mL- z49jnHJjIcpu0iYVRcn>xCA-F|*7=bRtsNS4j??DS7^!HdUX7&YC^H@U98@OcK-kzRb}w?oVv)=8rBIfl0PYDBP^?& z;1mA<>oqj{WRq&NhxodIpT>)H8X}e*tCd`Twd>ZgE&L^Kr+B{iSW?nmUc#2`zXU{z zNdbHNoYvIswDjeDzhC~nS9v&7_mzhP^OO9j*21;WF)bM3nV0U2*UaCw7L#tj6TZ=J zB%XBE$tB7$$cefE?egP;UrhO!n+h159x^$v4%NI7Z>;{&;v*#5lx&TAe7I7Z&kDH6 z`9~ZMY1xLoPZqhc`xG(BAqv+Y!lW}``wr*Rt$Me?KiT(M)4nR`y4}UMm!c)J%pHK= z8?qHp$<#L>@CY68(!C#7_z&UzU&s1>rEvZ9kc7ZfI zxnhh*%6;qR{{Y(8!dCtexX?7K8>`EhZEcy;&$wx%K+bXrKS5tYYo0G{H^lm0oBO%0 zujF@i2b6(SmUGTWRRi(#ubuw@Y}pp`;z#b;nrnMyQsaTnPCk{aNP8YY+p@)p>7CjB zv`Hu*-ubv08Qt{73oA1G+{i``u%wrCZo7VL9CC45q)(Y9l`L$mzjfor(U0X`lknjh zZw8p=+nEcU#PuDso-5BZiKDf;+|i_rq@AL@Gr@2}{{RSbNgn0h!v^d!K?4Kp*V>ea z9^`hnO>g9~{`zZI`H-$tjx(I|k^HH{UQJs1P4>{+vmCD9lmVKjapl@-lS6K0kZxWa zWDYumQOO&-C{{bOfPR%dN-s>)TIvOt8>HYe_X8rLd$}Z-F=6tqHva$#KJ;Be%)fY+ zQG&SXQGK3Be}YKMC@3+CnE^G#9$mbvBx3;Y2iK3~UVW=e1lr`!ZtCgg05<%~yBOp3 zuSFJ@7i+dP^BI(`GEU+2t_Q?=JentoZtQ%x?PggvylSCvah{#4NL-0Au~?^-&9aY=HLhFIhXa5>t*6O3c0tx}TGQwAC)W(~MtbnI%p$t23LZDJX?80U=t z0Gw9FdKz9SZ9d-ME}wNJ+A=0ySoX3xQM?{I6N=4^h}?c|agYy8bfGQ$qZ=`48Znku z$Xt8X=%cZaLS(?$ji?cV~X_q0!(da=LJ^d-)2!Cil5qt`>yRq>0sSS_zkwbSg+oXgMouNx) zE;4h$?de>Mw{3SjTr$Zdk-IdeSw8y~Cph|(_044{+|y&G(_Zd+{)Y@>$0;*JWiU9nN;ZImuJh4`an~P)xTrvP~ppNrJdPcO8lU02<%>FWEG> z?WQjblcE$Wovn^>yFP&NgHYknYFeE=zlil~jjMk@nG9*R+_&6deH+rX^uHZRrz1ma zFoqr-_qH;9znyTy#1eRQ8_BoxS@9TIiQpe^Y*Q??=&#aQkpakTv_%Krf2CbhNH{@BlO zrVtj^G=0mDM(i_M(|EcuslzatZRBB+C4HNaa#(iFWh!Qol4qhtt!~oeQ9O52u>Sy9 zP+{s`QKbKnSbgg2>0IPNL zbLIeli<5#6Pw=em(Tzyyv`dKYuPxeL(n9>5#B}Y9)`j@ByS`&@BD7&}#lBpgc*S#Z zU&ntUy0XTk-X!NY@UiK^bm&EQnWN4SnX(fjS8KaaP4b^F z=3r0tprQ!atm@})nU9!-@9X(dHn(dt{hxQ3$oc!*uyA?$;}u;lnn2q&x<;92k-WTm zbL&_-Z;Gt$HOXN`Xd_&fEC6XA1F!Txf~S~LiD$%qC;JS7IBsN*Sj=x3FuIG4TjiI=S5Eng{t^gjjjpB=0E$&r(rjkZ1S8EOc9dpwk{MDZHXhd-u2_#j%uU1EtUpO=1f?cWrdRnLU}58Ft(PMF$zxboWNm(G-f+jcr~IsxCB z%uRCEcJl0SzDt!Lu#IM8o&d-oXVR))MRg{f<c8Rz+-U{{4`8B1kYudHexSmTxbz`$F3btB4dVqf_;dJ>{3st#aE^9bne3L}D zRL}c8eXuJ^eL-VL?xPF)#lo_2AqSzy2e*102kjBnYTheUvoS++C9Tw;?Ex8CMn8m( z4k*$!OQ(UOX{4Mt%ObEFn>{(=xmmnp1iEZ3c+Dir8Z0udR~^neb?Z-q#!&s4e72NF z#tcuA55Irbr`fv?ob05X?qXPOBHJ5$xZ%0y_-f9pd-gpzLbjIcCz<7h~J;)$$^syqQOv3lH4Mw><&RBy;&zP3MceNvf;c-x*psmukf-`MYt)1aqD# z#+W*nI$dX7j>^^TW18m9Wu2L`F=ixnUNgrv&ubTuYq!OgM~*faK4A}^bKa!VAh~Ja z`*d1-kg~8zB#fzCckS|yxb~_#wuo$E-7l7{l6FU(p?N)e5$J1LYQ{2=Yr}doYc~lT zb6LLEE4o?4agTmYR`I2yHS;WzK+K@AWN{>J-%xqYOQ-2q)>;&rmzN|udu|?X&zYMY z7y6O>`g8iU>vIfvk%^H3a8t_>ocz3=zvElQ7+lNOt?r|;%p0x>9m=5K52bEtHWymQ zgKrgPw2tL%M3ecf6-XouDL=%01z{`5k;j(vHjaHgdRIxHt(;y1)~1$5R<*Ksfq#lg zSb(D#=r?4KL0Uvo)WXv3$%R8I_BbcE){|JXF_k~^$FT#yzojj^>_~Tf&9G#Sx%R2& zoGbZ%!u%2Ul#g0&Bw3=Jyrj-D8Afnhtv*Ot&E{<`&cqUWk4n+f^w{nL868qJ1mGT6 z_WXT)t2)kXKP7@@nmM*Qv5kf}2d_%ddkFkJ3N*oGnp6z2ZqJwQ z)aYy$AgZzxHtgj800BL*>+jN|)Dkw!%G;zTu6h3e6aFbe3yoe7Tujx~Rv$1o2g+i;cRClT`C1M%nwk z=LBJt{eK#nXKRqVRJJ)_NF{xZRk=;yF_K1*9(Q!dx3yT31~}WxZUCI)aOyt_TM4VX z6ERl#8JR-;><-?Q&}i{Obt_pmN%F`&g06bjeU;gjRy&AROM*t(7tMXNM*raN?w7~Y$g|hw#oavpZqP};d!m2m!I^1R`Hujy8&3x7JS%3e*m&-Vw{)AOmby}@@GZmV;- zxnQG@#;n}5fPBF2TyvfQ^#ZE-Vl>*W-!LGBKX$CjjF!lMg>i$Q(w>8heM+}5Vf@9~ z+mFrw=zDQO?!#_uD-KTF;P<4O>P^bnKQ}ld^662>I}_z@ZaqoC6uFA(T$KEqLn^OK zgUJQtZGxh6LE?7@4G4n4BeMdf&rDP#y{o5|! ztGEWwuj5dd{PmHT?aw#{ofJFdWoA`iGm>`k>Gc#!%l373>x|*OKDnedVliPWtx$@$-BAkkd+Vusu{9yN%lQ^ z*P3X*2Q`a-h#n-@q}46pn^Zv!l#xbRt%vupNcn&Ocg{)UrE%U1{jR^U9^M}k+06d{ zF%n%wHuK0IA^m;*265|O4gM!u{8-Z_)HL{RA+uS0uxDH`d}Q?NjM7bk%V^)TZPeP_ z*IKWPHH}OC39Vyt3cO{HBpu(7>&|P`bPXyE2T6+7Hj-g#iyFxx%SZsnC)DHhtnF9C zdVhuN=DXCcW3#n`iDYk-U~)dcL0b^ax3;l7ZRSSG8aEij0y_Rwd6UXPsn}ZTHqt{h zD$rS|caPzUm=i4wWz(L_b#J2U?A zdN%-8oEm@H?Cu$4RA}%(Y;HO99qSh1*`)?Ik-5eI>Hh%Mtt;EiS|S7q`WZ`|cck+M_J=d}fTl`d{P#g1<=)w6;!IqTGZ zRF5>%T7BkUC>#bI277)rZr)o>I?v9MSYAbZGzD8MIT_A6cl@dcz57bC?hL3lM!Cp2 z@0@ymG=QkjbjTLoV!KbuOJg4S^yavYQ|%WT)ze%`ZmvAiWtmAiY@SK3`R_E_H(2(s zmW%t@6^~5%d-Sh1Yxy4H=%JE0ZkUprh8c5^J@MAHftOotrz=G#96j7h8Zj9YC`RoW?zy(c92FEt%kRaWAd6-k=HV;fGVqc1Cx>NYOYn$ zQACkXyK!u&I|$%bg^I&Eq=#&IZ}n)$X+6E_Vl3>YRclx#Ax=n;jQVFE#Zz0`Lv}Z9 zNOyhRr*_|5)ZbEKT(#1jZ)2KonkaU(TTT}p!5@ujY4%N~&i4$<90Zm~&~nZX9Crit zs<%%JECh1-+yxA%SL#3d^?Sq?7Z&oz=R+hh-@-0p4y8nh#~EDz00}C4V>zHMSGw0` z^P`sCriMi)B=yg(YidnlXVapR&Pgt>0RI3;44*1zAOVi2fn58Lj#0kr4Cm=x27{$ysoS&s~`c15N7Qz;|`%Sz|N16T5IRhQP`t_-*YRhwF941em+_GEj8-8xM zZpZWdDqVv8Np4DwjG{@Vk(r+aotPhN(GTPinwl6wK1w z$8F~iF#h>5_x^8Qqn;~T3z=TxS1TMc!bt(}6rRKBntZoH=495ev=1C}Ftt@+S^FX9 z1CMUi&`qUTY4(xaUEE7?xq*sEm+s_tR^;*TT%FOAQY+?1ADtP@iZB5=>UsYFJXD(h z0F523;kCFzx7%33xena+A75cnD3$Fkp}DMH9V+R(nC801MiqdO22UsO&mT(I(>zZy zG;yq!v$C{X11yV=Q&s!9aan7LPZe^ zXx03zry1{@D)AhN8N7Q_^LcDB z7$5*f41KCf?2L2lcAc`EBl|w^-pTv`LjvIN`l&JsVMu&qkSk zz`LZAWRkzkgr0JGW7e91Do0f|sSb^$Dy));ZY1988i1|P0gqlY_*KsjL8rCT+ug|w zi5OqAhssD?<0Fm^dVgBu2E6j!$kRlPw0xUef=BeGTIw>zGsz1os(isReoXpjwtotK z%&udl)od+>y(Dcs$q$#fiD3t4IT+|hGuET=9-d}+W7BUpviy;TZX6y@A6)+co|Nou zkB=t{adJM@8Q$|Z8`HQL;P&A9ReSqst-jTQs~l_aDK5tQ4mzu@Kn_${|T}EVQ4Dtuw5O zf1YZL(OI%a(8(J#V5##yTyfX`0M}Z^HZyIJL3pdDh~b%|l0X@Qp(^AY;fVgVr+4ES zyqHl^IKIxiT!rAbO#2^UT2RsKN?>pWB9XM2@fSsLDK1}_;ucbozJaamV7rPQbk zT}qQ@=9M2Cex!H(YA+Z^9-XV&t(40%d3bQS>z)BVxa?~-?@^a)K=8DDxuK4p)*KV1nypzf3sTL6c&PU2U zI}=z9GMHqMq%yM-K4u|CN4I=)SKIq9`!q=<%<~sD#&i$os%$`^glktbAQsbV?)%RDkCl{0Sh1VsJaq#u}c!N=uSd|Rru_lKvFIF{Wfb0hf!gv))w zllOaLoB>#KG?uIzXbZp~9;dOb8=HAAd<9(VE`#@3Gs1)oi zOGz;ZKy9m!#;j>jG4m#ccS#Cv!hmy;jN+)@6?oJy%-P32zu``^MiFlFer>0|KQBrM zMW|qrE|xTr*}&XJ4^P9rUXxC1XAL#NMH^*{za)}74!Qg*Djh=O8Cj-3F2T2hf=>kh z0G^b|Vr!XOa~34?yRQ^V#c#2x9M<;9{*KIYNDj&{e-6K$RlA9m{L;m;Mo0&d-}0dX zfVlqd)AjeMBV!DzfEL}?u>SxWIZz}+YQH|#&e8x4yO4R}uPpCwn?7EFO5hwHYGHMX zW{wtYH_X`N5B|Mbg4<-9oHv%=Fk&;4j-J#9T}#&N3`)qXt}u5F{{ZazcC8yn^OJ0m zs?8!2%oqIjtmp~^@>9$y7~9W(ueDlB?Ng%- z(YmZ>cg)3k`ucNGUd0u_*vPHqf{1qg;q|P`iQ>G6 ziCrZ_oU4(M+xbu{^)B1lO=SZz%jP1I8DFRz^goSB7NH#eTdM7mM$ak!QogmFcF^1i z{Hw_j$AC#;llc8bSdQ8^`JQIooRPc`Pp_>mVceThwTwn&R&DBXr1gLPwN$W}5Q|%b|M51xEgMCJAz71aAa9w*6gPTDOg`UUNvZCq z63ymE^Q!@p2RX$yX``Qo8Im$^JAPDY)NF=SQ#va)?cG2hbo$b@%yP%&D)AE@Hud`V zrUcB*&g@}vj)I(v<+R(QF)8DA+~EHJT+rgW574J^c($^0le?S(IHI4uw{YBGU_Vef zqKg%&_ET_z$CS5o7#fr@{!{no{%3~Y1 zWqSq(zB#Rr1b81#@CJ<@pJ5AI+QXGqXWY%#C6BMYY$dw4%H6wqd(@2@{J(ps{Aec1 z$3No_hk9R+FRbL%Vf$1%bd54V$82oaz}!3f`c}QPTN!qK?M6W3paZwkrJR!LH!j@# z!#w*_zV1qe^#kcaKBPAc1cztMz+Ofwgz^6I*zF6Pj2^Xm<~DVcYY@DUJLa?Fo6Ovw zD0RltK^-~AT4fK87V=9nwp4By`^`_ckeCshaAG+h!a1pD-09 zVY4XUf_-z2Isj|ue~ed>Yu^y{X$yIc_LoM<&T-HW@UK?z$HPAqd|JKJ{9WQ5S)sO) zLp_b58`)teAP$>4FHw>`JAD5D;;$7=Cy2FJ<1Zu0eKRgte&u(OkA9i0VrM2tHkof} zyUd#no&!@Muv^$pCs^TLnLMsP#BdedjK5q zpTK0%&2jmdzA9$4(xk*{%^@LhI(lS%YljxiV!Nb|YasxP5~n`>GhT(OnPrD9v0oYA zj>DhUxSQ*@d1MkuOmWK0BL@k%Y)>h#X$`b+d2RO`;{fu${c6zB z?RQAo`#9UZe~WMF{OcA-VRT8n?aQ3~YUPF3*<;xntccld&ENbf50sGjZsA07#?Z+O z%+XJeHcp#}W#bfB zRxGBSeJM#imMFjkD~te6KqUS@Ojg_$GivcKopmL|mZ}ux_jz#+Hm*-Vdv?jJroWQ< zIMrunQonTPXgSEwy=>?f(}+#R=ozD26?Og+a9gfAel&^mDBN3pg7I?)of|gLu72_9 z+w-jmLZp9ZR#uWRwBR4a{uK_fBl*%>Pc(6_Qg#4PU~}p?&q|L$)LTuGZ!MQ@-KtrB zW6x3bq_-(cLwPM^veP`srdz2M3%(PLzu{T75gYWi+}mUl6ON@=`_+jiYik81itPeM z5w_A)l0V3+-W<4Tt=j2sBM`=?C(8=U>T$^S{{RZ2bu8cL&7;~_Ttg3;ae1~hj~LnW za>ua*^fj4rqhJ33YF=615A?PKf~*dDoN6%Xu z>GtzSb#*oB!yGUfKpZh3@QMi;KHk*&TnFj)vOK<3$CyMaGNA3<#sJT#>-7SgEJEGj zTZw+%9C<7AeDOc`S;z9JCDoeqN_B-|jV8hw8TrSzzjA9P81A&GA=@%}D&j)Ph5+Lk z%|2V|%G0T=G}v_uSmBQDXzq}+n5A>IV<(Jt&Q5(hRgD_mZ0#-<;#k#{91*nPK3+5J zj`f{Ci6yqR+itt0bFrML-oW$0?^MT&?qksfm{r>*cd`5O5AK8d`_%3oNc{U~WR;?6 zIQxW*E;!GpewC|js!OKMrWhk>t^nN`k9Ju0?tco0OtrIpDU)>2$qC&jnpLvC*zNsm zK3zoFYcZR7o=IZ?lrQk9@1J@(ZY1nl)%;O$acs8ATje`kA%`gyi@5-#vg-W5kDgZ^<^HrFesf23(_@j2mRl|$g;k_kO( zd2ClPy`%V^#>+zT;TIBWR~h+RtN;V^5zHjo1CGcQs#M z)h4$807yl*dE5YY;Y4glH~{p=9Q3NXzM~AYD@?LOlu`s>6%Ewq>(5F#R^sLoe;UDQ zsmB96*G|B!Z?kNQIphJ-pt#l~xVbE?x6Ap^AF1TkOPzKbT|l%ks>qyn*Tt(s=1y!^IrN zOwEVJLUrBknzwuAMW(m!nt1Jj3Ap7-jyks^9@U0cJDc{Ga{$Z+LHn8DRE+2h@>{@> ztH{4QGvUgx;Bm)Z^E`ukC41kz13 zFrw~UGo7JZClz}C0AGo`KXqwt(kjV1F&lVMSH)LJaKPKiF=ji4G6znab6D3Jt-ahVuzb@<=MTRMKMZ76T(^=)f-qYP^5ID5 z>qjku=Rqn*_QsBDp&4S&(=6wmNc;JKG;EIWY-=5npwAZZBa%SUVe^7I{b;kW z^xT_Myh!JjRy9}N**$ml&(PDZb)W4!6gt9Mn8C?us`0YZ)I7GlQesL$%z;p zLC-k!_NsHph`VqXc1}-v1Jp<*YgcWXnihNp^%y6bmK&|=Bz9$ByKtwV_Vldz@8q|2 zRCf87oD75O#a@otE-fSSDq!q_V>++r7XcSw1xKds_8BrTXPm{?iuNW z(2wiwPbjwYNgCn0?kCoujTqf|i~L+*e>~MF=vISo?<9`ja`}=;8xyo+KY;04mRBx( zEvb2%+B?(;cBu+iIl;$6^{jjE+{nzbD2~xRapZo6M}fb9l83}gEHBJ$L{hv@~ugG81lTvb(s~EZ(riaL;Wgidow&t zwD+p$NNKRN`iGXx4(|Esj)xU+1+`M6GJNNfaf+yxGg`?UfwQ?whaBwor(E8!4*S0F z+;9g^r>##YEeUOeeq$2bSnz+(^{FPi*>xKfStC=H!*P$TRk2v^rtKqVC$}8&{&Vg^jSGxgA-S-Tes7gqZ_BW4KSF(f`qgF|vuupa zjLFoxkC{F3{(I4PJkh$w$L|8eBip?<&R-<%`Az^~>;C}OsN8Dz2&P;4yy%spJ-E(J zG5J(C0L?jFp>h>Ujz~RfVLWj&0L5fcxmX->Xpi^6NX(;iZEkwxP#cX%_Di|rGRBw<>$o)|R`YRcV)N9otzBaDDqz#gp5v=7;5S#d5qi zUX@oxMRge3bZa9Oypc?U<=o-3-yZb%np=2E$9WvvM^|2ejyir>{&jCnWFNbbM<8Ao zBj!)1r7i7^yFx@Uk1>JthW|j-ov#tZ9p65ZZW{)@%FA>Q=_3zQiW%nZo%VrLHx5#irGo!d*josS(t+- z_>KoYwD`(A3^2bpC!X{q9Ha`nW7*4YIA2jo9}Gm8RqgFlDtWKfc7yYC`BAW!``bn` zPBDs*yCaiokaBmo10x{*l_Ij^3y|N|p=5Q7?|j+F0-Y3Xa}MCeS$$1CZc5yaMOa|- z2I&}{ta)Gani=*o?)e)X7o635#xq3N``O_7{{Wm(6Yq&x!!F}Gh!bz4)F9ZRODj5#d`>VGY1P+3l)EUTpbNHJ-!Y_xDYL<5Y z0BV>^95F1N6qD`jE9Q$&3;2ijulR+1sx)zF@T%?eNi7Ysg~G%?h?9)t9mzH6AGW5Y zdS~$coO5}4I}E00VzMJ6h4qMsjHu2d)Q6$elyd(^>bCaGr z)$C@;?ey`W_$*n5l4GaYn8|g?eTj^pPL=TG(#E&f6A`(Y&f(h`CcfD5-PD?Ifwg(1 z+YG5`F%A#PxCaOIuZt&DWM&L}*5y+i6VDZ-Ni#v&6FM(UvVw3bwdBku&qj0u9al9k zoFi^mcU*#cXZlr3g3-zvHCFZ?O0rGQ0clg-_>RNN4Vfjv@D{^&*GnmS3uC=lWdYq#bSvU3(3z~;nMMMG_-Js2_l zYg^-_>#Ay2*B1Ml)@hlL{{VL%cZ%m@xoNI|eav{|^}yn{g6d4W8ybeH_prjdVYdjI zKXeZybI-jp+VX1);WRf39E*^wr`L`uvNTdBl{cKMGEs-u)B4ofRlGAo@<_)ZoGLC! z`tw#s$V(8+%Nl|eUvh%qbe_MRZp|gc4dt(vf7&E4KGj0n804@LO6;=vn@(5dD~{*3 z4OxOlX!kbeOkkEhdegHfQPJ;M%Z@oCZ@B*e8qu?em^Vo#?46_)J9+f=6+}t0CK>z3 z89lu!OC3T>RbjbW9&)GnkFoZnLYdMFcGn@f)?Z#T|< zZ!dG_7+yi-W7eGUw0nHGTj%+k12`klR%}Yv(7NrBS35^N4{mEq!?50Jl78=OZNYqv z+4`UUwJo#)^~Sw%tj>#d6n(td9Vh7Rh zOpCjGAPk-hw>{S~(VF^8qbuL7$?Hn+;lxk)5vai^j}*Qu)n{#~?-ZzDbC!W9}bfJagf(y8ik zt-P_RxROFbw47sa9sTo7v%Onsk@s#=Pu)K-9{4>oQQqoXCZBhdtm;7uxC}k1rV2zY zxJ$o#EIGj_4;`|7YUTaJ3kojg!vM(Oe9MevAL&$Hc3nCaR#;m+jAL>4&t7WwnB!fHv~v=^KN<+2 zrP*2EXt&q5SMkF%KfATJT=|z0o_QUWM5CH*w&)8x0g=bOa`yLaro>n7t79Z^!|6=D znQr8gM2Gj0sBO!@I*`C&~(Lc4DD02RvZ@wUu)Aw=d>gD#<47#>}VX zBC9NnLhdaXV}LP@ryVILyJSo=ZjF=vU=y~SuGFQq;-G4)HZX+{{UW&Q1dz~H(R;Hf=I`f zzG9R9dY+Yk#hTnYhLxr*ymLn-ykF@oPx{s;uh4Ka?^t?fvnbPJgu@8(&kwf@;FHdC z_;jaDcqa(K7cr7JImpld09vP)Q9kH(_Mo$}KbIVAz-~UgpVp7H`4CAIZ5o-F2Ki1; zuY2;Pm*ZmjjmPBOO9hx{c5em!Wq{) znaI!k*y&mp<}s%2x{@`D7V~_xIFjXu@PpHyzSWx3o2$3Z$PZZYgX`1SdY|V(S~5#( z!F4X#K2lByBft6nwQxGyz7|iHq4~0-wPUj?OO=x>+_MGcKVE9`GOm~;Uo*{)L%TR2 zuOuEQ2@{=8;yKw@4b*Ka8I*sX^!p2`NE;zmXrG1)^8?Qx{;HwObkeUBY>c+1{Dq4`cPEGf5N&b1ad{zGmF#a2-B} z>r@rmX;{ts?<|4AKQQ{$%WJqJ`9-E<;O%!jd-nZl^J*Na>?Btnb)THp?7msRJHApo zbN+d#XPP_qU8+^NA&z0YaXoSRkH(oR zGAkffP;$cq<-ql(w+}M>Ox{cGW_8CcyPWaY^E3jZaQ?TVRhKG$+vy8sz;fV@>AH!a$x=%a1e?s(iPE2UYj%Ix`+ zl2~y|Z*tbdY>So84b+O2*LLYQF3{N87;Yn{v#;GFd{vjbI^}Um%YPb_Y(OeZ(;Kdx#~SB+HCC&&{cLD zzEX4i>6f#%p$659XpD1?{{V$oiP~V%s{a71IZ`_FQ*^-InR9Gem+x=`b~(=m9THyJLo59XVq=8x_ja`~YJc3knQdR6AhtGY=%zUzYb@r>8N0l7= zm06rO-6OBC{{R}#EB2OH{{Vfzq1br<(_R~ccB<~N?H@J|QT-?fsyYj%jzJ?NQY*J2 zGBAF=pN&&!cSzfoX1H7q27Z{RQT&NxnOTc%+l>AE_r+c}a!GR;f8DzE0kRX<>xw{; z5Rt9{SvxO05&6}Yo;OzWCi#_iu6hr{=}wGCbq`Wz#?nW6BhsU5#b?|kh=6c2oc{p& z=;cg0mE)bQ?n<*Cmm3B;4*vk>uUfSB-c8Fgt1~d;p5Ogyt*Ikv_nQ@ecIrqc{P9z{ zlIG4i6t9`Ha4K`nE>ecbhiS~1U@~*l{{Yue8Jaa|3vLPvV7K1K;l&R;f*~Y}^8M0R z=HnfDQzi3nBUt2hWg}~LW%M5Ob+969dzGFD+x}RRaxzXmam81gEBb;}k=!!(w7lfpLF6PD}P7OY{B%4;&AJXSW5u}0WW z3|p>oj!%5{#dcb5kEZ-L@XwQHZnjo7yQJ8^GZIhCNj$R?$0yJVaok*|fW`2)#y=i4 z_;0*JB(`?zfMk{}jFIHzB6@-d=hPbd0>e#_iz<_p-r%JVFc{I|MlHOGUAt7=G(bN&1xvf1!?s8uqC7##ePPp;2M(qJt z7~F73&*@(sTu+5N6;9!tV+;6K)?c+X(^z~dy7`rsNfiuicC+))5z`pY(!NKQ;0M86 zHaI)71yn_;Lg+e^_nDjSlhpqJ^{EUlT|+BI+-E()f!Fhxp%VT zmd=0uRiQiTdr$0H4xe%2?M_W<-b>9k8*P#*w!%wip4~Cm{Eu7s4WQ`0Jl1@B;aeG} zlS{hUK9(gL7%&+6ayt5fn(=?x+<#~IGhCHbfs#O^?&PRmhaBVU>s<%H&x$g9Iryt* zsclWR^9ROwm3IQleyUDA#%g+(xq;))4ol%pV)IM5S)to8ibZ3TTrv9e{{Ra13-1;D zF|_@MB=BCX;-$0KE@qEV4;G!~&!Pb+DC?2HWg{dX<0Au{Z~oN&4qqEww~4gfH|*AW zq=rO|eq|V3;GA?koS#wYUnu-T@U_kGTUHGd#^s|p86(qi=s!x$tBCD2jb_woG3j=4 zO{^`fpry&1%q{}`0pw7!QNsKdYI3%`M@OuGV{;MA7R{Gl3*4IUzXGmR6=?NKO z868R6{72KR5!{ru(8OfcbvuTd@@XWuXcV1?JKOKuhPB#iQ94jNiq_WJdvw^dM(i1z z7>Qk@_|le0jG{KRM{HtmVyE^huf4d{KBBFbVvthQ}U4YY>aqIixs`2T%yfmu9zrxKWKK1ou3gv?Y7PvZ*$gK1K z*(r;se>G78K}#RN&hqwMoK!Bfu{l#%rt}epdv8XlbCIe7cEJoDoH4;A7nJa?_Yovl zL|;NqD)R57UG(q4s(}bV5Y^AiX*aE(R}>}{YxB&*bbo6v5+cb+aZ}6APUgXrhlkKK zGmAI7$;1{hFTZE85Af>nuBWFAUKXK_99Atmy8i(O3F(NvtF#kfiXZ+o?Dz#u=-Qn@ zn!Y;)eFvE&I^jqm%0y<q)6L8}5SBScy)1>_<~{cFdjb7bCi(e{dP28q0rf-#)qo2%rf-WNK~` zEKjZD)+A2ooYc^^96ZXL26{jHOeBDaK!j`-owuEzAct6yHpDZj` zXn2YBZN&3G+5dJCx-%BCiE+8}^t z*$h$wvCP4l{8!0inE~9svTN{OxK4!=jZ&jA(i$<)tk=jyMDAvNT`C(6T;Eh33txfs zvb2N^$oh3&yTmNk^_G^y%LWIxfNSBZ7~Vd`0Z%gd#-f7$LD5B#U8QM3fz`OXor8z9 zm1n^shI`L!pc!=uf&fo|ANFnuZb?RdiGxz{eiL5Sz>geULBSu3;^L6cJkpus|Nh2( zy*V@AemHnSm6#;H{qgZ{)8lnFF1CNZS%1NV!Fs#=)igzYGP~FFCYj!Ft^Tq2^#uF?Q&t-maFMD`9pk<(Xd!6mT8#({lD_Osld;=m5}&*$vUS+X-;eU zXTDhv(Z}-j#fR8AofrEY$xjRiPWKusLQa`tO_f^{oS8m<88M?&+X(wqoLWHU`R<%QI**H?>E%r#TzLTa;EZdH*Zv-Bd;`Kk>N`2cMm585b#?q)hyJ*BIF% z^VQUQHTnb?tva5fA2)%raU0krvj5ZsU%}mmCPN%+BNrX)WmWtJvJ80$9xC1eia+|;hF=_9dKu&93)u_Q$~^<%bAiQps+M-mj7ps7FP)5FDYT233k&~XM9_7GksR^)(2!6rE)U)9 zO(jpSnyA{{jmD&8419HIB>KQ@dr1A?eBJ65vc^OMqDPlC9>Uea^7M#E#4 zZHf2W+m(%^Xb$>Oqp)x3>)@`hgnd0LVhiU1AW#zzbHmhAdm>T=%Kt}V8=r)_l%H9d zdY8<@6nNd?ADC7wnBS_}|EKk!Uj%-9(&)>C;uD9a(61Q84Ac|Q>>>YPJS&OOY3H2+ z9ezzT#J^_>{&`AhB*9ej8KgXb!#D6x*#Pzrmn*BzW(ihx;)DxhZo{>#B;Sc=r5$f1`$hIKv`X=I{eAYY*TN1k)wOJ?9Ff&XLeu(c^_2x4Y$q^wb-kS@vkq#<8al-r4u7Hmdq+w zjfd|}&XCeBTJd~?;vq^t23_u6Y2M-?K9{4!8KeECh*Cv9rvTF)Zk{CaYWXJ6`|Tj* zW3Hd&6<6XBQCx`^2GNT#36)s|erkk`eZcBYbQ+V7vG`z9o;fo-xR$uiDs8aO^GMS+ z-gr>(ee}n0gF`20wVc$>Ldv_HV2y??Q9r5?w6&y_4{JSpcg<@iHz?0l9!29PuhdhSp0$lX(@cTzLgTMI9Kn z_*;Fo9R%BDz%LcmHQq_`rSxk0GDbyg)}sJ#6zh~SPI|bpo!c%dQ;&SU=NV@}=#VRz>jVG&)#Cg4=#iQp^ajjPw| z&t$TZ&qaKOl1Ph_VD(%w>sIk`_gD$(<*hl}ffB-7gW3$YS9;j!6!k$uAxuvJvU2EUl*LE7EZl7Zw6wXyWP)0zN zu@*9+CpRv(U9>ZJ2s3X5L7;0TVrM^#SB#Hv&~r~}J(Io1h3Tq7hki_C)G&a)-QT)L z#`A%EcnpPE@*5v}RMiou1=e4W8ics*Aebcj7s^E&w)O(?P>=`BX(*}>p0|vmRnZ;a zJ;@+WHDGp>H%oa1@_KdkXf0$+DkGC2_^(LvUpe_C+etNIRVyDPMCQaot#IQ~RJbLy zRoX@I00V_xg(SHIR7f7CJ6o1@6w2M_G0t}}ab~rXL1eT?hyrC?jN(R+i*}}Eq$xICwZno$>(C9ijGcBW zhP68nan^g?C!P_^tAg;56(7e=w%r*SusFSgU7lsw(#kUag*xIK18u6@(_55eJ2l+n zgP-@{9|bY2m<qB#)zn&E;1Qx%X6WgPm$QN6#}4P+I4KWfYIzh&eOZ!pArU z7k^i?+&MYf(sN!SZ=4M>WNj*^b!LMh3(_*jvBY$_EJTNSR^cCF)sV1PDG`1Bi86lM z=$@LZD~IFXo_lvg^5`w+PqwxnKcinzz6i=v)D0-AGJDSj`PO0*O6+Wog$lY9=F<4R z-Tld9XcNhISV3*oT{LJ1ywKkBLO?&TV_0XddNMBcDUt-ig^l3=K@e5{{W07{OjdTK zY5K5m<(U`kX%|_WmYq#BOVO+J?4RC+!>_j*j?t1FiCM>Y@Y(gZzrZ0ZXg9Utu}8ZZ zjwL%&i0*a+Um+sXbZDfpQ_gkse!cVC0ZkGzabh0yCf=fOV z)F#gkZ25Pj=UlHvrqQs};W+uYcO1}c2kP(@+CrtBsfk*hn}<>gy3OlZ=&S39^T=E5 zJOR8trQhAxuVPZD`5If^>a)U!c(gq-q54OKXp7{1mdCe+<_vZn3X#4hnG$7D_E?mS z7om+-jr(Culi>Q{)Sxl(-8sU8;%kCkwwp^CJO{6!>4QcFXCBb?XdVE~7I00y{f< zaA}DDbLG5$-6VQqln8UXNUsdJVEL*r{!)&dh}uGUh1Y8O(L0phwWr@)qza@;a_IM<-gc|5YOK#v zSPF0{P?S8`>gSF8Ooy!4y>48x1sckj=z<7xLU2f-)l15p76keW0#4;V3G6O>Abd=bGEO=7)EQAc+g0?a;{8FE z0fjkspw1^EIDXE08Itj#Wv3D6%3$vqM}%(jA%OqAL`@ViLb*D%9%FUak{&rC9j$2x zcnNModnyMWoaFtEO9(*znVSUgSV7-t1|B0R1nlkAl9fV59QXc5(rnhmQVP%Y@pE=& z9CUmxxYBNm57^IORV>Y3FnW%YNJbJMBwTVbw{>QX7sw`;i9NN~z%=otR6XGb%U0dL z68vv%htJI4a$c88hj_0y)ms$Dk!2dK|6oo$p^0^>?OCtWQ|$$zw25}lJKo$)32Slk ziW#gz*+}g(cMx#7?mdZS<{Sfl%OreE1!WQeCJNan%HL$zGT{N-{e(4%SsHH!&gS9A z*l(2jkI{y#OZBhQ<+9UiaiaZGq`ex617~>F>1-J^KXyJ>d2Bo}p)eclL-IUeLKLbj zgjl^>mTPwgVXBYK-^)=RdFwTY2NW36ZMke0)3$3$3{M$w|DC)KB=(qdFFIKoclGPA zjN+^6kaztgx0z0x?`W!fIR_nq9AC&>e7+yjo&|MAnFF*>a$h6ueQZl@fQ^D5RGFg4 z8icSFP{XMJ@#vwB&A(`OGtP`)C~-8AXGX?j>8sIFj7PyLbw}nmSZWcrP7O}G6Uz3u zC99z}<eIz?#)>nFKipmp_*$vG$lI2=mR1+mN-&-!3|tjeN}UpuTw4=^GVaL? zFzd%dop!!?W^nd=E7wF;+wy36a{xiJiPhk58G{=vXi+(U!hYdsgYZ8k7Pb z#J1|%pY!)&LzmD1tM1Gmt+0`J4b+G|c8rQde%f+h19$7SYDbSTKibl6iK~lk`qBDx zDbUcUDG?G$jtw!7nB3$ho2#eMaKGcr!*0i|&?~eR{U0q;=1+GbfH!X`!rL72wn61x zSlR>PGAxXEr(ZnggpQ#7hMTojiBAQ(I9M^?@4M3a^Z$v&Hu2BhR~!q;PLgAMFGTNX z{^UNNv&{(;1;5bl{f4R@ch<%2lYCuVGB7odp6yBG59YJWXiS251Nq$=l=)GF{)bRb z-JdrHSyT9&vpMeujpy#T8ffIp7F|w5--~nt;H~V&M7)~uLvpOa^WO)Wb?u}9Xx`TQ zYn9d4n~zOoUsyTGe6zD$J9+&pi%{^rwNAJ5-zat_BeBd(b+=Jm-cowt9@Oev*{!F?GGxXLl z>VfnT+DbiWM4IkdD2KKUQ)oFUEQwd;Lm$yM&hqMiBu4A+bARq_QWsUKOZ^jC*t1*bQ!|0(lAvu-^>P%0^l5EF5yCnIQX$u6$DpslkM3v z5~Zn(#4wOho)LE@0o9E)aIv3tnmfrrdd{a^_=N^h6fdkRllZV4m!Z5#rh?`rW$D3|rA51@L2Z{*M5Rrn_Bw(& zl!6**IOMQS56@Nw#>Nc7Z7Va^9Q3*arhb&Dy z_2ubF9N7+s*KkWIEEj6=-8l@xc}nXebJJ8A(woQ)%eh84u`f^28wTZt8pYZ(I5d~D9QC`23dO%@S2siKm-k>yQN8X0 z3nv~R0w%$KA*TNoOzoh5w1|vXhzNEmr^VMb(gAx&2>Deoaaz|Q;@3r%%RD~n`%xd) z9v{^p^Fetyj$~KUBv~?Q8eGyNB*{h$xcx;*qee=)fXA4Q(1TwdOWO4D)q#jrNeuCp zj(lRK*F#@Hn=*EDh#wa8w^ADRYSrVyQ3>w)dmybRq){Wpo5{%DwAmJzUSJHBAlJ{X^JHNf(r$@ghy4A01AnD;JXF ziR<%YdPn~%2?fyf?mXVTm^yhgfbrt|{_@`4qBv?U**`Hdzsd-;LYCWY!Hp#q=oDYy zXOUkdw=N7Fjez&7Oh05vM@#uMb3&r18Nk?g`)Jyt{P~-9B8tbJDQ@FV8)Bk1YBLG{x0b9y_unghY~pmEWWh#M1o~YXZq=uo@SpZ0J;Wc8c^s|R zz<(_{%ot+yNVY@jhQklkjQ~;%lFTbtY3b&H@cKppd3>_@O2oBQta+wg(igbU5fr1K zjv#g=DVoK3(NUJmf241d90Jrw%IFNd2hGV@e@&U}B~MWcprrIT`5!zi9WGIOHI)tz z>PQdRLF{Op*(bsulEH7BtKNT6YgFO-2_g5Um*WODeO$6Ls@^knaHFL9?~wS|XUw;U zKQal5x`-mB+u3$irl0{OFRju)@fyIVMXkSiy_$0N*-(45^^3ygwA_dH(ZcULS{!0x zhZt1JE_Gpc3O@OU06%7Y5z%as&6OgY$e~<8J$YC#DS%Hh^UmglVywDja(p-SOpF^A zvFVay3RXyUVwuV?Hi?OonF=|Zs6A!<^znES|HHwPYbZk97I$~&=!9N=Im-F4%z}!8 zQLADI?TnFQjE-L}Bru?@OnD&Ru3TRwA}oV9zlVUvsQdxlL>9%f;X_ZRy^ZUuiR*HL zdNocazR&CLp3fy!md>jmKEwv^!uJ9&tm&c}H%Y8*3EkQ+M%|+xOSn~C04{!kkqzH0 zn8ggJj?}(8Gc?N}ULvRXUzxQ{NGz^KPfN;vticVmn|~7+>v_qfdxdcMxjmjL59BWu zrV6~39p9welRi9gn*rL6GF#W~V#psrPb!7}!Q;955VR_PVn2+~1qRqn@;g{kkRlXz z(DbLJw?d7x?Jt9D7zN5FO*h4PEBy!wSq?^V==0h+Z#n-R%P`lw*kZF#A)5xpcu$&A zeAtElH{>+kjFI5{k>oxsOm$YkefiC3L)83-i0rYVHgliAY(nD;WG| z^iz;TnQ{NiD-eeo%fibs=(WJ$cHl8a{doSCGl=6K4Qe#_k1NuqBJrs#aJSZrl)!oT z0Qw2iq$8H7J6->7Lo^mJ5;PWaDl{PW0?zi;VA?kL6L?8u&QS09)9(L~)G5oK24I3d zPcJ{Y#mYbXx1Rkf>+5O>r;i@UHJl2+N2c>>wo>k~KO(lnHI&A`@N|8fr8y8sqRt*Q zr%Xcb)z7C|me?Y#17EJGNOWE;`~2;79jZxx&;h$1Wz~FV6B?1YZ}ryo(mpGbCeEYb z>Z8=cfTXpg?93S=D4@hYNl>spR`2lA$Bone)`0DV4G;euX!Jwi=H#?y=3sP#r6~pe zQgb816tbxq`zf!Y!{yLigf}emesm&2k#|$=#qeRaUrLe)<({Vs6nEn!&Q1@CwF9>@ zCr-i+E^iGsf19CWM~}S17w=2XrMkR_&D8Gc6-38Da^gCEpAg-)VeM=?0IGV5&%3W( z{l)n7+bL3W)JDi^d8_(YLaent6~)4bnIau1C78XpL&-awJ(_3@P5jXuY2cmQ^jS#h z7Dc%w&eG+Xd_ib{jF#MV4_(?HOnjECIFri1I&c^fIzjv)# zbC}`C9V2!J*qIwMwduWRo_z64;nB0yI}9ruTci3N{~{y%I!0+6Uf(i9bgU*P>fbmX z{UR?lL3t%J8@zFI&^3&1@T%8&7*Z$ZIsfC&zt|rPsUSn}f0V4L^aEsVQlc_;@peQS z>T*E9g|^6Sy_0DVOvDlXAdplaJI^1HnM0avc)CBzL|FiK_Ml0RH=(WW;>4rGkgh)N zS+=7dO!mHb=YAQ`j&4IHNl@~ISt;GlmR?Qw#NfK>%ZI7=;8fJ_PI5Bug$GMX5Mc={ zO)C#n>?JQhPZnN1H@|o1HsriICx8byHu7?4^4JY~O?_U;Y7ej8ljWZ%3oYnwfvfx|f&~X|TwVbQ z$6h5KJaGCoyS1mfb$t9WN%7jD{~er0SBO+L6uz8W$4I@$;l7<+$3B~>0! z*Rm+D6A$#bbY*U3zXa{>Bt!UIo>a0>B`gwhJxkz|f_^i1;M!Cs~rV(|+N zoTy^l-`8)v{82$%O41CUmO%jy_7-!yo%?G4&U&On5kU^W8*VkF_8Z;Kk5@N?2a4$qDit2U+Rn5 zY8OYtSEXAHoA0-;mdobl2|N$aZ-E zOZCZbNCcGuR>`VLfPWOE-q(t-s$xid%8bOHT6Pc7hR&1m`k#~t9H;xF|2&GjgC-@- zz%z%4Nldw5VbMb-c}rG=PmPol-wJ*2Xn^*fA(tw|>fYAST4ui)S`0Of)qJap^#gHr zuub1nCpg%>a?c>;N;#YXwYT1*cy5&|jK=29)B`M@ANQ-lUNI z4PLJZ!+tnQ2Bo^o2WGHeY$;YqB5ho6Pw)q_EJG#l1V+1@|1#s_5ttw9`C=-D9^KDs z4Fq^gck*O1lNQ#)(Z(^yDeXs zvo7#*JV=?Ml%r}O1D9-=DdU?&8$gm5c};wsv;^A?pDj@o9}|@A7z>S$p9wQ-8tf@i zP7$WFSTeyG#1>#?^4h0Jn*UQR&tHW0PyyDuMs1O37SHbjAD0m(ILw%@p*1UK!f>Z;PXqv9TqFPv1j-*mqzQki?6ye zAxU{$5yxhq4Km$RbK_QD$o`K6F)O+$ShvUmksl=tydA9?AlZYCvPOuv(jM#s|B0u1 zxpHL|Z;d|xmV+~Rzmdn4BX>C~v)bgn=wTEEb~z=0_xIEn&Dn-?I5S7H$itOYaw_tA zwcKtWMR}DtONck*uY8s*Gv16XzxIL*~;>xiY*s&VqFgDvJbrr*&Eg!6$FNLU7l$aDt8E%7T%GgKPd)fHePLC`5tdAAC}lQ0%0Fph`j&C;yWEw zQ(G_L)I#5h=9G#Mp1)7agWyxwk{TwpkyKb)`aDtnqOTWj49x<3ZJAP)pL zMs~C+8(e;>`fl6q>VHq5#X*q)FjRzM*KY~=*Cw?Y%oA_I&l~w8XlH=5(j{Sr0Dc7? zS~B}bCI4xmR9NvlXWVs8H9l)Yeroc$2p^aqIpw&nkGQRu7*c79H@Y>sE{85xs;A9u zFg0#?Zqz@s@#?(zC~;l8(|LJd`FYy6-oayWkA4?cEZ4&*%rN!Sev&eQSsQT*tS2Ji!`XEiKw_M7&)gLecIY}* zYtCcu;NB*0qo?B;`__Zk-kmh4i9EQ(ylgA?ZME=w+H^wKg6}_(tgpGnE2t~E#`rWj zYq;v_+74MBl+TZD zMTQW2;7fUTUBsr#G;UZRYNc0!%$a24nivBgVEoUEmrro9H{tH8`k~4>Faj4aa|HyX z8oBqb9dzz5#cQS}#Sj<2Nt;sG{Vh#TQ$2=I|A2u{M>ipL^LwU}Q*JN6^gkM-7Nbub zL!6ZlbBJ?rgj0!x?I;E$r|1e1InAEn|H?MVmTK`$KV{gnlbXbAC9f}@k1SLV;9&UK zHZAw$%}Eu`1Z9H^W{8U!m1Uu@*#)B64V8-4If~AD$Y9JT5|kGgqDSR5QO7a9-rmrd zCi89Hh9j_rq|YU$ooXK=cXg8I=e1c+M}Q2G#4@rR48>R7+eo|+CIWv>+x#>0Fu^^m{5PFxEQN!{@g;aIOi4*bHpxHSDd((2|$Mu$jk!d*Gi7SoX0k^2SqGu z+g9Q8;OFZL99-nl@*Aj=QO#TJ^|yHX`KFMQcN{jS4KJ$tLwV!I%6i0S%>OxGM0F2e zZAn*q{Z5>m$>Rk%+^ZnS{f{KNP?%3}iv@Hz&F^VaLEHfxdE zw0q_R``PypBoFT0trs|?{du-g3D5*O_F8>Ay(PV3hTakDyZ-f%h@X#b`XcK~v>6#3 zya*4iyVkNHY6s&p<;6dc=h(1UZ>$qXR~Iw!TxlC)*>(1RQ?hA&NQTmF*hL2~zLU;2 zGV}#Z-|TI|O$>D@SD?$$+w%OlfOe^A^O0BSyZ6<&I9Qjpllsh6o5yna{{+{l9FB4; zY@@9(S$x05h245Bg2k4f2Pgkw`Yw7dT*+-+eGw7&aC?{tP5hd>t#7$i+L!-Sgmyu= zH1BBBmGN+9W>LV#%;|RY38i?^h)!kG>sGYM!B;r4)k17dx>hjJLnul{Qt?WJO}6Z{ zyu)q+R3}AG!f~?W?(uhccq$Gf8ZKDQsbpLXaG zE-yG)CxZ>P#Y0uZnw$IX@KwwkgQJLdpm&7`g!Y< z9wQ1Xhf42WnT?gzx%Y>5H=XaVJ9FL;|5Lb1NLzdR3GHnj6Gk+}h`f@KaM-0z)#^~o zcA%Yg24)uUBE%=gcPR`X=I3+`t=Fw8I;5HSRjqJukk&ga5A|rry)XA|_^=TdaLw!7 zs_qUp0Yz-uS(mCPq!5Qawf%WPk!gQ4fJ-E*-GDehseMzWx9gjp?OdoS_VL}K_PEjD zU=HP6-;yA|1!?N;g5Ry83-<9BW+S!?DAJ7C570uk)+?=Egy>Ie3G0iH9B$d*ccNN; zjQ!22WuKp3+3ayJZza4pD+M8cMXSueUIyU-;wfg3-cY6m~a0i#$&Nex%4yZZBkoa z7e(cz`m=KXg+`m>K8wU2*H>d$|8=K5Cfojv$4nr&Qx)?>Ni;am!>U;!x9pitwJ*f@ z7!A6G8lAAvX~+$-m)5X`4qQ$>HLWmni{bi&{+C^#ufA{xC=3cs-*6aP$)hg=di^vW z7#eL^2Vx_;00la-Lj82IYAr3y&}v&&#Pljp+=os_E4o(hZ!kF_oROc&H5GJgrcB-gx%nUJDl*tGJq z)uenk2$@IFB!`E%gFax01|m%ai0uGNwH&1Z^5|zT@xzVwT{~kg&eoGFX(B#U1&)*v zgaqLl#8!6bzd}ZltW?=Zk2hC1VgXE+Fz0QWE+2!)iJk+)ToCbB%C~vKT+;d7|yr!ckf)qY--> z^kdGH>y|(t``C761#Yi7Z)QEW1bSF3gVS7m(lp0Vq?nuq_A9pBc;A0YTf)I$M>Rz z$X*0C*>-XS1RZ_JH?j$i(H*{@nbtiVyWJthu&uz_YbX^Y;ZZD|4i(WvLqCr1nR|~Z z=@d855mGs%=0@4^k#fo|JRqYOWoK1d(IBWhlB*oH5 zGt=Po3OGirdEgI91pgM)e}(e( z-dKL3w#v~hc;s)J&Ii5wY4i+3tuAPH64?oC9%w@!zG`%spA^lwOQ=qyM%!o`f~f2a zz<60-(Hf=j7Gq(eb|jE=|NZ-JbHN$B40NX0lxDAdX`KPS%#-J4O-VsV*0dyeq zVo@e@naEn~n5k75o}&asBPgrGg_;^kJe^=l5HsWHc={-yJJnv!q@aWurdi=f@gltC z>-i*dn9mV%jU(yVPt!<$#Rf*KkLk!sUyXZR)HqcnSo%4_N=S=}%Xpp~lF~1JttxFu zj;?VB_XYPu6mEQM{{S0!#|I`nCFO25S<7vz91|fGbC+K_gt&0GVxqppU_!nWaN$dq zd|?8ENg^fINRBpAVblTPeu~x_TNam7=58Dq{#k%qZo5!D#O_^&N(TwNDpz#3TarQ_ zFzee}QQXtz9bL62-$;g!tRYgP@|M3^UTCBR3*X9o+j|w|3bB-kJ*Ydu z(^|TYqDJ{+UT?|!qD#1Budb$Q9+w>M^M4NOEIs;Fy9dOzF=c7JOg5P%?=9nz^_s;J z-2iNnHo=XunIjCfChKy$jDu&;I%_}Hr3}L`8MDVt*!nY2C0^-gT2nQn@JQ?<_n!+Y z9;Qw1yTW@5i=~uAbmsW3Mdy;a}Io`7)+-Q>w zt5G3dT8H8~^(L89-X}EY4a1)8zPqI=OXjeniOSYbt?5aht>Hh)9~g{%s_N)j{Az_X z4|rP@33Lw8rH6&3B_EDSq*}*n$gix$#}Tb0sOq;UV<@50{scdf_2-x~(HRH_+GIBm zhN0v_G4+PcNywC8-WuiMo`@*SVe!awHFi&pHzZU|Ii2q7SVG0$FQm**aTC8k!;kJ2 z?ZX4_hU^!Y#Lv%t;0P+Ep!7O-oL$OouQvUybJZMeOI5E z1PLG`x@kI+R0r{GSB(As_Wyz0MMgi0iG71@tV_LWaY$HLa9+p0lw>9ZTHj_Tnb+6C zq@!Ln-3oOTxF!{hobTVCDjylat=V}_SA)rMoG=qq9^~OgH9X(IZ$^Wf?>}(vcf+l7 zJ-z^`p-6|F#;lAZb-cxQ3wfWOH))zRj z5$KJyD5aMnpIWYpuIiHUN&&ba;tSY&aS{=VRARq~D|czc4#;`!0)3R>CfAeS&I-M7 z@dkVPHvc1WRq$rb`YKg471aEcU8C|LrNf5jaES?yC3h=2FTQGAe6&13t?i8xkR-S0+DX)ChZCoWGNrfcH652Z8mpy=Mq?I&5WKNGC zX4j7shO0?F_(5kede(4E#&J>rw{sXeNQANeiv3OL(8F5>#sy$TF$EtuYm|q2TIE5@Zd6=++MSG@OFUtp#nMjp9G9pJbH>8pQKk~7HM_wmW#H6#eF_S?jV-m@Z%ub z0f1NoH6CFpsS6bN!ua^s+&~4Yx>GNHLVwj=F6~aXZfleWlCO^e60z)hsS$;A+~n%B2)UKzUxB z#P1?SJaj}>tJvH>+o};YNtx~3oLb<=T&Jq-2mO8Me~P3ga}sX{B=FHW$F4R>wWL`oeST6#vNm#U4H$ zQxS0O`ipz8eOisZ@JsN;g7!60XPbXN3d@`<5dv; z|KoyD$#8Q~K?FEezV^sKjU1mtPziA!{?&R{Crt^s2!mNup&LRA^i%`?IuLV$eS-;3 z)2ZJs5F^wRmHlNUCSZe`H7*j;*bepAHSo`&Y04I@!8)kf0+VsB+G>+mKL$m=fDNwl zvi_TzODK-g`0QxU;g%}nyH-IJ7~(y*&&B;UA10ozy@DfnHycFNN(2f*E<9PB+QhuG~sq?+DHe|D6qO z1NM*LS%{~1{u4`X@Gz6Is?>#!cJ_@+ChHgTyJ9FM6BcE86^ex5M}>t2+`fIos`>cO zrzf;#TCW_8g{~UpR3tGB#Ot}?Rm{`J^F*VCQ8nLL^Rb+WQNx!Hl-r=VGS%Vu!xC(5 zR?ZP-OD{M|$_j$J$@Qf2q)oZrKq~jyzArlx{0n2vab%tZi$>M^I?MmfDc-33A4zGP zH@}W|wIwfxiXio{6Ltx`031c90mJnhKVq9Rk%)~+`4h(SYFwRmJ0vtz!TU4iI+7(# zb&9F zEuHZ-Gcv8*Jo`BNA1iofMBp}Z)k1yS$sLR*j>cer{)ipUQTl8fWcYRN?5dxQN7jpY z@64TS-Hsia&5f))(S01*Cf6Zd2}Ldj=jJ55j?EiU^1B`hqze9a?dI1$s>>V$+uIgwh}Zri?43=IA1ZOkY&ki z05Xkro|xgxRhX6+yC;HjfkL9-@DQ8EVCYUC1memXC_Z<4z!k6q3nczja1x=ddju8Y zJ^^8o&Vynv4Z;>E&KKs>WaP*%Rm~q{W`_J;A{cz8OpGooJx7h8)a;_RXXFho$XxbV z9(h|in*Y~Aqw4dH{MwavWi!Rpfwh~bBKbMT9^yn%;W z)9tlP4DG*bUoPd7^b*PAATBYAw#W(~)+k|5_G?c+h_Z&R*>PVkJJvP(Dn6^0V-A}^+iI30{#zc;3?lW_xK(&3io{vY(GvZub0|7 zp=R%fr|*={STEz;wRvdZ3^N({-h>Dv))m!T!S4H_wXy;p#a#@;qRvO$TTzw|Z(Lt9 zL>BG8^mwh)L}=Q%xqt5vYv81K_TsIGSrc>8+)h10pG*hxY_pA}%3vzD?a>fGuzVm=$6Hmmw(-rCuG{~s~is4jN(p28R0 za;qrtR;^Y9i)*&`sbzEJf#YMImR{N*=X_J`ZRiK-?o20;i6`OsRK;Rn3l z@^pft_))Y+3Ip#jW2SS&x9I$Qz06F9^X#75f5{?)hIrB5<0)_8Fl8xq za(PF9SH?-cyCEzXPUGIMHmc#fBV-t)!lkzoD(%KKEL0}>@?DqYdP3XK=2M*Y<8SI4 z%)TYQ{Da|T100-C-35)B)eyb$1Wz5}2e4ekthrWsB)xH-8~<;kO+M=L z1@F~{^-TV^c_O?69CH3!J85=L>fZTNBu-vu2Yzdzh+yId?QWHFR&El z{6)4eWKWri^&~Ep_|^{o^04o=+Y%t$EzQ>JBbsVl0*K6!WMd)~R3e|~)huoZWK!jb zVrebpjp17(zHk{ zEcUWv#ebBqh3qXh>M81nNdxPOBUpv>t~|K(MYuw%e3A>_D+6M{rvl=&P^K;P2Izhh z7@9F{ES;cgxH^9p9)DQ*X*OPiZA6_IcDm(2ub%8`QSfVa{d^1Ll46d)Ug&3urbiOT z|4NJK-)R$9!^WqzltH~zC%GKRe%yU>Ph&5f(VOR59>uo@o;MICX2_lW3*hdL0t>S! zyyW24@e;P@*c~H*HCM^&u6p0Qo{}e}LK*~?5d}ZCG2WA;Asn;N z8YLZbW!0a23pKEZ{A3e?x06VSjc3jut@i_OB^NzpoFJfVs+!mm8c#8Sk#M0s$lCyt zjckIVdjEg=qRBfQJnV-;%PcM@1v~xeA?Dm;@76v8#WH)#SeML$$I)zFmy>x7t&DY0 zhEycpT>5FJEbOFcWWZ5XC&g}pXTyDx_^MTOlu&#NdaiN=5y`mvWDCjXVKN3Zi@*#J ztdoZ|4Syuru9r_IJ<6@BJS3Sr<(YEbi(&?la5`A7zij z8pH+r1tL6<;%ub91ZVWr^m@IfR?-BfDuw$dFZz`p)g9h>O#Dt{ooH`&+qg5UP6+O& zelX1UNuIlJADgcrQpNOjXQHsmPJnS>nCWSKx&qH-H0Zn8nS$exy9raNgyD{1VXV()t; z2{jKi*!#pR8Bc#~j?mmF=`6|hf~YQ5*Y^KENk7Aou0DY;${}$C!Jw zTW7}CbH3&n8~;@~B$TD$D5?*_QFyIGXQEr4js*Xzp)ngB)6(Dnx&08&Bskb4_7 zOd}#XB%A;KP@ICB^kQ~Io_p$zJm0mIS+MNlhtomLrvZAx*EtaMAx4gPSndL8j1A}v zNNmEkU`8^lfJkY-ud^1c);FdO{flhaH;BMRx(-TN096Vp({~Ps z1e5ghLAlU7Vdq9FzRXx5oDl5p;#Q1r&2H@f0X;#&z8JRtz>eJXrd$?6Hn48Nx>G{+ zE3*Xof7O-#A~Fx*?NqfbQEe?`-y*NbbCbcxdUma=t&9w=yN+{{{x$Qz?K%5N$KZP* zV`C!Es$V&d(%c`Ill(*uLXNpVO1MR~P5YVOwI}T?-WIlxL(+fJHLJqQ90cyzF^@5h zFseOIQ|Z>cPr=>+ivH?bty!M)QPdmExt3gI{{Ru#b{>?T7tkfPyPs0jZWiNK)G*gG z5y0o}kM?^2E2@GIvfIbyF3`+L7{=eFb;g~Hd9K4q@ZFZ3JeKhvC3C}++N^tXo;r%w zu)K#vj%eq#Hxf4r!T$gZ`-*Zu_KuYbNYJXr`vBovKTq;%yGJ9y&`5vTMj+)6r}_4( zQAFu|OZM}_tZ1?b)!~{q-5~6L&swc(r8T^MT!ovfCef08&!tJ>wTn*Hk_KNp&IKim zHr$`<(=`3fajM)&ay+@CbFlr~FJV>WiI%2w-L{>#3>ERnBjyBmrPF46-`&XXxsFy$ zbB{yqRxjdPX}1ltZX9ksay@-|RS)eyE+$_vBPqhJJNutXYf^Pah25K4zS$QRr{z}N zlabC3^r!{5kuUn?xNHXj2IkF0XR7&5s?Fv`$7>-S$?6RgGeLIC8R1F%c>IJy z*UAb!VTMN6B=D!X#WnKM3>Ep01PXK7{jSAu!DU00Qbq`33_Nb(hL+w_>TaAH$$;NyBwQo<=WV(tt zcMZK1sQHIs_0M`8gu9gD-RhAO;TiMB1d%PSsN?_{2z;Y>)YsT{I8?Ttyt3U_`# z(why+t2XcTdHds>pL)1a?H(J3{p4;k25>Ry?^SO!KeZ{E60z=Lc3_fEe9#(Ps=B1F zD|yVz9DN;AYY)R6Dp$LeVsGf(318kvyPv!= z$~t3@&ze04=p>fgq-Oi8jOB*h{c0=NllOB&A(Q6XQ1y(DLr#kB7u6MhX_>N;r>=ed zy5gzo61{_%)wy6w?i}OW>ConY+`e@mu?F(IxZQd-K4YFowkpksi#*GSn&BCQUA$0s}scys823$GC4-GF9K?P3{nKm>c$=G0`inUy)hC70^wn>6X3s z>}6$sB@Q@o>74$w0`f0GJUWuGka;&DFs=MAk6z%O#-MvfFXhVnCSH$^z3hGe0G&4K zD9y6XZzB{?3#l0L+uz!(X>*-To)?dWT$u;(bLxHR`VRfY)}`|Fn@zE=?~AK2;iMzq z`X04j`@^Eb*@MaEOrREtar>1#gPim^r)!t1edOE6582gcEEqQ7AnBZrI{yG#z_`7b zU6zfeRok>KbGscs3VRi9#n~E5FuPSmnK)(}nyB1f&3k&@WYRQ@0VSB@jw@SeyS9my zl0}dn=W@TG{0?i;KV@&(-$eNHcdy&uc$u_)OHH#g+1qT7ebeE(hrnf4QMdvQ8zAw4 zEL$_mt*7(Bh_fpwE7$J*DkzrX-v0o~Z!JWJD$Rl<_B7o>IU~7}Nt8h(ZGyW>w&BMa z?Vnz>L45MU;IcCA$sFWREd-NE`!&kVYdc!rL^2`-f_*uwHgd<}FC}kbRk}QhQ8t$U z0C-hfm_F9BGM15w=Q!oN{&g+A!s(Lf_ao<<%qt*q#s?pZQ1%VkPVY`=H%AU+fq`J4 z=KxeT^P5;^D)KJu22e6bU(To1B^qt?miw5l@==Fj{(m~H9kiE8By5{5G94QoDtZ@d z44P$~cwME=;<^4_l^w;e+Hj?c%%ce@PnW6Ty*{;e?@DVJm86%=V!0+hK=0e9(w}dr ztoUVBZLyWy-^O_W5$Zb{pFk>&B1?NKi0>mR=%B}wob$)mHBKi{5Luh$-NR=rnf+?v zznbsMf>z4g#v@GhPI~@*s=MiPh1(*uakwLS<39CzisP?s+S=-PWL>ha1(kaHnx`x+ z7#maWj&a+LwV|rCZFsD&B%2XcurfpRJ$Mp$V4O zIf%&zVcIj1*A*qTz_?c4th;ccOmZ>L<5ny#A-NJmag!SyhCNjFAXRp?`z)^y&SX|Q zSbm1BSY*uJOZjpsZQTcKR8d?iyDIKz#!C(vm)jj_ZJI~5c%)^KbC3ul0QCZ*yMe8j z%nHo8>N_8LUSRG%VV25}Re>vx{{T_yDXl374ZQ8fK|OQ*1zOX`_QjNu#v>OHw&Tw) zo;a#kc9Pm$G;$`{6yT0HA6hpja{mB_F8QU~u zklNg1K2w9W$>j6UW6;)ArDF$TJ->r@s`nxU@9p)0)cM~Mm4h9OxxOXS5YiPRUZExh?N9RJ^Bk|0AvxsKK|7z&d^4{7Hz{L9ajRf;(ebsJLQ4) ztt%^!F!^V1&zxt1IHk}M)Y7!ojrTGhSm2Btucb{WVRAuS1sNb3&XU>erbcD`+`w`@ zM<3x=uI^s;467>3o)~esXQdYxT}f^33}CA6VjC(r&aKJdp%pvmXM zwoTEtc{uC-b5Yq$x^2*fepX(so*UMZR~Dy5rLxA1GOEgX$5WsG09{$0RWfbP+ydFo zNBQ=wt9Tk#P`$YrIL>Orgki z9SQsRs}Cod3#$d&*Z>J1=hB!*k}$k7<(CJz>qkK4Y?n^Bf<#p@uK2+vNc+p%KjBs_ z?6YU*VSSK_rc_4Tg8bdd`@jCWvtx0(LZw^FWdssG59>yNyvZIcM8OqRvyp*}=Af3? zJ>+ecE8k%NpzFsz*rprLv$ICZTX8rT zs>6(f%@quwzR<;(sK!TnDczabA4T}rz}n};pA_9${i;iE59A3z z`BG2-Cj+U;z~;7m8SqoX{tUP?+S&QHJp`8x=6QT{0P$UbUAG&Umg|+z6wz=a{n%cu z#_ph3BzLjsTH1u0S`}a7Wyw2w3}%?lL$Lnn&s-0tX(m-*Mht_1dEjD*{{H~`SjJEB zem_b&i$Xb@d;GhLH$6D~>OZtI$jiGMaNhN5Q<$^Z@Cm9d60GXmTW}a&dQp8vrOBRs z#iSfFb^ico+*Mnp%nZAqZzpKR4Op9OAsFt;4WMVPY6&wYakw{cfAfl^xh}&5K3rRf z`@`?IJ$e&VZ?&;&G4oxKcLGj+_B&_%YHecapto5Nw&VjK9=^x({OiO20BFyT)*b-x z#l*76WVmDH!vYXpk@04(=^((%N+Ic;8W38xC6g(MN6V-`iG7@NiT>s%r>bye&!xF+NsaV zqxC-Z*Vx#3FsD^Juyf80b;dR@a&493)4aI0E>~^{Bd^yLYS1;Nz*$%>bCLZATG)Fv zhQ=S2yv8Ktj&{^>*(9&?dXg|Y1I=l()Lh0~@p*SEvv%hr7#%x~D{-yS?;15+rvT;m zWaIRxCWq|iIf}RL+X1`!kLy$}Z>Ea+ONi!Xe&q&zeJL$iv}VQ4g4jzOoA<`bKsn`4 z*QI97B-0zFmuof@h71TK9zPsbz4o@(cTwBP405i;^UDlwIQHmqkH(SoTYXDuw~59%r-lO&h6#=i#AHCo`bLJM7+W~m2H`4aImh%VYr1}{XZIe zXv?JC&E>NaBMw6^Rv>ir9`spDHKdVI-yYQyQJTtbw^-Ye^x)?TGo1H zy{s|Y&GN}~12G41LC!JhK+6L4^tkgTWV4WN-WTRV$G7-aKBr)|Z^WD9B(lgm_dnxT zF3*<|LmNBB%-K`(cHrmyYCC-xPk(O&lR_<~a^g}!^81zRO#wwGnQn}1ip?+^^U3xg z)}+>rrm)@e$0sZ^$tSqbR#?k3wGmjbc<=015n2e-aG>1}leD>n7{t_Dz?{HHvB zpK6tRf-1`-k8%+VYV6qk;|;7wx$jx`jBO`rTRe=C8>#wL?-EC|MvHsm@MOq_pD=p8Mtg-onIUS8jb9E-S^GkyyKf3vc z483qY@;R#aHj*?sKQ_aYjx&n2Z6jPoxub2J2N)}kpHV`&L{XKt^>*sY4mQ?}&YIR% zi6Hr*oC!9Lz<2)u>(k`Z6qrh?!r1wk9mV}P{Bc?ux;4*->_l<-K1ndTDclc23w>(& zv>MdQDGPaqHd$jMaz04feLv5oL2ah}s_?9NZOOlbfsjefS~il{S~kelkw`2VaysN^ z-lWxhtBk44CnHy)>psTP~So2DOV;ia!QUtKgzUkqnA|CZRGinl(=E&4@@6!l&xU1xs*#Z zth>JN%mL||pH&}XcdK_-lInKwrq%N7 zP=Ld@C#WA&O>9=18Fn(t(<=PGFd#8(V0R|9Af01_8((?j<>z)g)oXWx(lP#t8?PaR zkHH;tf!?P&%-?4jWsjUIB8|A~kHgx9WuYr_Jucp3GwzJYu8eYeBN5l@R7Rh*zIGYO z1DudOO;2$#21R)@<^q2Hah^X4V3{9k$NW43Pf_nnsao8<4B|aM%-gwOZZI&sj-Oi3 zgI1ct>vSy8$fxCKn5h8q$?MNbu^sV_$>LV>*5D1p*9Y{hyXV<-t;+8i#(g?|6l@Q; zD3HiY29dekU5gf|($jqGyPbzQ82iEzUFBen;1FcAC(|1 zN(GE@IV$bAuU|kh$FC-zszfynA_;9lZz@*vRD+xl4tiC4S6S^OMgSb{E_;3zZEh|t zv>T}{nOp4mX52c1z~j^2rS4H*#1O_338a^D%Mz9Vjpc_2kH8*ks$R2cj~B|S*#U|9 z@tpPa`cxOTGwL=UY7+Tsd5|&T8>g*4+sM-3X&EHBlOPVESL;Qz0=AKLHkWngMwx7a z1F0zErgDFsbh_?|Z>H#pdXh%5-agMM21stCXVb6eS=ycRY7pA_n_4*I0Wfxj=l=k& zTB~mz_k^x=xOTLVf2RV|FZfrAc;2wH?DPnEAnozr!IAC#-dH^aR^DnnK1E}<;e&bgLl_#BdD#jS?4mbxV zrC8K#<(l3(Su^Cnm%M%E{_oen=~du@KQeOCfguvtbvY1e&6qR z;-=b<%*~25`!C9^8x_gOb+DqMwjQx8}w{6)}*RkT1(A2j*_|Rik!h-R4K-whnj) z{Aq@4Po4tTX;n| zS|vXn>#3NAajlSsXxOVUQ^sP6v&BfF) zTr)kTv33NEp#z}x8LUfvMnqLsW?ncwzXRK^YN(TDLa_Nze7m-uap--;Ngz_H-!m!W z8LcQ|i&&AQjdw|p-l!O58Q_m!!m{qIm|VJz-|II5K2;;>+v%RvtV_7%xQ#w-!I@P2 z!+=lu?M0KU>as3Z<^v>hPp?Xj0HDbp;;c^mk@feeZWdb!JjE*G`;6Slwz`ZsA1LP_gN?Zz{ducTH`-NxQp3=3 zlSh#3_cdcxp3lxk$8(b_w>ayGxI@#Olnd z%B4Xkx2PhiT&r9y)r0dQs`t-3eL1C_vcE73xCR?Y=A^Qh?CrEDW7HBl5${fQjz|fN zWbXO){okcXB0CS?t9{mW#sl=J56dp!Gh}W_BiME0(=@hl#(});(kAd2N7n@Q`g>Kg zV;nIzl_+(NK)H454oJlXY1D=Z)yPfFxNxCI1KOsroki4&dkmgBk4k$l*}}TUvNVT3 zAPcvSX>Cj|cP8{^U+(u}4{DhOu1N$+{{VR4H$Vp}I(6w)=0oRw=RYwUN&Nx+Y0=6W zM~`XdLO^Z^{689!IAe}UyuI6lZX3A+ikODPI)n@$*i`wklHdxC5VFGIw+S*29oLY5 zrD$8v_PAt@Pn!S?uMBvs)K4vyn`<4vccI6x6g_kux{mTU$Q3^6_s%$|Q}3uBdmB!B zRKYe3`HBhc>CP#OY|P$f-<62@xFh+|Zi7s%2BEi6SX0br*vt=XRi>40K3r^N1#^x_ z{{ZXLmI%DnmvB{8+qfP!=bX}AMT7E{I8elA7##lqoKO*c2(Z@RspWbFUZ>upQ?^D; zyCmD3=ZyMQh$HgdS)F=r3cQ2u?M*4MpZ9xX;Z?fsqWuahw4ye{H_d^Z5k)ojw*ZFQ z$31@rw=X2Gy}dJzqN&~8C4@@O!G2A_ zfE*vrqr243n!mH}y zYb({0Zsln9{HJhYG65cjt~#aW#sUFT#C|?&Pgm6bYxYD+CWwBIsG8zn$dmLKHNVv;18qr18gvm1F3 zDq!=;9Z%M-X?lIc1*S#V(R{4RF`V)JDhs(`ibkF|M(l=cjIlkc=8V&7XU>tEY|XR` zW2ZRurPol>_bKW&QN57)qhX!9M<+e&7S_#d@3S0j9BMLHe8AUhABQ}_aT_u>%nELA zx_QnIr~d$2p|P?WYsoa5S`CId0PaUoO6Z-=YWBq2yppPwWdT^^W1c}Y>j?s|R%R!u z1lMDIVH~<-jSL9T?FALEt=~D%On!CDJ)=)`%KreXJ9h#1$m!2ad(bZ;DP#LQ{hQD~ zfAOt@rirXKG;JKC2!}j2dgtj{N#PflPPUpvRmmi&!Q6kPT7WDUTbWh&ec_H2)0dDO z{*$Lhw^6j2c+ln4F$}{eim~FD+HF=>i)%)s=261{Msx4@X01sgMI_3$!bWEx9N>)m z`&Er*7<8%3ziL^eWmZQXxE+6$3%Jf!2p${7kIZCJa9vJL)9KQ-wJQ~ZQ?_lbv?u^) zJ@~5@+G^|4TeN$8%X5yI-JZFs`s^!btz1bS){ZivGb%|L zE_a*_qL~%ggG`z@)JHU}wakmg-#~hfz53OS6T_3kq|GMfHxe-6h%B+^Kdn23u1DgT zAe+QfNi=c~Fb6vr9lUXmTBBkmxJe|ik}}c!p+MTr{{R6!ezj}Fep>314b8bg!8{b} zkVZXgomlr??N)4(NMPUU&$c~iy~n1;_NSvs4ZIRGY!>M42%{~y_CHfrG%pTmu|nT! zxiHKDVH7DD_mF*@kx!$-E;m$b6zR7DXXN-9@yAOGg)0*$G+rn`}VQh&j58lTEF2f zb{$6PBQ~uhaG~nkO0mXv9-N(!E;q$G6@Xx0?FaIPR=k z-Jzbu9oIHan?f*V?0*viWS}b^!#D#yY!^ymlaZiqT!6a@m@i#*{Da;kSn?Zz2H+9IUzLufM-a!k)|Q zlSyvs%E5}2$5Ya`2DkmAXAD2PQ5z2}(~}YHkLoF&FwvSFW-G})SlF+h&RNbu$R9)c zQFaoFFvgEGR`Z>ke4K9FK4m94&+?)ORcvMRT#e@#BcbXK$NvxLobp-N2&Yu2X2s zi8pOo6|lhn06JyOi?n7y9XsLW%N zV~~n^;A9`CA77_hNi8G2zqm=WG~AeC2L$c)IqCweV`8XlL!uwRV zOZI8l+4+*mEKMAnhslsKG3)r$H`;`f`Eaa~M+%R*{p@Go-lfwuMzgq&egYQch3V8$ zx*dwQQQlu%TE5luIW8OSgYG|GDJ0V4j@m`Hou!e!=)uCb_*JMZyxXAbAW0TR<@)3d z3{^rVvzjT;Wtih`M$mIfYBHag%O958zFdGeb6Xchtu)wS+|4b+e({U#*qGsQ`jOI| z9je<*_Y*5WmN#LCC9}Z#e}ze^X`@%u^^kfPB$4Ba*{d_DoqzpxEAwWYz=Q1W>)NkbqDjN*$wYcLP)@Xs2P|mqrWP{f=IVLIBYX%uP$MJnX z&uV;$BFplzX!?@eVES=XPOO+p$)m7e`RX4&_#-t=C25v6+%kD24oA|ZhT~SoffAwbKv%y3W3y}Q&}mGpPs0C z2Zw~8x%B@43VpO~cNvmg{`yRf!#N#BYPH;P@7o^llRL68k?X}*sB|DnJgFQuHshh> zD62X)pAFsK=~>Fgcafo)}|1;QQ8Pjf{6NOeSxhGle+hoZ}eJHMOSPG?9PHJ;3bC9@r%AYXWB$Cg|F0uwvz_16Y9ln)H=2cyrSn_fX zF`Cx3y!(4KjltU_cn~oskbi{#07}Tav@uRekLFW?4+fT-iFP4Lm&}iM83bn-+xXU{ ztC-PKJ%e&Tuk@_eUFgbLPDkU%`4pw(X2D&hf7P%!G-`@W*=XHcYcIGt&UmX;R)s~n=<+A*;clme&)`i@bZfVwu9%FBpobDXs@TQ=W+C!a> z4%`C2d!Jf{%IpYN_?ffw9F?m{BFhp6Bs&ra$I1uwsk;bzCG!pHnwfjNB*p51YnP;sqSvp>u%LCDz4Fylh^!c(%>*o8CO1H^M>O* z{d>`2r~>TCf~s;d2IU?7=#A1Wz8ON28)(S~{QWIGb!JcLfo#%7S_yao(91m|an%!mvL(@t%K9qJ@`WWmO+A#~kC{owU?C zmX6sUE6a1!y;PDnihZpc#e`> zk2N;40s*^uKQnXK?Iwhq%Ff;2F~}Igny>bW0lu2+*YU6}Gt)(3(Q0R9|Rv_5n!vrPX0yd4fmBL@fdszN_0vAC-a zK+Zt?YJatToj2`Q=KypJ2T{_AY*HB>nccA~9Mt9gkZn5`25(MY0# zc~7v~V&m>I^&p=A0If4?c`LgI+qdIVM(a9!$~R*Ro`RN4^;OzWpzJG`c62RSRnRne zJHBJ`6Z};alB|(PK5?EDkmBnsqS4vkf+yi#y$NjiTIiE4&TBWZRD3%F+&_6kauSwbtb7R z=uDlFSK{Zz%O3{lGT&Xv94TysmvR&ke~X?zmGNJUd{wG`&^{@XQoRyKq1!MvF+WL2 z{{WVZy)*1M1KzKELGkvX`$u@WMCP)0uRWBmuUbdo~1R#}coBVKqQ0zRJAPr~-B zmU2cTRY^f$$AKCD0PA)9D_+}2{>q*>q?308dylv?{(b91G7)n2Qmk;Pe=&B*SZ5sb zioc;lF`b%EEuoNM)rZP|&#hXxd9Jkx*4{nQuMBpcpmfjUS@4UA?^&6TksB4*zb@1D z>VCC6!nV2^R@xQ3cb;^!E25H2LoC<>jGXoEKb1qMSTB(xnAdAA$vdGr*=YRK3c;nyRfKupP zTSV6Gq=H}cX4tGG2P)s}k^O6B^f>g{?OCL4k&q5JQIdLMvDVIQD_V)CSvIg%B>w;q zBlH#2rJc5fe7R=(bS&OzM2xbpp$3h23lvO(`Q^8a$i3Hk;~s?L)6$P9#}HYg4R0qh zY~w6>Bzx9_XtA4{i5JXYH9=jyN1#5QwY#DCKH_^-l1Su)XCfojkE!ej{#jCRia{ZC|_3PsXe2v9;WBy7`W>L$SK zw=fZ7da1x3xE*`d-#Xeo2Hl~LY%!g=eDRJy`t)iRzUF_0?qk#JuCF9qBH>gg-p_u2 z{Z);vY4+=WWM+|-!EgcOo^Uf(yh~+y9<>_ARjuV4A}TPe>JL0%_v4RRwWa8ZEu#IQ zq%RBX+?c|X*C(|tdX&2vz7f|}(^PHIrXNnz#&W;;pG z0QzRD>oZ#DlgAFg+f`aNQI=3ouT1`Rds5x3CfOvC6^`F>o#f^5(0cJjn+-aNf26@@ zdShi-q?0TTe(2-;;-}a39Xx1|+uU496I?JS%Zm)L^axH42Y;^>Ps5;iiZ-{p-EP}_ zuQ}UmNXM}E9M)%ztj3$--?K!rN#sVJNtfkGl=ICN?iV4~JR^0fY69ZcNNys@8Al3N z9A$y)?t9c)zr)+jGUncYDmIPRJE9?oJ$W7aAJVJd>c-mlX*p=yVnBc}$j=^~z~;KR zwY#LW7l_WXTPrMB;DOseL;WbbTL$c9hLIdT9K4zt6Z=9%5{F-uFGIHAH(*Iy$|>NA`nqH!(kao-FuNHS5`Mm<;OV^$J^!y zAc8%&8Y8CTH6gx}!%|s@*ZmgyHuEF{Y@XOXkF9i`9`QR`SXwIXy7MjyM&Wq-^gQn=(JTCj=bYr-jkIIkd@I*6>Wx zNat}MG+wEWyK~T!T>k)w^w#p_xznzphD?{5)lSBBZ@gEr{OdnL{Yz8ZH;%j}vFeIe zTU88p46=IgIXq|et~XlI>~x#pAIz5BLwOQsB3yR#>D#SqcuU3&;oFEURtV&Ux1nYy zD%m|we++c4XIk+E*N41SCL@jPW|MNjTQQN6IX#YQqTa;nHXDn0?;*Iii*y^X(GUYk z>-g2r5=OG>cJeebMH|}(Wp=?;B#nS)vFtrFRquQ_x8u&Ul1X9bF`Vv$KD=}3pXXgK zi2N-70NB=RB!Jvoz!9=Pd7n&osvj+k{{RYq$M|)ULvLyXQlhp?qZ|zX0J?egtv?yt z&1Yn?TFJUgDT#8Nw$si%yVjS(?+!zt+pViepKFnXuFP?{bHb6y{A!+|;w?W$_`P#x zE!IfyoJVybY%U1-aJ|4d8RDgdyPS84bcWRKEpM$Y=VjEB?x5jYBp#hV8k17+=A(6` zEzFVbYeD77<~TU|3fb2@TQr)y+GW#2BrN+QXxGa~{SV50eQJ%KjJnpC8rJD8E}&)- zTg*r-RB!?AN9D~+=ue@o;Y}vi{{X?OEK&yY%qPuj@semSftL-8{}T&liX(&oAE=#$)I?uNfnHc-6)zj>B;-U zJ@Lu>sl*6;AdhLNG^sRswTY%)p!PpH%xpNUyaXR_NUaPC51cYh%K* zs(4FRyo{{Z7WOTO%U}S+Am^`o<$N5?YkJX{1Zy--2`il8N&Km;?0~PS?UByaG2oHc zJbQXodpR*Ws_tx(!~LV$v^BIAvq=}3=SD!1IRN|F!OczK8wI_-KQL8~4(`j5#TO^k zcB5eNTFG@j(Af$AKQSNvuUe;RYQ`v?qYZA-D-87Of)BlFc*9n0Mq72aU)-4pNZE4R zeSLW}?E=y7=ekvuR^A*<6mO549Ju4PRrJ)NzQ1m|I(?E?Z?rUqaHw;^B#*v>??RIvGv^Q+KzSjLis3!TVc2fwa5R!*mK z*7`M^Hy^uYl1CAcLnc56^%<_K!>b2{JQ1s0UP9A-rr+%G?_Ge%eq;dpj0QhS;by;^ zQBv|VNiF~~F&SbpkH-|RsIAa#tebB4723J$o<9oI(=L3?9o9{IL-w=QIW%R%oQb8Xk!^u{8660f2CTv)8xF< z+UY-du#x6t2P@M*%9{2HBY!QDWdso?PCfnq09tmBthR%7=0?t{*;hh-R|l~km0ENH zgR@NiTY-_cs{SA2P?NScNgHldg&}(SXWF&(dlk32j^@~Ix40XWFCaJfezja%{{U#f zvM(0^=Kv6_Jwg7InKtZ2r`$9LYZlzN$341!My~y!N?ErtX6NP|z3U*cwz*@qjE6jW zV?2J9b}NK+;1yHJ&tsa7wkX!Kyxk5Jn{tedcKTK8E7onn{Lhqq@%%N9XK=8}4+k8K z_a92R71IX8e9N5i_i^k00N16^4LycIxpw6_KHimn86&yFMt5aKLov#c_*O(0Thk0W zaHM)wn@oiBRhd_SNIicFTG*bZvg$G1Y*q}erzhV({;HeL9%k>l!=S+Vv;P3stocx0 zLb3)b-S9GM{i+*?PUVqhP)coHSbNf16uS!0E$T*|=h|ZB+zdkC}O? zmCWx0ZIM)QfO#gHKINOH{)Cdb$D#dc^8&aed!lY+RL5L`7r*)XQryO}72TKGpc1S1 zxTuomSa2KVUWYtwB!81rM{OfW#eQYyAdsxN{(X9TRa`pUuQivLt@l|}{p@n1`qOvH z%O2)gGmtX8k@e_mVkAiNWDO(o*-pQOM>HqME08eTPFJ|}_NZQCDoq~wn=80K1UKF3 zQmdA6zb(+cCsD>P+*3^Dglekm`t zjh94~-P9|N{MB1o#IL)1Zd{Sbf$Rueb z+|i+Q8NgsYOY0=Y{R9 ztgYjPOjfWcK(VhJao5-0x@pr%T*h+jPo?-?Ek4O%w_UNS^IJADMzAbyvOGN(Zx|zveQLvad-sa&-eY&c+Qbo`{#i^kM?z|O3k@s!i)^J zu1~kMG$i`8i#N)mGJkXjUwr!0kvy$9+*~wp#?C+h=acL+NNCKtx}4ig&|)~@!(e|A zKEL5rqZg9utYa>+whKA?$Bfp;iJ~WFkYhzrox3JOfE-VqPX06 z(xUTc6UMSS+uM1cyjCB3*Yl)S=)I*}EJ!WVHu+GHR|E4o_MvsDtuNJ-sTAi=|CJOpUD21f5w`$@!T*Kb=S5?O)5$rdjtbyME|DeEWSpzLdR5(&na@ ztK2t;lw40E+Q4?ifrwQ-kEqWXs~2(4;oWVAog{I|^Lb=$45zA|)ag7qCF^cUnmagS z-eytvhxc>qP13Go*A?=uH`!R6k&WNyKc!3Z4Q@W#D|@?UT|VC3yv@rh{{YKj$;Jrn zn#jHIy}h~^)n&4`Vj4+qK49dN)12TR#nHe*F~-B4RvE3 z#jUlj+~duW3pXCVyjFX7rKLiQu*YslpndIMXD^pW<2kTBs%IFK%S z`{&ZNt)sls^`9M*c$ZMU*BcibmD3!LocGz`&pFg@Y%`cOoBkmD~u|T2^@9r*PyLW7+t}A zBr@Ex!*?R6NP-=%2L+eYfIX`hLDgi`V@rmbRhv$Xm*)VC9(rVotEygH_=3jPR+XMb zm6Tz+4%qam3)qWE@cglB19E+$-KP6g@;Kdq2O0PNhNXwZQFxQYjPrS)XPB5{OykSr zj=l4W-MrLR*TCBlx0!CfUBWNSWPYPRhaTM54{dyH?p8)pd#2U-RME?&!%H1Tk!2vz zE-j?UnoFf2$M7f_$v=VpDz(MSYW^vXXp~DID6H%9i~^;H(?6wkw-<{CgM@|{;F@5s zBP!znj=1aBHI3mb+j#F=PLkY6({52JwiQYKF8zJ51u1L@W#y~K;q1uib$4c4%TPls zUVw~pd*ZJ=`i_&JL1%o;=G^?ueo(O~b;$Iq9~Cw6 zqw286(=*IsBRfM8*yHKj9V$xLtD@@icnZ?uYgv}=b!8HkUaC*0Oz~P8j+1b1zqWL_ ze7&l!l1RNXl4B!0V?BL^V(2q0>2WEB-)xYFiKcIn$mb+~o@&>IJaoEluWxI8B$8Up z=PJMm`Ss6CX9F3i>!2GxBJk~>i!IYrv6*AOXw==?DBQ8X_lG=#Sm(ow;yWpp-Z=d0 z89*-o0CcIzIP^7l!= z@CnEGny)Q|j*D}uLaNO&kgVSeTVCV6z?H0rBx*yFPV&hMdU(8?mXn(v9^r&vMo6iqx z@!RSjyn|J>62wZ0GC;rtdhz(6sf@l1>2O(ksZUQaocT*gQ7W2)!dpU72xa^g)JNQyZ3vGX0) zObx+LCm)aGD))xg9XCu}R)3rOGy@ZD+|KR5Uw%0?HUkF!(ocuJ9Ml>~E%$5CBrqXe z&E@V4?T_Ice}!}29i5JsULNZx3yl{hfy^>HAAvo?oy{@WOo?tpIXRWQH0GHX19$= z-LvK0j+KAK(n%hwW@c8C0nRc%4trKp*)_$toTz?cN$tme-DnZN50?dnz1-2ru(FW2 zT(e~V0Frx(biQVZqF+d{va>=WiHQrivvZE!0XX-h)}~d_G}t3%kVgugxcj7%0s8aX z(wnQv9CmTp$-_cHY`#J<1pfdoD?LV4jZjGq#_h6A5DFXkn~~S2rBSf6md^e84dxNI zZ&8wS&$US`vqcrW5vy)i&JbjSoag@lt=g|x=;GRGB)gSig&#(t3O`?l_S6{{T^v&|)SCl$_@X7d%F%?!UebMqg< zp5f4*Tg4Nu-<1?@Tn?tI&caC2Mc|T89cm>ghiGPCMlerGB_Ko>A4t?qBTH5Q);g&>PuR%nxKHyMo*nVtvBi@JD zT&U<)?W2)4fH&^kTzm2Ss>ZXbO>d*ZkjlyB z7LC=pW>)m{#bS{pL@*541BL66Q`X|KdrxJCy&=2{?y>vb@zLMfdmz~z}M-+#51mh#60cB$fQ0&~{q+^q` zdegM+u-9$JgF`heuFyLTq!O!E`tI#?W z?XN!5D>GyFhieRDj@49#YpD_Tt0L!d?lDg&GP}NBa7Z4WoYtP7Xf+$C_balM%M<bmAJeih$p0A^ZEX@J8ENDmA3BOS89?nagK+Y&G9_1sOwTX;DsVM z@VjuU+Z2{kn9+Q-W@z!j>JNUEQNH3{Ld^=?$sqxYDZyME{c1RtOK>+Uaz6MNJXMWt zUMuLN`IyTRzC!)n(O|2nywS65k{FAqUU!f=Q|aES*8)u<ODS`0i&Zq4gQ0D46BBZ zY^XPZ^8<{3T-J2W8FX0WDx>(febY^{xM;37sxD(3ZX2`e4M%k*=Xc$OW1XWNdhk7~ zJwUZ_Y4+G;kxG`gU*3-S&tJ}~TeI%kp<91m*sUK5n656{&twsVDu2TjnvyN0!DVcW zo(FmoxD%l2y*nMFwOh5m*o>05-pCmob?=YHsZ30cj2A1Mao7CwPmbWivVV635Jyjc z{|;|GqXujg0n-|XnhpFDDMNjckC_Htk<{HwR-&OY$%kym4EjjGJ6 zoDMkp3Yd-Qv7>Eu_68DRe6lu%V0NExU&6I5b&nyVDyBID1_91N@4@u?)=jgigUbH^ zmU+ss>(Z}j6GH;LbAIu0`?lSjH=&~UWAirUwvJnNkm5BNbB>BX`uVB`j`5r=Qe z!-mg8-~9b4w(@m1YMRa2Z?I(*SXf^&2M5t@9p?8yVq!ciTJkiOE?aKm3X#T7r9*ivir!l{`&^v+3d`{Zww7^7p_Q_7TbwEX06F}t zmNC}I(b*MzQLo3N**D&2UK?js{WJL2$v?E8$4jq?9wE5!pN8%x^3ThCe65YCz%h(x zJ$cWs6|4J1e$Y3X{=FxJygwr~^t*-h%kvvVBWb}L?mV743|AZAp8?0<=@K2gUkkg; z`B|8bzft%_*YAU+5}~aK1NO%k5iNNuCq_G^R3H#%FXhEIulUs zwXuigSteYQhTwD8>spY)Wz*yGdJ~lk^6~Voy-6D#x03?y8v=qco^zA@>#ERiSZRwS z(Z{(*B%t}g=zk8Chofn0akfdM@?lfUxf##3YkzLr#X78Lvty8C`9|NT^`JVIt?ee% zb&%H$BHG)Amk+|{X+Nz|)NbIyvOJ9%f}vHqw{xGTwN2uES!~f`&Sbg(C}EI_JCRtn zcFh&c(C%c6OSCG1{c3#!eGRLvYwUKB#SAF2I)X_(aypY#&Ybh;w(+ccb2`dMJbpis zs94E$tKLQ#zRwJ0M;#4x&_!l%m^ z$IbcVj8+z(qeCUEa5Jk-H}4(U_WZp+!2-rBobCk8~{H*rYniNxsYlNG~1Z6?Ofz!kb7df4-IMy3fn{hk|o2a zZbLs&{(Wh;x+mN9=G%tzCEU9~#9(JR6h>VbU!k9;w0HK4ZFJ}NY|RkPIX}?UnqP-s z`xfSAR%BU}20RGx4tVK-MD|Z}sz$J4V}r1T^v_Z4j`gMD-BM5Nh%IefYZlvZ$;t=n zcBjqWqXH%(;>eoL>C zR50hD^*^t-6`5meKDg1(appC>rU~8AiR>}jwH6lfJ&F4(e)$-oN9652d;0!WCbOiq zwurWVb4LpQ0Ihy9=e|Fc9)n_AYt!mQTEuOW%q5hJd8?D2KfB*Oc&2!Y4Leu8X(nd1 zn%zn=pbREC#|`{A$8lIGsz+m`OL-1=Se6m_nZVQtM= zBFW}k5X&-;o^ZJUW01a`eXBy^YmFbmawp7gwIheX=V0e7J914)bEMn&TGmU2jwz+U zFnPRic?A7EE1#QFn(Q^i(r%HM1#&Bg6Z*k&h~9nk4=4Aso z$8a)hBf=9b%Qe!j?XR&*slnsYqtRdcUsrh8x0f@S8Jnpf91ozVwcShp5&a~?Z6@C? zV(S?{GK}(l>3J}H&Z|$B z=il3qt@wiKOG~I@MUA4=BP`CtKRCbydSm*UR_Ipb zU)pT9QQFDnv@wE!4l+pK=j)2i(QR8+y7GLnBQ8K)+1NXC?@iRE{{T&aRwhnmw(bD&e!tM2stu_+Zyn zs%ZCmKf_rrFQ$ZB$2gI1?H@e4#b*~IMui5_08r8}5BPs`eYdJ;Scd^R+Rq-9KiM%0WZ)Cq^)GnKBsHzr8 zg5(q@oN#lF^~Y(DNq3;#TcWzWJe}kQ8P5QFW1QBbcsKh);pMEB;#hTECTEszcNrsM z0-W|LN9#*t1;>f>`>14H+N6=>$N*n34sb{Ht&~zijqYW54Q4(mu!=PdB#&D(3S9@yf-LIUe}^ zJ?dR%DDE_y`$*;U8r9a}P$~W1dXeAjQuhvHvhh8N_>aOGKCJ}Xp54ks%H!^W2nUnU zlh4=MvAkd5$m}d8)Zmdpk`Vh4eb&#-p8d(J&xV@B(nkiFbj+~%#!Gh~{^{F;k?45* z>$J7dBGxVSeKzQ-OrciNL?EP!Ny@h!dEn>14NaZL>S5Uh)w~mD8ru}Onqto}Jnb1A z5AL=<4r?#PnyxkNKT5axZS2MwH)Kf1*B;%wRgVfwapCLR#krFo+341=fS+>&_vzQ1 zdWz4~W`{?)k5IT!cCKT?3_0v*enTzzmqCg2xg(6LTrOs`iHTjnWVSF59X_}f&nv0W zt>zn=W*L0;Bc?N3*Ip%066+IRSr?A#%z2SVxb89FD*=u@c=W2bwid~SwcOFl?Iu)w zsk@vHZ{<>hp_lOv`|aaRxY~EgXsIC!jqEeqr=@disN4-Pt-Qh^X^hOBFy8gqc&^#C zZw^}`B8g(SIp-fPI(ufhoi@kJ)O`2(g1E{45`8oHaSV3|S6~=IxyIhP$*LB% z3nWnIcbKpHv%7+Q>UU!`d_Qi!B5Qx%d2!mwzG*h$kq2JY7maStyJ6>}#@5jmw}1ij zZB{=q_c{Ek&7GJ0BTzNFed~quB^$UapSpjYVca{}*xg34gAJ_81Y@BMlb(A~)ICON zay9+D%FXjA4W8eCt?hm}G+zxzYRa+5&L-=gTPLs34lA9|V&8upe2+2q08bp`3h2B` zb0zXTb8lu-&Q2M~AIgo`8Ljj-_5y? z@~bxyv59vk=3Ev4^%&3j6&u1n&NI2PbLvOqMaqexsLj6O)k2NmX9S#d$vCFzOsS~} zWDM}ClG!)|9gpMQqhM~Phs>LEG-?|Mq3nO1I^m&;3@bA4ZHx%)zLdQKo1!$YL5EJh z`9Vv7C6AtPPdNHy3g=%wO7IB#rF#)uS5DVH6o+eM+q+<}?Z)hVKU&9$@;77U`?<$M z>+MoDUYtg@R@)U-m~LeN4u_htuiUH}v!hKLCeV26$nW&3_N(^$`#51m^EMPAkKXyS zQeWw-q@T=btZKJch zvx+d=6-e5Dg!ZaT3~1Yb%-tWI-8UL#sc1D6Wo@T;z~Vw@}EyZe=K>{c>n*Rw&BlCfu#Js0Ywg*E1~9D!2N``Z}%wAIQ=? zQh8-tDi15h?^;NrV9WDk*KzrK_oD9F4#Q-Wi><#d)&~QpKH2_N4Ycw$<&*C&O3D5H zwR-Z~Z_GaKGoHD{L-Rk&&fIa4kJ6`5*s*VYHMV|oy$RuZhPUg!C5^Z(z+F`tI1p9h__3J{`R)rgkhC7PqARp`W zth+5jLlkocP|N@$953ZsA87kPZM#IQGDdp+DATBFv@|TFVEi&K&U!z}KOWyocA{3{ zxXeXH(#qTh=bE8l+n;XXmpmQZsjUq<^c5>{8%K@~N8TS=oq&$YM%uYu%rll9e;-Pe zZIv-5NL-BcAoil_$PgKLQ-;9w_NK^^BQGlH&UyK;2NWPm<%1JS@s(48a9bEsY0SP| z$CAZM5N<@%9+85??pzN zm*s4Hy*hOMlu>3g>YaaD`vtoJwmqP;H&QwGua>`Rui8%P%2)8ehutLBC+1lfEG?sK z{O#0doR3P-{ir`_seCbw8%F;CO4sj{s<1g*anpN`$EA4h!;b>Bz01pd?R9@~A)0Ah zmvdhcOSfRKqs76SnK7gPIo%8f(iS?@tSN_ zYjJzDs{P(c=m$^p_*Rl!s)ddy<7Pz#GCGf^^sbbi#!l>RpQpB=B85UY`^-9z@%F7W zm}%Izg-daalZ~HD)^)Yaw$}@_vJ@PQQxox&)@c} z#K!*TWA0W~;3DJ|$^B~HkEO#bNx5Y67v^%@a5)3=?^UCVGAk=?3W#0tr zZ(*p$qY*4&l)gF-Q}v|ygJmRtXNhE*S*|2$PbBUqo_{flgGti2+a<#8R=97UC+_1s zAIH6P{wJ0{?E7hzVVYqM6;XIr1K05WRJ{sbXCZTACC7&@*fS!=;x@-jj(PRzSUOgz z9f(+=LQ6K}kZ0sSPf_bynyvJgz8;OF%E-42u0ZxU?bEGuwnyxGlxOcRKQ=oK#+*~Q zw=`#4tA}T48cDKLhkUo7{VK$odU$%(B%8|nb10H9es3vyaz4D)ho2swJ-yobb4_-E zLSQ$NNXF{InI&yZUfjrA%WOGe^DyLaJ?ib;R@AEwuQOh}lW)6%c@)k^B)6~DwY9Gf z#{@04w^}F?ET@J89EKjXPUiM4Fvu<8*u}m{58ghURUIQ;eKJ;#T+bcGa*q8y&-l`_ zdlYqAK(w>)>~~89-b^Y~OyDRa@Bkl$NAU9YS#_ywU88;5in$|c9+~V-L*i?ZqB1Yx6%yuIY(CyWo}`qjH6RD$~Pw-Y38(V%~qa}mydq|_^SA<^T8 zMrBoYWnQ@_xgON{M5V2SZE)Esqz2RO$bwYlQ!mAt=>>Nw0%%@B=HpO|g=c|Np&gGkfT`qmhC`EuMbEHjLO zoK@z!lf@n%k^0T05J5Ro(ewmyf(HQBQrsIgONg8_un@7FWG;K+wEO{fA=KkZj_75~ zQmN?Cxapr`gGxvW)6W~K&mr6A6#;RBxE{Whv3UOgYtXd_Lk-sJ9tj_Oob~*=RdHz0 zYxf#lkrk5Jn4n>nI2q)7p=nx$%rUCX zx60hziQr(`ab)7mWCS_@aX5!U^nMVY4J@dsJ zy@rlXU2OQSMr)0$e5C9O2wBv09?UAu)q>gHLo06GaT$$(KQPWl593%@3YIt57Unrt zXxx=7cHm_5^ugk~e-P_7*FF-`+R*L3SsA8MFit)FI{kA>!PMoo3t<$}C!E4Xd==bprSBNpNug=CKWrN=n&su3gUfdvG1TYtu6?x_bv*^4x*1iC zmIcPs6AT^?Z2BIx+@yTfVe3AK)+q}D_IpD8SagSW|>BVzT zDlGe>ZK^VUU`_|W<6D{~t#Br0xI=^#U_7~B|qeG*jx7utO{?P5&SnxeS85yot;>E14?vh50 zQCK1nal0hpvFX$6PCj9&CyHcL(=6UMZ}fsm8UE-T)S3#$ZFgM!vBMk8`8;8HAD>F2 zs6vu7Vmlau(}O^Ng%oP0_L*Kq-U&0N1W=9m^WCFx&wu$EYCpt!J5F(^ql%TH|=nQ}WO? zVyRZPK&o5JZ{q6M`g>PTF0&emCZ0r)WmF*<$=kI4T$<-}HhJ~vSLS7qmMfm48L9P1 zV=+2Mw>Hh@p zqk`SdbUI$7(doKf=a|!dh1+tE@3#QgIW?1MTC~x^e8t|uzFr8)BR`%hl4WyfG{q{) zs~+OcKN3w`@nx8>mc|I=-nQsQ;rCdcO*;DOEj5DM%4SIrlK996xC0%lKU!^#YSIQ= z#lh>})A6B4Ta(b+@b$&cwWNP#+p{!sPOcOljn4z?#bG|^TqJ{QBNaXHM`QU@w7Z74 zzbdk@G7`v1&r9l{Vrw^5bkH zE1Up3AAEGD#dM`!HW(z3Gti&&>rrV?$$hLxYq+*p4a1=4ADug)rdhvFv|R6jSN9+( zQV&onEmePhpgQ?@$Rn@6(x-*x(X~sZD~ThK)a3lVaf*WS(N|6rZf}(vc6zojK&8}N zy-}?UCsLZi#yK{_G1?3L-hF+0ip{yRg2LkN7LnOuk)lG}2f@Modj7Sor8?MN=@Z7X zEZ8l${{RVIoPKqasK~mF%S;q3jUn7Kz~u9vem^>!BCXu9qFFOtHsVpEjJmUoD;|r_ zty;?a@{ihCh|ASwYS^_Wf$yP3K)tWq8l$AS#TjyK94v zPtcye)O8h%tr!D-BwsO#t4W-7;Pd?|7f&)-GCus7!3XlKof|`MwMyI;iYXn~41xeB z^sLzIq_~brBVEd$dnafE^X8f#E}9zN2Z!vJQ{Fqa%XrG;vy;$!b5;CBsIIYTYb1%~ z+zrav=ZxTfG`I4unc)oDB0&HoMW1+JZv-amD~49kC*bQO5vfU;r*iC;ag+2 z(SeL^BftLuUaD%d$3Cxes>)fIw$s>p;-&E2-`MpLlen-dH{n6_2l1?XT_QO3Ym2`+ zMw(`96VWr0MGMS}8WzQeQ};;9_s3#QJh_ejUBhs}0B~uMzU5!M7=j0E{v9f5tv<_Y zcSyy!DjSjY({3^H0|4t?5h$u$7+O5+kS1w<@VZf{9mpq z&bW*^?IDN&6ZcIngC-lLIo`vN4tpO{PB#8g#uv9Eo^ksAG{?4*&PEK33k;9;hZz2S zXl7;r2ICzmt$@2{cw%N*qump>2tPJ`Dy99qTE0t3wXzW78?(~~^{0cdaM)avjOW(0 zWQlbj4@S}jGDRpwImF2qs01zMN+O@3b^WxgFAC>w)vqaIa2jxDV#MW)I z$184MF=XQ%@^X4q@!iK8ZDo<0xjZ(0m7S4M(H1TvR*~ghxIAO;0DsA-Cv`~n?nPM6 za>J53^{L+M1i)Ra!y_Y#h8NtynRgyR0lz8*%ATxPW%8|LR#F*G)gi+v$5KC)GJlyu zx2GNQew8w+#;qRpaHk-8{{Z@`8Q03YX#W6t^75dZ?fgHjFt=i6b!Y<}%FUH!3%An; z^)(I6;kZQ^U84i;^!BLZW|lCF-dP8y2S1PbH3@vXe4&&Kk`HgCIR(kS_iSzCgY>3{ z4ZCXe1m(V!8Bp%326*lKSgD|uT18W}w;>-g^!$INP4q2msTY_c=0|1S$joKG&;I~l z+KRShQmV?)0K<+)AW>6xEl(rxcY~&ed9@8nR=U=&7)d;gGE1LNrz4KQSD|QDk?HWX z(gk@j^5p*jKk=;HKE+Ecn8)!RI-gIaXnB~Kj^DfjFDC>8UAv>7RjFy$Cwp!u1QL4D zX&H{_N%HP~6B+q>p0yx+ouF=A*yMfT_)_du3%8>a$sGtdriaa7F_gaYM&Fk#zdtSP zMJbQW4pscMDiwk6>)W*&h&zqJP0fwjzz5QwYYWY0cW(KP7ag-mQhiFnRV@-WSNT}5 zZ1Q;GwR8(XENdss3}F1@oQ}Nbik1x((|4H~?2j24;D3p$iMlw%Fe`lDD(&k>DDH_Z zVrgKyVdhB7$pB{@*7lte_N}rX(DUl|6_Q%}i%dnl%gL?F1j<6s)!dwTkx37?X0ct7kuWeAx9BcKPEo z?S?}dsLz(%`{&lPn$joQ&6O$2xb2SBCHwuR>p6AU2Tq@b9Hg5%HP_izOTo2fjuzNS z`>c9>f2C5A>7Am6efw?{vlbhN)}IV*Z>NU^oo*Xp`M4l=`jgxFRd=^HI))@|u*dh9 z4uDb1*m`s<>b5^+)1qsvEvzf@;1Ri)@CU!IwQhJ@TAEvCR+Gz$>3q0WGB&CKjOX${ zTIYOUsWz!3aWeq~C<3VJG5B|=ZM7DQP=#S(<;5q81*-%v9ifr#&j3muA=3$s2#FkCMzV z2==Pw9+oxri!*JY+b+`_myFUsBRCuYdE+%m%#v74tj;bKm4oN*j{g9aSk>=V=G|oS z&gLwP7n}jp`u-Iav|+D&pS|Y~;_LYH^!(~$ZlJd;+1!ZbwT?DvJmKYSCpiZvKcDie zn)JSCk`!+)Yc|OQ{mw9Iu_(HNF4glbSnb*l7ah(sgHRn(88w)t2R>;ry94)*a65lG zpF&$@R=A950^xVOYRnx-%C7^r!bukvg*|(1yv4Pa{pT@J;i_2ckaTm#vin|7-BP@{Z8(+S0$E8vc{hr|M8qq?mnM}Yg1g*V@oE6B$&-3B#6O!gUBAWk#lY>W?%Jf8hqUjUApo;u}b8} zxms3qxzCxM{El*e8rFhUlTVE9K4q+pBZK@vjO2bbn+=m*Ya?cNNH-DzI}hQ|RoyyB zVOzv!R#6wqKfH59wJODX`9ZK$kC{L%xc52h`BmFDYh5PwmnGH#F5q#rf;t+{yS8t% zedDxziWimRwQ1SL(pg@WRo&!)$^QUob?u53t*9NpiFJ7OYdr(R5i%{s+&)d`9Ear& zefa%FaXP($({3bK+sxX>VUw?3G6(amKM(6_JT-r$%%PU)Jm`Pvo30PnpUbUQut>FQ zefyoRE#f4Cxh}k9{vXz-U5eCqiI)zQFlM~zkwoFXjQFb zWsXMqn_(FWao8T2r}zPy{{Tv5-HWS6-)uMk01xqhEaSap=#d+XIW5!7X&WvV8OA!3 z#U-8J_FK*6+V#y02cn#H=3SG!f*yQ2!3 z0|Nv6^{uThSNn8+V#dhI8cqk@0CYcM`spP+4wWy1BJ| zJjdmj+Br9~FJs8h<4o}HiElhPbqtoQR7Y?dZ>Z=&J@O4w)9#u}*%Uv`G7<9+mo*!f zwuxJEhgm^f`+xQ6ley?x^1a*KLmY{7A&gGQPFJW5y?b%TwQ$}lv>HXtt;~F>U!Bxs zF&~yV?OR%QtkCPwJlk0>Br;7IPnCff_4TYRc^l8Twqv!Sn;5D1sq137OxKP% zrhhG%?NY&UT?dA*Rt+NRZ!dIq@dp9VA+yKg4Rf|ybK1_OhTx|I<~yG}{{Wv#*3>6h ztY+KMRBplOPpuLQvm;OO71f5gZ=+>-nTeA;tAa3k`qi%#H}qw8O0q1mxjj1c_9M5_l#<;OuTx&mDE#|9vMP@; zgAfaFIPdf{?~8glivAr!DSYcYkYYlEpx!>tLbrln(dNhZPD79Tw|l-fI zwWAiX9%G_BOGQ-g#ErEUAV@L2kCb5@#Gn?(&STWt8} z>HdEzfudt4m;6ASf_j{qdj9~(EtS6anj1O(byn(8Z^Kv3ZK=t4xgTeVif5d*FgU9o z3P0L!HA$spV@_mokq2i$@Srn$9?g^({ldmJ48bu{~K+1J~~<=BCd22dPyX?E8LV zWRCSgw`}r%5AshGigvPD6G$s`l3&WU;qK>KoU#GvBx8 zPDAEguI5(Zq~yL@wE5N7Lc%r1z+Oi4{m?Y(w&fK zb=np4>AIF#S-*DCHhZZAaqWu5xYN#;e%oYXxGuRreL4^S09UO|XRIxhw(}R+=HVEy z-GY8xpU$MaQGIU5BYZqJI30h4dLQSCkkG5*En++UUN?tw+r*m{cnS_F8g{wTk`k-B zIT&CLKqHf%rBp~h(9*6j=zIDKbC&XyEPG^(k(}{^Rw-^aWOa!=#bjPe=eX!UtyN~3 zljX@?K^=3=T)Vt`m0vJzC^n1?j1GU9HC1GjZZq2h(LWsoD~n*^QR2>$>d@vSR8Rzu;dsPLvnWy@pkp60XInGWXpdjt1@=jm0c zR=7-noyu5@U}SXT`ufvjfmLw9k$~Xja(%wE#g&OF>Rm1wZW1aQtzPe!o#ffNMr3 zi*GBlouPC3(2+ z=CnTD9C{)r%+m)4h0ZWP&*e(?cKThcZFRYs(2$Bg={+-4WVczAvi!cB@(8KfY6ZKw zR%H2K7jZKqhLWo9bdas&70x93o%Lx35Xm=ZX_ABVL{%GUPzBc}k9*!s}PNZ8Zn z-?}}_dKAdcKOg?JU%fj#zcY3ebqAoXdfH8rB#K+79OQbQmAw_`+R#X)nQ(UiGlS_< z*T@U@$IXj!=jFg|dG*LOBV2i*S(&#f+E*WY)0(AWddsnyUn&7%j1IMSBbi!A_Or3d zh3I{~sb5eYpDS(M#_l*Y=99`KuHTq&aC674Bb6a!UJ9{ZM}B*L6f-s(EszcgA74r> zaPkl~)MNLz9-#E7)U)}XXZ*A~l%C_S>FrK2Y#VluatAdtOXbW97Ho`krRY5@R#}-H zyu`-N0a1;{l1NY9M#y8p=v&&Kb!@ULBXfcBmO0NoXkgZGDvjSaJc?IhAd$B&T>FAL zp7e%I!)rIo_lK@C(wyUV7j`7uk}>{sQ9=oq48M07Bop=eel!)#PZW|(7%aH$f^q!l zrAQh@8(D`P2XDu{6w0xWYQYB3aNHBkSi>q0yR-~_c|ZMXs~c<|b(S^&XBnyCY{J`_ zwvW0%>FZs3BbQ6+T(&HL?rqARhpi;6!ZklC?$1uuU2f!wc9Ded`iijvXK?wC95Ej; z^`p>FQPz>Q-@2*XRPmbWG%Y&PdnAS15=h|#Fgy%%&0;|6&GRz#2he>hMQoJ zoS*M(A+3E{>ME&HF>lav;ve`^5hMTCJ9(z3hsbbe8c&BC%y@I3A_DAI_oF zS*N!7nHQcrwOH2llclVT+ms^!2k{J_N~Z%Xir+8F8y$a@NmlAdVJ0pFi26m2Vj2p?q{qA`K7#Tf9MsGa4<2Y~*N%=_Q_3KY!qO>fn@7qq*lW&!l z+Q5JYKgjD*>Q`IrBFC1B$0brdv_)M-tF>6nGSb%&U$`AtXW*_jUqoIADIq*@E-Kvu)W>N#lpuJ`@mo?9ckK> z+arcJ!x)uztM|`RbM>UV2IFD50?l@?-Mo-{k>8)CK0C2(sriglGhmVF+N)j4vD&Eq zChRyOq(~nA{{YEsiC5*x;aGLg)83^=TZXpKy??1e6`Yp>7xOQff)YqOMsh`D*#S0| zHvQ=31fEpm>sCBRb@scZ+qGkWc~L1i8%Oxlv};kQTC&0knl{fIZd~)n)QTwv{wzHBhT0Og0)oeUU8KB{w*)7q-QR=R;>x;slYj^0Jus)gGe{KR7!^v7z=xswy0;rRw}f&d-O zNJq07V3S%iNE@8-k)AmfCX$V3ac^|-?q($IU^bKKkMXGv!>7W^tjmG{_09<-dikr``ISD@T0jp_qqQkmEUs43t_7yO1d6P%f-{bB)DzEYzp7fV zhCE!XK6ncSU>Ga1w_ZCRYRHkA8MmozyMbM&wQ8Gh_)07{I8QRz<@ouTdtiQbF3(}z z>`&q!4>pnvawt||=0tObaC?#X;<;xHm*7&L0Qqwg3QYP~xjz6=w zKf)B9znIVDE0>-*Cb{3cYd6pG^NwmqFi=oXQ_C?IAA>Plcs|(UFk4%lIb)GpF>DSu?m0b&(Ee2f?rl8VnZER&Dl7cky?g$&`!$nO z)-74GtiuGHouCuXx8qgyOYiMXS933!3~Tayzja5_vnQA>E)Bw5T+ViRC{71c>Bsr$ zS+QJ9+HK#@mXVa@xE)Pi@e;kUfg}CeefA)5NgY2bsv=jknUu(@D+~;QgUSB@>rnL$ zqz`c%+q01-21|B7;Ynv3E#pSz841Z`?dWN)i{*U4e683XYD+z^oT=a286PzP6I)dV z_Qv^%N$Xy#6treMt@3ulNdCJ zRlZQt{{RTcBmCxqj7@oWYBDx9u=$1tHlOlpG=DY}T#w&2Mh15fI6wVryW(hCO-YtQ zq&YheK%Kf(NTiP1&0GFkDJmHIj=zmAg!+*gyt#XqMq{_4Wsf5~ zl24{8t-;+Fm$!D~v~kxz=M{HTopenKD;4H@q2{x%J69M0Qz#oz7n1#teqhK{QPXhf z!|H1~=2L6FITQ&aV}M89>(BoHTBXxoH;PVwd%1QHae_M4+xtbow0pnfkmZ5LZZkk@ z)W^0}NuyP4#@#)7btb1VD@D8bLt%;Iclgu~n`GOwag*g7@H18sJmo5^Sy$!bKPU!( z9b>dl8E#QdbLozqYFY2sP@jMCZri}==~2xZ+b@=IzG8wn=sMC^Acf>WrME8t9!J!6 zrmh>2?PhYI24)}tLG-B=S~%C8ti1Z1f1gTi+X9MlnG}}Ksn6w3xGZh$*`z3b_D5P; zfY{=VjKP&vR00o9J5*?)xsP*hAno1L=|uLsFMd{LEzo52{Hk$#i(?-Fqc|k>TpkTD zwTOUd^%l6wt1ubo<=|tV)~xDQ`!w5m2H%;OfO!FV7(dJLsFnkD=6?}&7~?x?Z9r~` z4e-`9L|r`qbtC+H3ys$+tj5WqxK&vM$7=!D^gmHmG{sph zXN8miQv;msAol!?Hd17=UD9pZK^Z&%9T(FIAZOnX-KGn72eJlG9Te!8|<_zR8=tg~iDyxL7VOt&0 z?sY5Fxa@uDL|v0_mPX;8quZ@W(WV+LxEantz|9UB5pX_kNWkEq@@Pbevw3!x5$zws za85CU(yK_N9fOA(PBKQ^_sv+2CSdHvj?xIp`=`A_GI^N!kIZla^u|p+b^;j_BkrEO zXP?HE2b+@1yKXRjYD<*!C003Q$-zCp&T1(mWtBqYl^GzMXXr&CUr-}_ZSx%UAROcW z0M$;|4po1IkU`_$r}O$#Zgz)B4*^(w#dyYluS(EcBX@VTH?HodY2)f>D$S7C*v)r& z9C3wyoe#_YMr%V*yMsZCWFI}(@jD&DKD`I|?NRC)gmy9gp3IdT38f#zMstooTFoV6 z`FYHQ?EV9k}^#qp02*Q^(55f`HnEk4m%&e*Zkt5QRTBJELW}%82o9Z zG%B%0?YjrQ3C&)!xtiSkk{I^$kT}n9eX5*HT0{IrMtb(=ijv+%2t#MkpMOf3E3oCc z&{{|@QKZh@;{{vO+O+HyAZ7Dol%lrQ+BapZoYH4#t~UlJ%oxEu*5$6I&_c?0I_)Y) zt~*lYu;gf8*vY3|ZC6{Wk@hV7qviV3{Qqgffo(Sd+)zvmt5 z!MFJph8jQN`AK2;_o?+Hjcy|hskTYCH_BA={P@L4_(o;>*ck-%Be|$%i)%9OWn?4E zDmXoQ(z}$5Z)M&0fgCVDofbp4L7r~x{oofHdUN%n_UPRe%QEfbYaHNxY1bC+r*nCM zm}F#NF#6}xqfo6Zgt7(327d9u=|_;YAuWW&pLl)VdeBDr@tG83s~jGE4LalZh_UT# z2R+&cOZlgB*utJ+?THRAxR?IR3q z34+|$eVKdMQ??#@B) zRw0RPrD+*T{{S0EGr=9Z^`&rIjfYJA@0iTF?6^HWdRD?%#Vw;Mt{AQ|PXivc0lD7W zS9C16`A!@jwW%7LjjbPi?hJnYS2GVZQjXv3@UAd6^&s^>=e12`BS&}UDJa9Z?ewXw z*T_bZuopXu0y#MR>a23T<;zHl+gSa@9OjEIq14oSscyFU?IU@_IaWKVvfQL$n{L$y zZb3YOM6r1g$b{{0;o~H6nxvO2IWg`s4W|WrcH))06}c;2{iANy+*pyjBy-!fGUC|n z$;aSnS~ZFWS7NNBD&&3PP~1q%2wlNjB=bQ!+$HkjPrbCS2Pf}!<26;?t`6l385zz1 z>^s$)=KD&=^6uOKBc4dlIO$d0ys;v-)?DuSTcP&<0PE1hRLSjTl_TAT+}%j@{3(br zI<&tsWNZ(ND{?sRPgtaQ6`7l%BoD_N{sN%i=Q8fy8wJA-Fi$_@QE zh%?*uCmsE&wxtrh5Ug$tY0!Jrnp3sYDzGZVV1x4$^!g68-C79X4f9Fz;DA5Im9;CS z$mWS|1Y22~W*a~KdbO+V)2*DVF_P!yLPk8b@6V@dJU0X0>PoG*YM>w-VSwsAs+PB? zoljAbnZI_R#kEKPVAWVr)N06Nv}FzRgOUm3kHa{r{36@+P#H#M{odW=F&WNBp{gHh z+}lindFngoiqX&~l0A0acLTSOThxE`sw^*3uZiuVNv`1>U56vo|NkdNNt7ZwD>EZm z*}H6!aW)BO-`RVGP{NsKlk9OeM|N^&?|p}|E?GJAtk3WL{rv|wUhmiY`Fu>O;faXr16&tv%;I$YJ@&*1ilg#0kwA9XkNIkmL{GF_kk zvRzE8)<71Fo-EppaHvnn=9&AhClr=C7eD_dSjmnY%Vr9A>y<#!957;)%z%kO+P>K6 zpL9!?`!GsT62jNqP@+}}a_PI<=`;A1gdW2hGnwPf%Q>831T@@b+ESH?uPJyZgaKFy zZ5?>It;-(+*R7eYF==UqI|tVbd`yZEUg0k7n40;u)EfE++Ix28byVsr`9}}+PDa(e zg7MTYLP~G!sG>O?>B1oj<%gZFtbPsa}C3phl+h3m!c$Q6diR zN=jMKI$NUXQR9d)oeS+Gi6KHYL#fhP;LNt6O46FCsgZcUfOMYoJ^4SF2XMcecs9sq z;J8vIeRYD``G5tgUw@2?kj|glek;=4@T`6MvOc&FC^e)&y1F3ly-aHht4f$7{>6g>5^?#VhVx==>Yz;E<(gf5Pf@ltO8Uj^cNosV68N)T^{NLJ)^}8OS>J70BAhEp4wA(l@t>Q{L$iC-DmSbIruiQ% zQ^SksqQFg#)&y>W;rkH`b~n7H2o<7M^`-(4)69%p*G=Wsiy?@YRCEX?I?k(!0%FQAy2UC_>b0we5PRm;GLzw* zJ}G-ucFDSO&dIa_{vrR7tUBk}24uhb2ADPjFN|Pm%}_HZ#!hv=#|%V^^AP8gk5i!9 zp+ojga{onuL|{HtD^aWq2+I1^kW5M?wY4=pfy7LY1!1Ob75JY%Z<7M1=ZcRiaIKZi zfVfeT#XuJS%LCn7P&Gq?8VV*(hWWj({oVMBdXfactfxEB&v;z=jjq~Z$aglLXQacw ze~e_Ez;^<7Mj0PO1b5@BMdbeGFBIjC522hfGw_=yvi8lgj2j)Bvy1eS3j}{TA<3<` z$4^A}OXF}$ysl|CRn<ADY*A!xq;|bjj`Lz#fVMzPugC~`QstlQIuE%nr-zxsbjd&XSo!6wEj0HB3 zWSRdNm4HO7m5@7^6njHjbDI%Yzjvonz;k*#DzG84uB?(bV`&(-V&{b=O;^s3#4n9G z6c_VHW5tjGK1mi6YfC>WY5=|c@;K=g1O*8o19C$B#sfcxuuR|btKsxU(-8MHim)1f z?jIbSH}W~Y!Ogr0A;tPS0StUJ2K#S|XCaO!&BC>$XeXRF_cW(zuQXv$nY0nl8l_Q! zE)h@4=X&c-BM{nTJWR;_034;J@bbc>Bt~$i$-_~33)?PcM}l%^GiM7#v4IYU9MIJc z(hsihZR*tVjc>P2IRn^9^##*QgsW)q0(RU7kZwB5WxwyG>DZoW_{--OLayCs%io01 zAm3ozJp%{W4psj$9vIKnLlz&*HF&N z8<#h|ja~`+SAJ~XE8ZpvwyYO^fV$h_{b*O*r*7s!hNyroKv3W2NQzDPYx~q*u<&fA zE}5d>tI9Kj_u!R7dVbUt)4~37>Fc2ek{-kLgHz`!(bePjk)=D7gGo zYWC3j7mR;^VmhiW2g-`fq_huiZI@@onMRBB@qVu8od-E$#jPbvd)0EBy*GWptmde6>ybYD0&|J8Ew zzovz{+2>0hEgBfIvJnS{I4=$MfhLQTM(PfLr^|abuhnWfHJpY5dU*%E&`xL6%C#vj zOgE@+9IwxOLJt3{>fL)v8e{Pgdr)FQ$}b|a;WZ{FtaEbLB4KIaxuDSSc8j1S5Y4U` zHRBgwVd^opl9e_4yt!(0D7Q!HqV3al`(~lXA@k2&3U{1GLgP)<@6dO;84m2(qA!y1 zr@6P+D3bI^o+zaANnxtxQ`rI_CewC_zGZTUmt{PNJ~{S9tu(@nl}h4z-R?2+OZM6C z4~yM>hE(ZWDN}STh3pHxCnigUE71t0X&<6ug|PhD$@kqwkGS<9Lcq5^9-G&nP2~@I zS&(zpPW3|8Lxeof+j3WYLK}eN_;&;e6Q$3{X#d3v(D%1G*-3mYpF!SAcmUVQKj7i|4K1Y5D#mi4n}!nt7VCL70bnO!=x(hmnDY>Hiu&$BS!u z%kGlpzx(%%BeB)qo}xN%I!355X%}K`zRx0AHZMvp6VA4NFdJ2N zGRli2GZg1F^^KTcb10bzKMXZ3X)EJ!gusee@P~y%CU&k4E>r~RDVrrJ)4PJ>{wxcU z#nUfwuH6AaX+@CH+ofvk2vDb0M*q>Jv)faMDlt=t{PuB~8GWQ@9TfL4uT(z26t9@g zkt|1OP-B3|b?!YYe~)Dkp7fN->sr^-Qlee>^JnWY=>jGB6llU7_xEJ29mUvh3Ad61 zYVSbrie`Gyh7qo=!DA@6a^JWivNiN?ofMFe)r9pM#}wSfR$9K1mr!4@YQ;23j}!Y| z!SGynm_6oR+V}_0{zqbWiH$fW6EiUrC4+yz^E@Svrlv!uiUU?`KBQZlyRd|Jr{4cg z0T3EMgzpSDJYYSgHPbMGlyS34menn(UP6^b5B|H%Y@`!=(P&**60o$5SyR?6dshd^ zQ)`h5=`j@VofGTbG~?@BYps8@c3c@fq0iMq0^_45-3RYuvY$Y28N))|+RpXbsBIp~ zSgH<9D+_6bJ)pZ|vi3*(L|?ilc$_c*5_@{;PA#`JwO*5%bZG0r6GgTd4|`xY*afXm zvcK1=D#5!A#>-fn{6|6?qO_ZrW1u}uG88;4jA1+ne@c|LgDB_N9UecDse9i4lPcmR z1ove;F)(Pthcy*L_P1qhe5R?17(A8@^E6?hc%P!d_mD4Y@yoci56jWzmuE|DcO#0U zh3Md?{W8Itf!Bp27)LZ5f%Iu9rOtpyr^N5vz4e zXSlFEd`QOl-qng(>>z!6?iznbI7m5;R_6GdwDS;w&gaEW$i1{|2?-srsx*&P)2PMh zq&Yb#oq`iktF|j&+qYd0zvHG@Vxzu3eyhUN_lgf)B}!<%b3XN*8_3kkG__mm$Q-+w zW0QMAaO1EyPDHmqV-2bSpur-Suou3w%%S_C`K6j4e|9-7aqkx9wZ{b-iW|k#bWAVc z)dzEIc@ij~jr%X3zmF3sAST>lscku5`ZZdRq@SpVt4#E478=n z^>NLt-qY)}H_1;WhG0r3vlGq6l-tFjk91#*;?`*c^N1Ma-GDSK`%@<=qAEDFtDEy(XXjip-eac&U%U%^ zc_QH#FCJ=tu|N_bSJsvWP4{dF*!g*jBI2vp*|f(n_vbnc^PTm;{9?(UMc7A91O|Et z*knMsIm9CeY{z~#Qs|wWZ#{uVXQs7i>)>w|eZg&43)R<2=0druCSQ8&RmZ^H zyDLaR^T_e^H-!1T%ElwB>oh2xnFfbZuaHdLsV=}VHYhFpIJcvfqJ!>oHj}^U-N1`w z-A2|3Zq4E`}~q3k2(?E&qY$dftY+- z%`ZD{C*OuSAzc1|m&VLYq)5#>SscabD*m%F@&h&CbFJJ~dGCuowX?*y|MD6;E}OL3 znPhH*^EZYp!U|>7#p`!m|4}fG6?1tYo5bF%oaBc;ZMs^9TCArLBUpSRWbCWY9uBoP zwbr+)@@;qW;5Xb3&u4X`8RMrB|B(nC&N*3KT-X$$@}PWSQWh97n9@zW?BooU9rWbo z_qeEcsd*u4tm`w+Y7B#sn-Uqn?g;0n0$F>O;;qHS<4-T?0rD!B!(|*plRM8 zot8L1geDbQ7KSN?eR5!Sel*C+W$w97;sL~jN#A(Z_4}ErPqxW)+44oWt2Jw2!D?n& zQ}f&ZNZ2=Dvf162neB=}_P8~P26&)F$M}yVtHTV! z}aKSxwV|eg;H^DWp;HAI>(yiF> zN!^7#PLw-x^G3no`oop&@k7%hhGHl(ngVubEHI|5Lu<5RWFs75?HeJ2oE%Wsrzts?>S=xV4pVv9VR23Q}$Hj3EbbZ{M zOqt&{H8oq7ZNP8AFt}^cdMkwQG`(qEkInKER!2?Shxu=H3VW}2CAV_F`28-Q4yn=> z6g$N(eFZKuXN~EK*M@x2Eqwzlxd%kN^Tq#)Z%2==WJ_VBMzo?3+;*-9JvS+xs37G= zX=&MU$1H`#U2=-vT!=CZoQaJqgUsWNQ*`&JydZVO!;CFG92|r)tt9THK^hVS zjC3EqVf3EXLXBr6IWmVZ|Lq5X^@jTLW1@KF%kCaI^RA5qzNl8t`kZuYX|nz!q_qz>_okEm zt-|HdefhMPY2U|qMXvh)BbmM7jv2p}teEqKc=0N zcg)9|9c^8DHvf<0m=3ha78A#>-t+lJsmh@Nf2(J}>A69R>HUCwiQyH#Q}kXA!Le;| zf^_0LHNc{82N|Ls+^6%84*+(5t-Ck6#6^Jop#MnZr)R&R^i3f8cY}v3!?#ja@;bH# z6cRts?e~&mmow@AV5urk1GtM~m1A7gD_igkr@JZ{=O%e}j;yC~UTpW;7)HIW>F#=s zE`MBOMZS^4r322Ii*=OJljMva>q+@mZEAt>6F=}2yi?YsDTB@_a)2%`@}G8G0s5%;6wyyosl-&w1^=Vog4Suc^+ zHzjhS^P{n-i>RvY^034eT5{X0IYsQX;H>_~q}>&Y%kxQ(T39?J5#8%tCb>PAqH_px zbNBSfS@(2iNcXH1+*yZF0JXr&z6v5WIvAw(YlTe*lhcr$^~lqJ>&5|gTiMU~8HuWa zd5r@kiUpxM9(fDfSuLPp%OZ097FX+>z-x+Fal5o9f7MIDII?H5dGSV}(+-wZA_U%n zyE)W20JP1CllS4ucIxMHI*6z!{sM&=1MLa4 zg7@|B9@_@{{typJ=X%eJ!!8(aT2R?G8Ml5PsoxRN0Q{Xc3eq0AAA>S=2X$74kPgWW zf-~S>m%SVtmvUEIN8@7jxE*`Tl@~@7U4SfcZ`qTwk|lr`ty@axe49RioT1Q`#G9ha z*|^@H!<6xp!F0mXIm<#3z2)tZ??aTlM3V$_rkdbuu+8Y&;Gyi=ruYsw#WGWPj-i*t zqRz4(?-<#^w}oa}Bu0u=V(YkklgB*kz>;$$^6cWAG7mjbT?5**ebT(TBs|SDqd;AX zJ!VLE(L`coZ!yYkdu|ez9FiH{w(CW9#DLDWu7k#nc1ET*OgJ7W+wr47Z7qPq_1MV# zw%+Z%2vaFr#MAV3g#PO0oil5YD)4k3fzSl*aVp4h3e`p)OPgKSE4Z-2;zU z{a6RHp`NjreHgRi^}Bb0ipIBoB3n`Pe}2X#hHRmD?lFRl{d~6a&62#xQ_Ws8{l}xN1 zjS>uF?{s*vl}}oOdV-FF$fwXV#5_Cqm7f$#3RXJ&Su+pbtVg9g43gz`c~f@%M(V$L zXapY|tn!Th;`S6Y_sAbTsfBIsg2S+-_SQ5@?{hxL@tVIC#Wx>PHo~eH-EX82g1}I| zclCcK8g5ib*(S8E!T%Mh+T;g$mM(V_6TLA27Si$Lql^tz1vVvh4OQ)=`P8A+!Kl$C zL?<{J%z(}N=oJ^jmlKrhX}q6ucte`9!*{o=?~Xkbvrp>@v@sZ_-Pd9n%QUgZql)kR zxrva7e{z*;M<6QnVnREc5Fa%O{1g^;WZ_N!k&I1NFM5Po2|HfExWcjAjsU9?Pif1JPtE1BE|v$CVNj0)7ctGWKNYlN}|xcZO7G_R6UD zd2#_)d~5dfej>^DvSPn34-V@}Ng?l9(Is!Rr$J26D;;^ct=HZcDsdL*Nm18Nh^?OP z>&Dj{j)L_U>73QSqZO{+zfM;awd?2`cak8+x+{WE*3(%XHS=E+ydC`asP|NT{iIGS zF0M!1v(NC1WJpJsH=9nhe3jyJRMdfFvkiAG?2~A-`L`akwkdKv&r@HEoAtC5Zg4!z z#dz>w;Zwy{ZMr*HkpEf+F*$fLqLqPTZ`QSrn6kH&5a}5*aa25QW-;EBR4sN9SH18w zK4R}zt$dowD>W$STLV-!XP1oWq;htD^RHeF*jkSe`iCQL#%gug3}Wgl5?@`KGQD=r zidjSyf}R@XW`amgnS0i+!A4F${bl*}hi@1vct z^BF4}KUzNnC}kIys&E`$PJs{ce8{!;6nY3lue3{TjTm+D4a>jZsB{H3M=x0lNA2N_r|hU&e%ys&;!~5&W(dSu3)2GQxjfes zXdA5fmX;V?xu7HBNO%>LxB-k$L4mmo3QO`ai}{aSxZ3)M=~WbheK?r!(PA5I9cX|s zP^%w>ri+rJ?;kQi!KVaZK!t{Dv7n_a?aTTiFc_gHI4@pDUA ziTiLG6eO7%;#=h0rBB631ONPd%`Ug{R|}{*4-6&i>Ud>sW<)f<3-T#l!aeUBl2C{_ zAf5YHq8!U@L$ka?p)`pI_p}~*S?REW4`A5Fm}z+qZ1mq1l6?kDopMglna*+FJqBGs ze{7qwGu$P<)^mOO?q3NAv1vdv5>c6(m(hP*_MRW_X3szobrX+zH(IsCDynOezG-FI z0e3r`tW;?m7N~5BR{HfXgx7~(3juxa5>y!_6M4Jmtu9%<84~$($bGbM{}PuqnV=#( zz%TfFg9;uzbI*!C?_Xn>2w&U_?eSykV#m2*SCXYq6vx+H#hMAT+ik2t5hO(yqROha zuoF}ek z^#~6xO?I5oSsWq(xg7A64u8p#3GoI-FZM;#+u+p3FRk_Ns$Ow`Q?V?ST7GYsNr+iy z`gEh(jVe2mR-=bm?v`;JYq}GjS(o8_Ja$|IJ(AD8`B#*%9>S;MX==#tDU9I=#~zeb ztM;3_%ZU;ICBDe*d2+ISUnc0b;v&d1|Ic8lz(oQBOAgqnaQUx-@c%rc=DBnox{5l| z$ubwd73=nRHz~bKxi>c-v}XcXb8~*W$F{!YPX&H*i2Q#f27Pi#;cM=r!Y!xUZ#&v( zd)*fSRPy5d`lZ>txR}_InZk}%TS#5Sa6#=FY?9i!=3k!4K|*1k)3@hw$QB<4vIzA@ zM0p@C68iN91(31@>kf{xqWKO^Wd-b!k2|F&)efH-S;t3sBz*f+WHK+3;MFG8Ge&&* z)I$n43~FVL2BNK;8~K$gZy7{e$ z-R{-m|8+1@#U0=)>K1h^PDfOeLJw4D9oHpoKva^Y4>zTSx#}=TYH?o3^+QzB+~xU< zOxk#|l&!gH+#Y2NWp7SCU}dAvibQwA;GCrCvbH5})HXNf?zQ;_z<%LTO+3T*C5A5A zlY0voiq^hU=aZRP zit_uGMRvSaVfoyMg29&w48KbZ=J+SN_;@WEY=>^+?Dm|WZICq}wEI{7&M`fla~n56 zt~nYEC+2gt5Mu}>MU;OPzLdjOqMcPCj>|7u+c@2o*o@!3%A0!)c^%2KVS7kI@lJPW zYOyehtb*uj<2WENEdQ_kX2p%YKX|5uyp<~;7};Em4QB5+y>46cQd(%Lz-Vy+Hb=|I z_{ja|8Zk^-w%Lz=)8-{ZZ^&i0+F~Dh zQ(LOa{j^_Kd(vS3f&4Jf