From bab6d6342ee35a11af37c4e99a7d3cd0bce4b9ae Mon Sep 17 00:00:00 2001 From: AimanHaidar Date: Fri, 5 Dec 2025 14:38:52 +0300 Subject: [PATCH 1/2] update tutorials for polyline pilz planner edit description clang-format corrections --- .../pilz_industrial_motion_planner.rst | 60 ++++++++++++-- .../src/pilz_move_group.cpp | 68 ++++++++++++++++ .../src/pilz_sequence.cpp | 77 +++++++++++++++--- .../trajectory_comparison.jpeg | Bin 54522 -> 0 bytes .../trajectory_comparison.png | Bin 0 -> 79668 bytes 5 files changed, 188 insertions(+), 17 deletions(-) delete mode 100644 doc/how_to_guides/pilz_industrial_motion_planner/trajectory_comparison.jpeg create mode 100644 doc/how_to_guides/pilz_industrial_motion_planner/trajectory_comparison.png diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst index 54f4ee6cc3..25a4f8878c 100644 --- a/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst +++ b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst @@ -39,7 +39,7 @@ strictest combination of all limits as a common limit for all joints. Cartesian Limits ---------------- -For Cartesian trajectory generation (LIN/CIRC), the planner needs +For Cartesian trajectory generation (LIN/CIRC/POLYLINE), the planner needs information about the maximum speed in 3D Cartesian space. Namely, translational/rotational velocity/acceleration/deceleration need to be set in the node parameters like this: @@ -60,6 +60,9 @@ rotational trapezoidal shapes. The rotational acceleration is calculated as ``max_trans_acc / max_trans_vel * max_rot_vel`` (and for deceleration accordingly). +You can set different max_trans_vel using ``MotionPlanRequest`` by setting +the field ``max_cartesian_speed`` and the field ``cartesian_speed_limited_link``. + Planning Interface ------------------ @@ -70,7 +73,7 @@ are explained below. For a general introduction on how to fill a ``MotionPlanRequest``, see :ref:`move_group_interface-planning-to-pose-goal`. -You can specify ``"PTP"``, ``"LIN"`` or ``"CIRC"`` as the ``planner_id`` of the ``MotionPlanRequest``. +You can specify ``"PTP"``, ``"LIN"``, ``"CIRC"`` or ``"POLYLINE"`` as the ``planner_id`` of the ``MotionPlanRequest``. The PTP motion command ---------------------- @@ -144,6 +147,7 @@ LIN Input Parameters in ``moveit_msgs::MotionPlanRequest`` translational/rotational velocity - ``max_acceleration_scaling_factor``: scaling factor of maximal Cartesian translational/rotational acceleration/deceleration +- ``max_cartesian_speed``: maximal Cartesian speed for this motion (replaces the max_trans_vel parameter) - ``start_state/joint_state/(name, position and velocity``: joint name/position of the start state. - ``goal_constraints`` (goal can be given in joint space or Cartesian @@ -215,6 +219,7 @@ CIRC Input Parameters in ``moveit_msgs::MotionPlanRequest`` translational/rotational velocity - ``max_acceleration_scaling_factor``: scaling factor of maximal Cartesian translational/rotational acceleration/deceleration +- ``max_cartesian_speed``: maximal Cartesian speed for this motion (replaces the max_trans_vel parameter) - ``start_state/joint_state/(name, position and velocity``: joint name/position of the start state. - ``goal_constraints`` (goal can be given in joint space or Cartesian @@ -260,6 +265,45 @@ CIRC Planning Result in ``moveit_msg::MotionPlanResponse`` - ``group_name``: the name of the planning group - ``error_code/val``: error code of the motion planning +The POLYLINE motion command +---------------------- + +This planner generates a continuous Cartesian trajectory passing through a sequence of waypoints. +The generated path is a combination of linear segments connected by +circular arcs to smooth the transitions between consecutive lines. A smoothness level scaling factor is used to +determine smoothness by scaling the max possible rounding radius. +The planner automatically filters waypoints that are positioned too closely; +however, the user must ensure the angle between consecutive segments is +sufficiently large to avoid violating minimum rounding constraints. +The planner uses Cartesian limits to generate a trapezoidal +velocity profile in Cartesian space. This planner only accepts a +start state with zero velocity. The planning result is a joint trajectory. The user needs to adapt +the Cartesian velocity/acceleration scaling factor if the motion plan fails due to violation of cartesian limits. +the planner will fail if three or more consecutive waypoints are collinear. + +POLYLINE Input Parameters in ``moveit_msgs::MotionPlanRequest`` +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +- ``planner_id``: ``"POLYLINE"`` +- ``group_name``: the name of the planning group +- ``max_velocity_scaling_factor``: scaling factor of maximal Cartesian + translational/rotational velocity +- ``max_acceleration_scaling_factor``: scaling factor of maximal + Cartesian translational/rotational acceleration/deceleration +- ``max_cartesian_speed``: maximal Cartesian speed for this motion (replaces the max_trans_vel parameter) +- ``start_state/joint_state/(name, position and velocity``: joint + name/position of the start state. +- ``path_constraints``: a list of position constraints to be followed in + Cartesian space. Each waypoint is defined as a ``moveit_msgs::msg::PositionConstraint``. + - ``path_constraints/position_constraints/constraint_region/primitive_poses/point``: + pose of the point +- ``goal_constraints`` (the last goal point) + - ``goal_constraints/position_constraints/header/frame_id``: + frame this data is associated with + - ``goal_constraints/position_constraints/link_name``: target + link name +- ``smoothness_level``: scaling factor for the maximum possible rounding radius + Examples -------- @@ -425,7 +469,7 @@ is used instead: The :codedir:`pilz_sequence.cpp file ` -creates two target poses that will be reached sequentially. +creates a sequence of three commands. :: @@ -435,6 +479,8 @@ creates two target poses that will be reached sequentially. // Set pose blend radius item1.blend_radius = 0.1; + // Set max_cartesian_speed (overwrite the max_trans_vel) + item1.req.max_cartesian_speed = 0.5; // MotionSequenceItem configuration item1.req.group_name = PLANNING_GROUP; @@ -461,7 +507,7 @@ creates two target poses that will be reached sequentially. msg.pose.orientation.w = 0.0; return msg; } (); - item1.req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints("panda_link8", target_pose_item1)); + item1.req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints("panda_hand", target_pose_item1)); The service client needs to be initialized: @@ -485,6 +531,7 @@ Then, the request is created: auto service_request = std::make_shared(); service_request->request.items.push_back(item1); service_request->request.items.push_back(item2); + service_request->request.items.push_back(item3); Once the service call is completed, the method ``future.wait_for(timeout_duration)`` blocks until a specified ``timeout_duration`` has elapsed or the result becomes available, whichever comes @@ -546,9 +593,9 @@ The future response is read with the ``future.get()`` method. return 0; } -In this case, the planned trajectory is drawn. Here is a comparison of a blend radius of 0 and 0.1 for the first and second trajectory, respectively. +In this case, the planned trajectory is drawn. Here is a comparison of a blend radius of 0, 0.1, 0.05 for the first, second, and third trajectory (line, line, ellipse), respectively. -.. figure:: trajectory_comparison.jpeg +.. figure:: trajectory_comparison.png :alt: trajectory comparison Action interface @@ -588,6 +635,7 @@ Then, the request is created: moveit_msgs::msg::MotionSequenceRequest sequence_request; sequence_request.items.push_back(item1); sequence_request.items.push_back(item2); + sequence_request.items.push_back(item3); The goal and planning options are configured. A goal response callback and result callback can be included as well. diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp index 6e58f9abcc..93e1218f00 100644 --- a/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp +++ b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp @@ -170,6 +170,74 @@ int main(int argc, char* argv[]) plan_and_execute("[CIRC] Turn"); } + { + auto const goal_pose = [] { + geometry_msgs::msg::PoseStamped msg; + msg.header.frame_id = "world"; + msg.pose.orientation.x = 1.0; + msg.pose.orientation.y = 0.0; + msg.pose.orientation.z = 0.0; + msg.pose.orientation.w = 0.0; + msg.pose.position.x = 0.3; + msg.pose.position.y = 0.0; + msg.pose.position.z = 0.6; + return msg; + }(); + // Move back home using the PTP planner. + move_group_interface.setPlannerId("PTP"); + move_group_interface.setPoseTarget(goal_pose, "panda_hand"); + plan_and_execute("[PTP] Return"); + } + // Clear Marker to show polyline path clearly + moveit_visual_tools.deleteAllMarkers(); + moveit_visual_tools.trigger(); + { + // Move in a heart-shaped Cartesian path using the POLYLINE. + move_group_interface.setPlannerId("POLYLINE"); + // To prevent failure due to exceeding cartesian limits. + move_group_interface.setMaxVelocityScalingFactor(0.05); + move_group_interface.setMaxAccelerationScalingFactor(0.05); + // Define Heart Shape Parametric Equation to collect waypoints + auto heart_eq = [](double t) -> Eigen::Vector3d { + Eigen::Vector3d p; + p.x() = 0.3 + 0.0068 * (17 + 13 * std::cos(t) - 5 * std::cos(2 * t) - 2 * std::cos(3 * t) - cos(4 * t)); + p.y() = 0.0068 * (16.0 * std::pow(std::sin(t), 3)); + p.z() = 0.6; + return p; + }; + + geometry_msgs::msg::PoseStamped msg; + msg.header.frame_id = "world"; + moveit_msgs::msg::Constraints path_constraints; + const int num_points = 40; + for (int i = 0; i <= num_points; ++i) + { + // Get waypoint from parametric equation of heart shape + double t = M_PI + 2.0 * i * M_PI / float(num_points); + Eigen::Vector3d p = heart_eq(t); + msg.pose.position.x = p.x(); + msg.pose.position.y = p.y(); + msg.pose.position.z = p.z(); + msg.pose.orientation.x = 1.0; + msg.pose.orientation.y = 0.0; + msg.pose.orientation.z = 0.0; + msg.pose.orientation.w = 0.0; + // Add waypoint as position constraint + moveit_msgs::msg::PositionConstraint pos_constraint; + pos_constraint.header.frame_id = "world"; + pos_constraint.link_name = "panda_hand"; + pos_constraint.constraint_region.primitive_poses.resize(1); + pos_constraint.constraint_region.primitive_poses[0] = msg.pose; + pos_constraint.weight = 1.0; + path_constraints.position_constraints.push_back(pos_constraint); + } + // Set all position constraints as path constraints + move_group_interface.setPathConstraints(path_constraints); + // Set the last pose as goal + move_group_interface.setPoseTarget(msg, "panda_hand"); + plan_and_execute("[POLYLINE] Heart"); + } + { // Move back home using the PTP planner. move_group_interface.setPlannerId("PTP"); diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_sequence.cpp b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_sequence.cpp index 45f210b80d..fbce8e699e 100644 --- a/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_sequence.cpp +++ b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_sequence.cpp @@ -71,7 +71,9 @@ int main(int argc, char** argv) moveit_msgs::msg::MotionSequenceItem item1; // Set pose blend radius - item1.blend_radius = 0.1; + item1.blend_radius = 0.05; + // Set max_cartesian_speed (overwrite the max_trans_vel) + item1.req.max_cartesian_speed = 0.5; // MotionSequenceItem configuration item1.req.group_name = PLANNING_GROUP; @@ -92,22 +94,22 @@ int main(int argc, char** argv) msg.pose.position.x = 0.3; msg.pose.position.y = -0.2; msg.pose.position.z = 0.6; - msg.pose.orientation.x = 1.0; - msg.pose.orientation.y = 0.0; + msg.pose.orientation.x = 0.924; + msg.pose.orientation.y = -0.380; msg.pose.orientation.z = 0.0; msg.pose.orientation.w = 0.0; return msg; }(); - item1.req.goal_constraints.push_back( - kinematic_constraints::constructGoalConstraints("panda_link8", target_pose_item1)); + item1.req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints("panda_hand", target_pose_item1)); // ----- Motion Sequence Item 2 // Create a MotionSequenceItem moveit_msgs::msg::MotionSequenceItem item2; // Set pose blend radius - // For the last pose, it must be 0! - item2.blend_radius = 0.0; + item2.blend_radius = 0.05; + // set max_cartesian_speed (overwrite the max_trans_vel) + item2.req.max_cartesian_speed = 1.2; // MotionSequenceItem configuration item2.req.group_name = PLANNING_GROUP; @@ -123,14 +125,65 @@ int main(int argc, char** argv) msg.pose.position.x = 0.3; msg.pose.position.y = -0.2; msg.pose.position.z = 0.8; - msg.pose.orientation.x = 1.0; - msg.pose.orientation.y = 0.0; + msg.pose.orientation.x = 0.924; + msg.pose.orientation.y = -0.380; msg.pose.orientation.z = 0.0; msg.pose.orientation.w = 0.0; return msg; }(); - item2.req.goal_constraints.push_back( - kinematic_constraints::constructGoalConstraints("panda_link8", target_pose_item2)); + item2.req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints("panda_hand", target_pose_item2)); + + // -------- Motion Sequence Items 3 + moveit_msgs::msg::MotionSequenceItem item3; + + // MotionSequenceItem configuration + item3.req.group_name = PLANNING_GROUP; + item3.req.planner_id = "POLYLINE"; + item3.req.allowed_planning_time = 5.0; + item3.req.max_velocity_scaling_factor = 0.1; + item3.req.max_acceleration_scaling_factor = 0.1; + + // For the item, it must be 0! + item3.blend_radius = 0.0; + // Set max_cartesian_speed (overwrite the max_trans_vel) + item3.req.max_cartesian_speed = 0.1; + + // Extract waypoints along an ellipse + auto ellipse = [](double t) -> Eigen::Vector3d { + Eigen::Vector3d p; + p.x() = 0.3; + p.y() = -0.2 + 0.2 * std::sin(t); + p.z() = 0.6 + 0.2 * std::cos(t); + return p; + }; + + geometry_msgs::msg::PoseStamped msg; + msg.header.frame_id = "world"; + moveit_msgs::msg::Constraints path_constraints; + const int num_points = 20; + for (int i = 0; i <= num_points; ++i) + { + // Get waypoint from parametric equation of ellipse + double t = i * (M_PI / 2.0) / float(num_points); + Eigen::Vector3d p = ellipse(t); + msg.pose.position.x = p.x(); + msg.pose.position.y = p.y(); + msg.pose.position.z = p.z(); + msg.pose.orientation.x = std::cos(M_PI / 8.0 - t / 4.0); + msg.pose.orientation.y = -std::sin(M_PI / 8.0 - t / 4.0); + msg.pose.orientation.z = 0.0; + msg.pose.orientation.w = 0.0; + // Add waypoint as position constraint + moveit_msgs::msg::PositionConstraint pos_constraint; + pos_constraint.header.frame_id = "world"; + pos_constraint.link_name = "panda_hand"; + pos_constraint.constraint_region.primitive_poses.resize(1); + pos_constraint.constraint_region.primitive_poses[0] = msg.pose; + pos_constraint.weight = 1.0; + item3.req.path_constraints.position_constraints.push_back(pos_constraint); + } + item3.req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints("panda_hand", msg)); + item3.req.smoothness_level = 0.3; // [ --------------------------------------------------------------- ] // [ ------------------ MoveGroupSequence Service ------------------ ] @@ -151,6 +204,7 @@ int main(int argc, char** argv) auto service_request = std::make_shared(); service_request->request.items.push_back(item1); service_request->request.items.push_back(item2); + service_request->request.items.push_back(item3); // Call the service and process the result auto service_future = service_client->async_send_request(service_request); @@ -223,6 +277,7 @@ int main(int argc, char** argv) moveit_msgs::msg::MotionSequenceRequest sequence_request; sequence_request.items.push_back(item1); sequence_request.items.push_back(item2); + sequence_request.items.push_back(item3); // Create action goal auto goal_msg = MoveGroupSequence::Goal(); diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/trajectory_comparison.jpeg b/doc/how_to_guides/pilz_industrial_motion_planner/trajectory_comparison.jpeg deleted file mode 100644 index b0821bc8955667e1a36efaf06234ed61ffe69a0e..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 54522 zcmeFYbx6(GPebL{ceKP?WzZ5uq*=ZeLZvG-H{tL!8`%nD-A8hoWSnwb0>SXWqQbzF~ z?5L_N_JY5?;P+<#1snYrY;5oNPx*+KGJ-bN&i~x&ANogP3=>;5m6s#x%T5LW0h9q! zfY1Lt|I7Ic*<}L&yjK7KLd?I?jFJI>`XB&+c;R1Zv{?WE_ICiFZtP!a|9U6(hK`2+ zQ61t7hc`6^0L}{l08A|a0B;-sKm-0q-V6ITvQfQck-f-e_p+G*tN|tfDu4{Y7GMlu zc|q&|Rsb7-`_Cdk41fUt5BRmwa0s035=L*vP0agz^d#1qluSkAR4a zg!~reH5)1(zNnHR0kxWgf86iMSM16^D?27m328p78pYrCqvaG=iLaV^ z^Nx#0!#Jn9lbBmVQXS;v>=O7rp^J`J>f7|jCcTMiP|eHzNM9s*k>b?=71sG65mGlA%Af!|x6h{LcYD*H4LP-f<{b zPSDaBoyBHX{aFBDAiPMAi+~Fd0ZitKe-al*{J-q~zJveY+JTOK)pALE$DwGIPAoUg zuj|-DS<+GbGH_Jn28oC9TZ|Te7JI@rwV*@iHuJ!3g(|Z8YC)s05{6ETy@PF58365Z zlXFiQ5$(coCA8F{_f90HM~teYa`aa?J2FY;YwqI!K~c|GY)8NC2G*2P5II5A@?CGH~XtIQyQ6Gm_^qJpBwO(x>U-l4|?1s z@IYct+W{8`7Z>jT03$-wmvuNe(#d-`4CFf3n&;M8h;k^3=90YIdr$ou_03!J_+xr0 z+(I%piZQmPI}K|Ndg~jEaMrDRHgQtMH-Z>+V^(QM?X+_Nuzg#U$e_kM?BTbg#9jH_ z$#O(&L?M6`hlbfLiYp&SXyLbc))X(3Uo{Hyl%#>WzP%j&088F`B8u6RMNLDe*+_~A z?HsI2N#H2(tHcQzeK=dL1@AOWvn#BCWv`z3+QML}$T4MA{|ig!R7i+lNC@ix0S4J< zkZ*F$S~wQxRaXZ&ECC79M@v_&$>w7}&GuPE<2y{Jt5PzP@v!tn8ER&bbF3=fWny#h zCh|B{KpOk1?cpA`$7n|4q|zMtA18DpRHwu~i?epTIy3P(8p^;5hE6^eNZ<{^OeeMl zp$gGmp^a{q`orAm6UTKt!I^LTv$WUC+SCI-L7oJ#mS(KoN7iki^{yADH1xo+`nL16 zcA>0vQL0B++Tg3kwN)=o;6tuClsvmm%#45efQ%lq1%bYIL`e zK@)ZSAHX=xzCLCT3RWn6R)CLHR+)q(V#kupY1YYt!YdU8t-^xax%R`d906{Nw6;2Y$9?FyZbmOK*%HOn@o_8QaWe(4{F{&76b4l`n#G9K2YTt_lbXXd z(4J|y(u@>xFd3=wag#AvHXbUgFkuG2zM#UGCVeqM>SrVzTNdytAE63y2ds@@+6%8F zBxGqrdX24;#B5o_%Jd}4?-=8Iw54qF>EYS8H%Dhro&}ou9L((Wfv!A0^%W>NrH^}% z`*!-96E_WGXxse2h;&Yo=WvUmSK@ zx^}F$lnmMJ9iC_eOB5je49DWuDrYf#`29W7?I2JYMBh;!upysN@OJn9kbSEq4wBAj zNsKubLea-sgEdKE(|a(|-HM4>-nqHfyc)-lf?6*$`L@ZXEP&{0AKGrO_sh^p&RA;$ z2HjJMn~tzI2O+l<3g&07tu7w2Pjyke`;~{+Z|oIOl7=d|nclo+fDAP^U&i8bgJ7H@)l!7Ghv9zw8{OWw&vod>a5Z0 zP)Z~Dvz_oaJ_wTjS@o~$ZR>tUS-9*SzSDAhrYw0>ap-=IUg_tQ6*%Xb_vZDM*C9^8 zeiyt~P{Pg$EDUuWX}xDQTc8_(onxAZUKtf9Z&k(~+d?R~sdwi*-9E}xr@xKj2|()S zt|wi6NXR%3?fMSUnL>u)zSbYMyQZ4Wl=z{%Ekq9e?@b;#kDt7&^Vt|V17oMNHaU|@ zCa4D#14CYKM-dw)a0%2n)tr%+EqH`em2_J zxs6gpvczIq;JI7Jp1U6Fq@{T%etO~U-xW21IzjOC#_e}vXR7AvX0C!l*Jb4rm~jpH zN3JT}#X3UIFBmN`?)2NGHZgL^m0|a(!6#h^cS*~;6(8@Sk4H2qslnf6@r-`a_1|a) zGFFm+PxxvQV29Tw;bzm<0aO5pmCXgye!}Ugc9$)^g4wZX$^4JCrGdGY?EyY0K?j94 z3Wo-Q)msQcP&gSvn@n%_DG8FX5hb$AtdYrSGc4{Py%BXcRglN|ipW}Fa#d!+Lm)_r zlk+vwz|+B6L7r7`De~5t=(dDeM_YZPdG}8vKK`smbxAD(oweFBHw)iL1W_wd7Vfjs zsYWRO2v=Mta>C-4XDTp--OC0+N{aKG|K{+;+~J4qz$i-G_^DUJ!M7hnD{hlmNO&Ln z1;;ymFd~NczBi;=5_^BBuFvVRhknIYtj^d0mY*x+>2sz9xV-b52=kJ{>OPylTFI!Z zJ#>JOz+rQb!y!Wv4{T)s;0Md?2LRL4c zyY?hp9@w*A(9S~k`AJs$I<<;qBoi_%8bY%02}UG6GEWLJ^fdR{STWhBaLC1#dJB>~ zZuQi%OjxlWjSp0p1iBJ7MUzG!zvsgD@b%c{68!w{bo9UU_FB4#@5)eohoJL;Xf0Wo zU@565QZ(lBK{?4yV%S1GCA3?=I+tGg8WFi#VJ*RZs42{WOm4lamA6BQ4 zmy>E@f63bluO>6*F)gZQE%b+&lIfDgO(iz+7oj_0SxG}kq0`qcg{|uD2)IM;XOPFE zd=qkWT$L{L%#o>n(n50wZWc`bz_LA^jHH};Jht575s2gZ(%r2`wNtlqoA1*cgd9Dx9zPW^o#n-3kjb^*Cm;$1z|34w#OEr)qzGY+Q1?sG z+6R#W`V^aE!1#@>8B?1)qS44K^lq@5RM3ypPcmS^)w^>9f?>cGyxcX6qsys;T%pzS z#V9h7OaR}85o;GKk4=&U<)>o64dwZx#${NQIC384`2WuHE(H|#9HD2=FEtL%KXuSXYZ z_YkP5&~B&=lN^v?rQYa{36zfP={S;53jJ(xhL$8USV^ftAHpejYnFUB5!;TdOoFB29AU=FeOAqwkN(uy?NDD=Q4Emv*6C-+1jd?s#ABxXrO|K3j_K{CMVz&UcjFWi*8k+!HezN}9$ z+|s*&;}A6N{++p&tv>(@M%6+g4{T@uBed3*1`S%VBzfAy|P}Rd~>8esIQQMO2 zTy*~BLaJgdSN=z}+K6^0CkQ6ZTv@Rndb+cnQ7KZCtL||imRX9TLCm}rGW31-bUdKm zjW2g~u5O5bY9&R=(0Q9AjBnQvvbdt zz2s%O{0HF5!hL1B;T!HM4w)j%9Hjdcz?wljeQe!)*OEEcu+2 zi1eW2ccoDJ;O%yN#`);S?^EkaDx5~a=3nJNsGe{%?hEz7JJ&6+I4hYy01tyz$!6_L zt6rPN@}{Ot=EIerB0Uz@f;_i(_gsPp3YlP>Q%ai$fuGJU|E5RA=ATawRJzcVAjah9 zB=vxwHQ1=qF=>V?(;T;d6&ZCM09C*~5GqcXNv3&M(BFc{@)73I1<8<5x@kx72GtX9LaM2@Wsdd(ZfnjzWx7#DKvqiP)&ZEidlZ+H*W!+Bzxd#Qs3;uT=(ez{)NE0%r7skhqtd>wC= z1MnR;l>1c|M%1!^e{OA;+v`_Tew*M3Glo)Z4nz050=(Gf^(dRYR3#B!?LUB_CO^Ox zP>xB;ep_`aa?w4rRQy3u@IyUlb#$flP(s&Ec$I}h4}-BlvEJ3paT|@Lc;fG_jexd~ zeWROBa@3m{i1%C+acob71!2tfnLP zd<&+Cm|9qT-0}`*Hn{ggF)hL0%9_A8E{ya>jE}e1zySz;qF7ecHeo69c(Zq&HG z_YffTf5FK9NI)Nky-dH0Vn0qem1%onC!84_g_MKk9&6$?Daw^H{*LabMMe+-5%Qzx zeHeySYR`IdT~n!#U+tp#PdhQL#;)=UaQFz#nKJKHO^_eAUq=J8e@p*$90^-(|9AH+ z{)JX{=0z*-;=%gSy4Q(RhN+?p#;1ZxK@$14jRc@Iq`iY7QW@) ze*m+hMW}Uij>?0704ZZno=@8sAK!W9Au43Jw6;> zibWq4)F!1i`)Ru*wxT~fXXL1tuBbQ%cM6xYSBjs$89)l^Jtlg#ZBg%fOs)93A9+L) zOO_)ft|X~>C^Iog>S42{vlwH&Sx7=DMc{MZIn?{GmyE z5nXRBioT>g9>(v`WaZD6EAGi==|#P`|FC$p>1O5>QUW%w^@6y$d(<}lpb+s^!n~hw zmJIp3DM%hSaZ$_KWA#INHj|AS=1?brieGbMw^j4_2Vh@wgJ~uZGTE13%@Lh$8#Va5 zmXn*rcJamGnvD6KtI`djo-JVct*Pf`W(rqcB zimJ^S33jrW5;=guHo}}Gpdk%yKXZeU{{%r|N@+HLqFUqUt|D=A^(&f?`1F>dG2ffE2|}s@~cwxOkxDO3fkwjK&iS- z1mhlyZ~R)vcA1~m+2DtaKrCv%M@c0+9FJ)yEnt@KA~&`)L%xCBaA(KM{s120s#?k? zOrXy`aw0W>%D6W5PlH-|e*hcRe*iBBca(Qb;Pxqbfx8=T6Xe`%@PZ3z(Bv+e6w(lw zDXYuWnNepT?Tlk?gX|%rWC{H>6DNIGEi%sP5K>?39z8kdS0b-c!YK`w9Q{vIjRy<% zp4)cgs)`+(cW~Zm46I!nSSaU;U*X9R{1GV-Ndp=b@n@WQt?nA&yty;zi8x&;i{$&5 zK$7o*)`wlPzEev7-D#Sx=Z(ueXB}vCM}73Uo_Uk&4Z|<&D0c^qMoo%+;@+Ctys=eK zKR~OcSyi9W`Yv?mMd2ne+F!Rn@{6i*beG1LHIb1v?&wfPcoS+AP`jTCz3(;cmE-GP zrO{q-T-r3E0=n#6(>)5{V>1n$2c9kQ7a-&C;3Swyo_4YrV>s{-L7=W-TTW`(WAY3k z9Z8u7e*p22hqjY}dAL0;3Rumzxl(Up#eSxnO)No{LdeI_hWT574c%75Q&k0LhUMGrGMm!u+$5-iS6~zN1^vg=66mYfS?<7DHSR!C-yD zgo*;@=MCq9!D{|MSzvP5yu-G{Bv{-tH( zh!E~$)wPtO(&E!QUFeXptAooQI8xej)>^YWs#n_Gt!J2(XGJc0p%BT^|Bb!+eTfL z33U;y7*Rf!0(!A?Y`bK+5p29&B{ip}BYWzb13|P`rZH<|&=)Ur6q4ibim+sZr13AX zUWrZm5TUSdH-8;tzdI^A5Wmd)jL|pn!$R#1iV$}&39h0;fs_pKij}MhEmu9uIHue~ z{M`_dxn_^Gs=IJKW*8sCU1J~XW#l3Zl_)F}8_N_p$v>jtQjEXP-5BH%%l zuwdyrWC!iq)qpaSMEv4Lms1fN=D~?_GxiHW2m!TIg|BX$ST<19lt>(v;mc#JOs|x` zsnIqbyZC97c-8-guU0G08w`&lQ$uXcDCtl zZZttoEn=&FX_WPtm>4Sd@-Gh!XYTgBdRJ47<^1q!C*Y#*Z}Zu)B2o&GA1gPzwlbTZ zq^m7CQv#cQNAXkqU0=EAJ)JJk^FY zS%i>)#6`8u{Y+$o8#^NRVmq1~LOf@V6qD7Q{)6BP3kL`W47%hx(DaiwL&7Qqw?by7g-gtt=Piy1;#pHos zSQa;Oz)G3-7&hK#(61iNJ`*_$_TA~5RMaE=U~g+tfB=rV|GZ+8IwwYy3PTsKGgDl! z9zjU=Hs-ERW1gEoem{k;9^gLgH;5tO+F>HhCc}-O`uk{E?lHwg2E*i&S_A*gU5nF8cv;rfol17g)Z} zmowS&WhcoaM$(DL`yQI{2Y@DI?(%K^7|rMp06)8%Vezfm-Tqq(z^eWRFHnAJW^X<; zYv~lWe*KY47~ispyfz{)IH5WvkR>_g(^+_?%6p#U8k_n&A|IXhM8o=PLh$hNc9%LMKNmM< zgX-xg`()^uv71P&4QSEId0GFl+Qp8AR0!DtI|n`;oEOXQhDbeXkLd#YWP7!Q)J~#h zbS%$%Y~5M+Q%o$r``E-YmE4TyjawAXy1O-#6Y`Q2slJ+zV^{Zu)OXg$x3_V%Zk*sK zjgfb6gL+NVcltK@pyXc8^_WB~vq}XnWAGN;1uU91prPxWRe>WPfzmMx+{oD)?ZVo6 z&xYF0S@`Ajki>%n5_IYVX4Jo!9sX8@!$z$8R553yn+y0q*9zI}w!Dt-W4>$|ktUr! zI1gPBG(WIa1XD_l*J#iU&avIUB9kWDE}!3sZ*1c3Au;&=0}FGqOAg0+Mcq@}`pge< zKRC$CIkIerJ6(~l-c6=G#D4=g)e=E0@k{~Gbz`BjyO1l6Pn4UD7g!W;!Y}AO6%Taf z#m`dlx|RgQ4X%4D>gaw*ZT2yNa_Jb@E@AUWEywxy?dm$#sjo&`Vp%byh*tkVvNoz^ zMsRELZ!9l!0$V|rwIR)um`4h}qXCP<%9v12QfJ^?MX$T(S4W^e!NSei{p^=vwK9Xa zpGF@|et_yen0`UOB%N(I77eaQ3ANz9t9CcSVDWM6_A$>*?%_`Y#=li%$PH&cyumis8d23S!hNQZP(-Py(_=i=vjMbQJ-%1}x ze-+OQMow5B-7LF0x+u)h;xqfW?jH7owDUlhOU`<2Pmf86C83?2&7%^$(z}1t&F5*Zr?Hh=Ab1$Jg~THqW2#zr?}N z=<)3dzFOQN?7wHU|59&w8&7V|%@oI)v1@TTZ!0|LK%=IBu<)>i;0b08&6gh1mS(Zt z6Z%mIE}7GHDCx2=V`%`1)n2>|gg#?74wPXt1YRe0#(8Tblp zve4bjAXAEJZ!u1)sYBJ^gVkK5l+y6Y)cWadV%9bjv2sOSM_F-c>~I4M(rnnP8cgc# z+=Mw44|ym>lMA!-EiXHm0_1Hqdb)W z8x0w=AyFOO9X->>_vH?Y+!`j2>f6D%yIg8S_wbjAxfRd)tGno;o{@6CPf@qlUB%sZy+bBl+#gix=!tqzF3YG`OB5NnpSKjYw^7t8K z?q|fuHVSvVZ?kd=tJ3;tc3=wv7HcAxa*7;yKFgmWY)@?DouW(ugrqJZ3uvfYe~r;! zP>p)UUi$}bdEF=x(n#)(g-P~*NGC{;jy-=FOs&h*q4} zT@d?W(?lFQ=qN;xNMDzSaw_bWsZe}lv zjwO@Ls!5Ey#Wool8Gj~6N9c%#{+HV=gai4M6Li={nHbokt!|F*!tB~k zuo^gDpNRhWCY{D`c6#Mz+1HmY=dOiB%kf9FP3R1fp2gp^6d46tAVGzb_~}_|o}SzL zL&J`IDvz7iTr%b10}Uz770z>Rr5zM~li5Y}N;o(v@xnIl zdEu+|fCw&Z4tXaRT1Xc`pD;rxJSoo0ETxeX@9_!ok@qg(E|5UVxQ2Z|s$(34X>8}x z#{7K3O7r@34R|8eEvkCPb-411%DV520;EAXZdibD3umtl(k#4rqtYb{@DlYOz^^NO z;!H01x8AkRkh2Zut5VDwzB|aabNl8jFT77@^|AdV-zTE+%;c;mS)IB(mTe)?*CU zm=_73`p=3ZN(<$BkNj%*St(v-SggQtM|jP4$?KKja&nL#9cbn`p1CErSSe)kqc4!1?@3d3u!FPjRK zmr`9M6Y1R;*~O8EZ`i%`@RN{L#vK*6%%aLid-jcx_LN z*|Bs3DTk@xs!GJT&e}AMV;M{AEs}UpfjtUq0J`lfs#Qha*Z6h}kH5p$v<{e*8xb%u zbvN?@a~mBLsLUb|mN$ubc}jm7NcsWt?r4rEDcU)h<^?dr()z+szS5;{@UDZj?V69E zq$hr zp?Qd6=kBi5$H52F?EW{>#1E+C4kzT4haX%vhw%=gDh)~to;SXCLISQ zg$3rMO=bJa(yQsQ6&dI1=BHg_cb}fV5t(;OLqYS-*_mkgf=|Mum8PsU-G}PQ$2!XK2xfUxRU)u!K_=&C6{zkQC* zL!ynqHP4Q z-q`XDebAvR+c9+#pVG18B!q$TnhxENVj7H1(p-L#bTI}II18iWecIUpdyC0Q?#~_* zVOA2(_VnrHS)S`Hh&P~%R0YM6Q*D+9N3l+_yaScC+vSxVR}o5V|ITozoM4w{^GmS| ztLssg&5Nj!ga$}2fodUk+S~VIcya~#9)c=AzD^~&M)WNdLsvO(&ucgqBs5zrB#Od; zXJ?s`CDfb1m77Z~$Hu_Ve|skP_?G12MNDxF7N~vGu1JFpL*JP4gEk|LWo( z(2kw)QW3e7H=<2)yw^oK`=??C`qDr$-q>*AtF81ecEWn?fbGR&Pu*ie< zic0A#qLaNM`2}48lUXY6Bm~~6Pv0;`HD&-`g9T0BSg(na=pYhra`PrMhhGWoJrF{U zWTN(_{J7w{qP-LPOhZhVV*EW{Uqf1dw{`W!ILB9^q}luXLGT{qmTAd#f64z%)NFsH_FIC?iBE!fT+ z^YV9)1V8SvtfFTAJkLcU z!8KK{(+i;d%$T5nqS}SOmn;>VAa<-zko>z79odf?t1n{%s_a-<2Cdu~5bZ3P8vc~S z3`+Mo7VXl9`y0#!-Ua8VDCCR{O)~E?^|Y#nF$~jO2!LRSGr&Usy@Nfd#sNl#Qh}Y0 z()q6`KL0`v>pRc@x|YQC0^36F#GkgN{SZL!dLOwQ1r5jC>3$cS(V{~R43`Bej`?qxX#u(o(CLx}BI{nko@h0*A~wDcmaK`O7q2DB z29)nR-#11c&6(uUv{7qmNeev z%-x+fdvOA6>I!PO2c~l120`&G^Zx)uut9pyU|f67gL-EuV_D5#pQ!RW@Vly=RMaOZ zUxXQ#z^B$V&;4~)*)JrPv9K~}P%3KK7ER_54 zi;G5J4-&J$%c>;wIfwdVba8HH|C#Njt^2fEDU5S&dR2pDBt&FIubeQnnupc zy~c^S6v^yJQ|vBd$c70$^tJrv3}k`??pBYj7U>*;3z^yiip!^YvTvYYXX25G+B(#z z{Lgr@+wS)hFwSeN?qm+n5jY$K>uWsN@B-1(s}CJbn_*o^c`?AYPqxg?Hb!1~*I3q8 z-2SpbD7>|!JrNrJLV#|;3ctG?6^13oenfp&E0ey z#XeB!J7tJ8HJ4-xeQQZH4JYf0t6KJ|YTnlnMbEQ3mbPE9z0fbB+7snLhN11Wq$?XZ zwA_iX?O?#I37?6EwB{%E!##g4NDI;1BA=~EU3uuptBf}RJjI~4F~@NpH|ck)|MHNii&av!JVL!7Rw_{nNz!gu6*j6eXHV+{ zLS_S}c>1z7({*D{*GAPEbM~7qS+t!@vvD-6(Mw@^9(DHdMAeuF_f}-Jis%E>lMJHdshDe0@e!*ZSvx0uX(F$7Z>NVsffa9;IzK zaKy*U*&HwPL^Y{~fLHhf@ViCc zGkwI!f7BTlQ@wM|bAJRbyF`AnfIa37I`08Y=vSePf5` zJjupUpeLa5*GUKR`$1KfJ`fgpkfbd`ffczeX???mIof58@h!e;4d z=4e(3US7lqOCh8#%DVK~95IlMNPJk#j`dANDP4TLTe=Mw831oo^~>BGQskqVIVaHt zeBNGzm^C^EW|VH(wsxpQieYwlc1dz0PlSEL2?;N`6uk5}LD2c^0Jn?`jTNlQ6dkAu zMP@G`GAJvWoF%&w_4=_<<7Eqg%R=YhzN;w4xz{GKwMFJ`S5a6i z$T^m8J#Ou4p^O5-Tt(<2ZD*-;z)o&P8h}-BBhHb08C9Co6-XQ47OBNEl9*2z>Nzns znn&fo3beAohCW!8&P)rHwGt>#!kx)xH#{$x1PX#lMwQ)PQ%Qb^ zL&n3zwkZPj6`mArHe+_sbj)&Wgrrp0S`gza1k8mk-&sKKQ86 zKgiEH5qY8a5tV4!#94}ymRC*f7^OE{zO10c6Tdt#jmeAaQ%mY7Ir;S=^?EL)=+~k# zMz#m(c^?NW^0@2J__MN@8!6nb$}o?gH1}QZ^{E*%kr&6LWEBHh@VzUmseUjGLiZt{ zz;J~$hon|J+iM+CTDJ^J{3stkw~_eo83;R?8l2W`9}SvL26?0S5-FenuQ#DX!^dYP z``aJ=ewr?vr3>nZNwdXUk3|OUfPU6Z2;(w_n^y~wu7MEz$mvLj@InQxN4>K!?Wlk% zw-Pvll>5(DyK!!#jzgaEg9_cSoE{qD879+4)b9j17tt85e55kQi)N$^O$mr@`8`86 zz8H`{fZ%$S&Od+_HB-$;YBM)QQZeR{26T24gIyG(TRB}k1)gT@eQJ=HAB-wS$_=ge z@uNt3&Ha}x)3ffeH%CM+t>b~i$3A`01@$L;^1dyyHb9I=k_AcQj(H*;eBSS6L5;qz zZ;1M=C}XalkI|+H#Lq+-$D*nru?`~;pU``JGno^q8MhyLxny#@ls?;(DoR%2^Il^r zzloFxYC9rb+W65HWGK}_x)672Likl$j%(f+rW^@z6qI7HmOtg6Pa=M zu!bK-SW16cV@HHMtCK}(iE%W*p2!~|-QuADQS@AO)u62h-JpP`*@+0@i;KN^+Osu+xwmh_OB z7T_W;cXRZjxQ~#)Eq30&&(P#M@bcxJ+zv~l(B@BLw~gmbu48V}AsH8?T6Igu25_P$ z^mu6ev(_fnWV7+Q-gnh|6^rTWjDOJ^*UC%qW&WArbcjUF;q^`Sf!tq07?D<6_K}e+ zpr}27-qtDlhr@^1=jH2kCMkx)RRYec)XTxSMrK}%NASL@E%Ui+G$xKwH<@J0szhzX zmVec9nl$+!QJlPfM{$AN4-NIo&hE+)^N$v9yHtob2p#6~`A#jjb>tJmg0pc$ zUr!Lyq*NUIqPShLcStb>vBn_Xgc{stKlF1>89fjzl=<`(l{n^0ych|nAWTiaDqL4i z3mQKQno7I6G55D-g&&f+EqnItcWr$M7pH}{tXytO4cEa@DbC=Y>~PGmSb9UI0{k&! zUA(Ni%{i&CojJ__E|eChY2IJ^Do$D<_F%sWLnU^8oe}lPKDVZd?%AjkpwoVV9b(Z? zQieteuZ_F)L<=|p%@4tS!iq01Yi~_rq^7zjl&4PBDvbh_dj<&9u)r7sv1K*PC`;vYki8 zMzhgF z3526@PKV!OMJc%;CQNMU?aYM`GMm*I=akCz+XU<>`Z;ydQ7G<^anIxvYBkUS4Z4;p z-(Hfbj82u}4drVLpB(U9XkTiRLkKh1M;gnltP?cZJEK+{xe|s4k;F ztULubDr0W@v_eKq=5~st#WhXp(gnx$z}=UH5Oqp%r{{PXJcyayb2seEhUyZI+18sw z;raBuZAnL;!7+<3-F?3DPNAurf5B5#HC3YWCh zod&w;2W-!@*Bq3dMfEzZqVE|yq}B-9KkVPUrz>#)%x04M31@8U##hj9ut(_Qe7|%_ zovQ4*?KzN)ypH(usBHbWGA#Ir>C#T<6fTZ+G$Fj{&Xx zCC>Lxz&>SCBb$(HJwA1m>f&HhjqcN znMM29A-47ix8BoZ3n12P1+XjBH2Wq0CjLyQ#Bjp&H(880RG4_nX5mhv-j;b&dslvu zBCm1@e5#wyVdm^ybE+(=C5MnH%NngjmkZeSDnJf^gMMnDmvP`^!b&i&)d=EH%Xx8T zIM>Z)yaWf-wgq zsKL`rS)``goLbb#)Okx!??FbLCcZSH*1D+Eh4GbimWaw0;=pqmucjZz_BBu7jS_E3 zZm|VM;j)$NH^lTlfOC`lckF(iI=^iqyk==3OHxasM~ncM8ouFf3u^_nZA{@l{Lr|s z5;44PlbPfB`;bibz^-Q|VJpi5i`xbdK{dJCAET|b8(u?4nFL+~&>c}+jYp-6=sX~# z{H*lZ5>ni^kp^A@ZdTmjYr_yIpQ(Kx*PxRX$4zhIite0%$mxBaWXU(YOO$ubifcQ8__w9Zv(^9|S&VeNL6JJ>LdRw#J1y#$!d z{r>>SBJPsZITvYp;}xU=k#iGDa1!#7l{;|Gwv+nBhy{j15L$=GW(@^AyZoJPhbwQj zc@yEXoT>f25AZ0^}e*`&U^059OJ~YTp5cQJ5x~G=j z6hmmv`5PWQ^cAs8E3BvI_WCv07qf=)O}8s<2h!#`@+rNg8ZzNLC2U8?n5thrFwPm>=4UlyGpivCw$BXYNFWYbGzy zgkr()97epq@r|{z^qa9W*t`M(;zD(ArQI7`fgBtTXQk=v-aHid_Z5iHl8Kq}bRtTr z6VaN-unLS&?ME}bzV(2d*O8sPiyW`mdJLQ@Cbtee4)N)k(rD<`=dQ^${7|XEh3RL* zv)rSx}s6iFnTF98crXR@UQrp6kC#4^}y6wfGl+jJ9q!TXeP$xI*A|HLs zXU97GXeHL;$NkQL{P%gnV%aoeO+$`(QjYzdSd#rA-$rm;@6K@oUkvg^B#i=DQ|O82 zNcFTDr|Qg%oQmLTM65+FyRcM~2Hz+@Bvz)O0UEZABw)ewrV0JK%>jnF`Qd${4hR3I z+dR^49dh32-|7UEUp}gFw8>8NpcJ*C(0TV<=yeoVU9)lQKH~IjcNT7Wj}(1X8Xlf!r4?jHx(}Q%^W?Y@Lw1!(&hpBgJo7_IGTDI9jwU zcD@ZCMMgoW8fsJ@Ue@Zw@q)WEZiI~j0{HGW@iqgL2QzGXR~dKHX%qt zfZ#3(1PJafAy^3R?rx1+a0oO`aA_pCLnDp5b#QlgclXP;_FDI@y`OLId(QcDe$`WN z*V|8bRn1vdv&I;cOE%#(H|Uix)qDdGJTrqYkk>yXZ;~h@M{gTbxYtpy;)OE0Qe@kWk_SZ7>Ga>rQ2piqv1$!tsWeq@z3Ey*dolxe$=TY7YJSPK z;GrU+sn{2ZmMN^k24ZJU`}nj7=w zGF09ec~S$q?Lp^mIuxnHp}UJ~5SJU+4q-_^f`b4el4a3gU(wQsBij&y$M-+(hnoGg z2jPCR0|2-Hv=<;r;Y3_HQCWU?K+geTSyj+#4z$NV<&f)j$0E9Ap(y(C--SZ{`3%dQ zj$v)Kk$rX66&{>iT9W9%Qyb=9{7U=Y9~tucRLiGN&8V*IQ&ozj`N;uQdOq?iEhVMk zoWe!iszt}9V}hFFT027bxGKR9v5u&?CLNtR3L@muCHCa}&ehRnnLw&Bw!G1EVE2Pi zfD-QX0F=ncyEUHnqMPL;n1_n7r!xoEvoo$ z{FJbOg7pjXUu|~8X6#1T$v#X5v1|AdPX4r(=0r`mq(6MGuGEQkotw1?ZWt^0EfX>b z=bmg5{9+*7t4Z<}@t^`;GZ5!`31XTX>D$g5c8D|`<~%M-sM?p_BD({Y@I2!Aw83QK zPs4QxrDLp&`}Ppt_v~Wuh@#}jyXZ=tm=&Hx-Z6-bo>sWP zB?T&@$-0GO+4i@Ut-6X_U-q!HFPgXMw^|N?!w2l~_g_mo%$=a5uSP*)`MY8k+Du(M z8=BL5s=AXbeGh|B;>{!$NfR&C4@oS9pb*mSBi-C9eZ~ontU=U0RCw99Q^KR8!Ay>5 ztBz%Bh&fj=&eS^J_d+$a=rVsD~^P;kk>JA zBewoi>1Nv`Ig`+wPF#Y(u4`>Aud#`Q$R$*|kjh-HIem ze#d0DoKlm-jAfPXoIl?F0khVe$^0p!b$Lgrdf|IOCKqaLh7Rw~8}M2j28R#E;@(1cUBC=ZuUcE=rH$d%V5{p~h&uNXq<`rcYRJDKiJ3kf^}D3; zA z&80tGzE78XV@kN9`5>4S2{Ev^Q&A*e`AboY!N9;^M?33pk?t?ol;#`)npv){o{xVx zU8BBot@ZCl*EzUNd2d);#>X8GF?wb?7n>W`F(oI+aF-0T>rFPBrb7(z z?Q=|2KflBJc1s{9E9JLnhh~R&D)wi*wB6oq{Bw3bhnV}vk2W4Yu!sk5>#`{dZJEQn zpn_``i*jtm%1!HGl!ac0Et)aJTeO^CZcVlYBkB<<6p(O@9F7?iea6?dr)aNz-yE#! zs~P4?wihwsblp{-hKQadDP|pdF-VJ#jsNM;R%h%$JlUIcHg_iR@nBLfqV^xJLx3ZwB+adeq2Fj@K{b07W5!J-p)HyTtVFtE6^Fy z#yr|P4U4qqHs}F^pf}z5e*9H^+7(ucc}-Y!@gjmKeD*}we$rNWM)1`M1N9asopoh? zCtt{jqJ&J!mEmn(xTYjc(cD(ud|}zEx$8K>?QnhdJVh7_JveHtArZHYHUp%l)G8rC zZ|1b%@*W;!rH!tc!?;L>oxwUtBz+^s!+scmjlVR?!&r;o_46x+*5^pxm^NWlRv3k@ zCWC>i#d-0khtgYot?rGWGoVabsN4$sG{1t~||ExAd9w0Qje#Uy$tbqlqX8GECL z(|(upEK;s^V2xSu!EkIO0veB~`Kfk4`)p(l5|{HSVcL>O6dC=OKk$Kp5j{2aL$N6P zlhZ|K^MD(*tK4dOwRR0x3IjK78{h?$Lq)8E3ey?DxpA$H#v56$-Px~)T^QxcZ&POw z%{zZ$5G{eV=)lM*GOXTQ`uid7cof@Yf)y~D`Grk|8RMg;lq z{blXraqN5LPxisUW{WeU(CeVJKjdzD zWPZ2ZmXhYERZLGcPD{JB&gmvXNu&`kl(Ou& zqn`6@?ExlEVeCp2PF`@&ezZY$(;m~C>I%f^&%cYiGlOzV9f_~CxwY+te7^UbnDils zSakMW-FF(Bhm(x0N$A{YZD~;Oj|%adHX*_Fa|g0y5O(Qjy+Bh>L47MdiRvVb5(-)X zZxmTY0gYh_t!IEt(F+c1FXkfXcPcc9FHE?0mkjDG>8k`iGG^<=hfApHhT3cW{Obi( z&LMZaY1-BqT8oyqPfCiC_Gu0jU&wbgR3@JRb;t4vS>1lIbeem!$adb~HWFgINm7LG zGa-(P6t&Cic$nTS$65}<{>5=^b}b{UOz@|9#gJz}w$A7SE`Lr67v)eg+zKX;wkYuO zfc=hq;%zuuT6BxLNenBYOuz;1{#v22zniCpfg{mb3G%tN-Q&JJ^$lIU^w7$1r?&5( zkkjCjVyeaEmGxbngO}%`inAB>^OWzAn-oI)pSFo%h;y4 zNHIe6ZQ?6b`hN~n=7ra{aSWpyAzRp^BGguVyc)GC&xkVn`v~+uj(D!Cml%p_<0>-m zW4KL?qYNH?kG&xUYy4mcw6S_M#3z7hQX*)%#rtvOkC9hx%AuCm;(Wj@BkxnDb^Ege2E{b%rza@^H)@tO$=^$2lbrQ%K z9I`F+)4OEYDc~*j+f*&xvC)HZISrX)`)~Uvw=`7F+A&UM)$CowK)8uZqB~{7S)dA- zc;IBq)%1Z2-9}llB3cfI4JC~vg?=5#MH!i$m!e~ped4J})jYQ99BvIQotG?P-NdS&RePhFsc6mE=- zmtIoWYX!wWTNXP$et!K=w5n{5D3QmBxoIdrwKew#y|g{;%@j`iF!}9+wBSLpQ2omDf#{zPN;WHBZU!m7qQCz>|1RRB z*VLLYh>&=*DnYd$A8uTJ5)p*H#jTFXcXRv8NT+qCx?ApI6_5Li8<_z z`F8wRJDtQIdN;g7E0BUJ1}9#Hph-Gs#!2#-&pb^opY+C<{VmPhmeR252ez-%@OHg~ zCs+PJYht7dqkz8YXgdScjo|xTeS4lmE1z9t`a~)6n+o3j9A;7Df&veGv@*&aBn{dZ znr*{<^oBx0d+)3GYr>Gd4C(5hhO14;fgTg5F?3B zFxT+P$Sl-beHM|eT3RuDTqfNfw^y9BW0njw1|9u+?aC{m%+uhh#=fxBX=7&Lik|DP z^7Db={_DWyMZF`38IqP>fCGgh}~zX-Xx7 zI*C3JlEA06NRId!_++BY?xb@iJ1nW@c~d8`q-YYl^_)75aTMbUnU~L{QzKIU6lN!I z2-AE+i4asN@oLEqzJqz}%OTbJm!_w#TT=(u+_Xvji<>F?!ie_v$%ur^T3iYz!O^gU zfZrrunsoVZZ^U_>SlB2Ih`0?;iIDYBnbs~iA&y+WxU~r8l~wLPkVI^HqP>LIx0R|N zyimTJ9BF#yRV1)VSM@5keCrQG|K3I6*8z*%?`}Khb&a-&@*^HUoS6hI zpTr!D<=M+5vAP(x=Q1>cIk-RNT>e5moP`avP;Q!4&@U~{5s&p*5VMN zj`e`eLU{rx61pR!eHZjX)Pqe1czHJMI#aIdS4Znhql6onfGu3NQ{U$i*+7OfZiVd? z__XlpBVBt?=)1}kk7$IR^gjxN62#0(X}&x5-k4#sQ=y?{_k_^2Uxod4jGTlMR z_|=uOjfT~*8?(6p4f}AD2kNK|)pQFwL;XQ5<+RN!pY{jM*mvQ>!Rp8h)~o|MFS?C59l&3tuQI3|$DVx>D_rOB%unQ-R5-P-dwn)|W0> z;J(Jg@X(s83AsHsQvtFHRt8CM+j4_MC66h2-1T8RQC2fj+T(UB*1|f6T@_URL?M&D zR|yT1=y*s`dT4}<2IWr?yVHc7SaR8<7Ae;QTIVanyD6dUF9N2ahpvSpM6;J7TLua7 z>&aDt*MZR1S2h#%#vZ(d$qD{xZS209urzd1_&O#gM8koPtMvg`cyM`>F{l7&H9udX zr+X`hD7;2e1qq@0;$9**!1KxEhQkYMmt|qBwQ)T?V!9t=H=A{7h}wpU2Q=~v#{Fxj zdZ|_QWF5Ax98V-PtD{YCJfn)ca@Twf|4!`%vI0{)4^8%)MaZh2q78hQzCQ!z zJR@_*3y;=3O&S!>bY>Rf5h^z45RnVI!S&5XXDwWcnZ(g95_|=7%t5bq1|k=iPa~T= zfr$HxYnyyf7k-|bK%!Qhf%zowtf^KQ=jtS^He&yCy~?3r>Nu%`-$N$~y}_%M-F*2M zkA%w5HTjY#q9AK3_UIXyiD3b}qZ z0SOG_I(9}^!P%6pNp8EE6lUj0K)_O(*mx@Ak$}?m!{heEWivlr2JGDA$B_tuW0dQe>{5~_N>4x`7mnm{JhkevKa;(eCfKovGbvah zh&Zf0KIHvI;_SV>H3=E}WZF%Cx^YChAMlW=9N=^i1^$(wuOALe7G8>PZy&8rTeQ(f z$6C8B_n>V+)1HdS$koRW(42VzUvzzQ4J)YNB6h-EFXTtl-?)Z8bobG*uraP+JFZSl zh*cVLV6xO=kgO1pLDxsN4p`vWH9;K3MZiD=91a^h_Dj z$DX*DT3?6B1S)TtzEI93L^NnJ8PSMQ)TMmw*9)5)dcrKOtWI>!40^FE+@z>$NsBE` zx4Mlv5Vi}B8oO{2|*-ugug!^7hf&TG^8a30czy>i?+`2*HbpZ6DO z#lbkBw3M^ci4yJTZfnmAx0Wm`SZBk)%Wwh)pDiD!Gl=7GD2R$Vx}R!br-r+8$-@Sf ztTPx`n)MBS?Qfr|eA)2nop=V^C?q@sMt|KGP4ry#SJ&k;<(K8 zYDtPY@9P#QeRdQ)ig$moO1V>8e_kj0>jvT<4Ahmwj7-636 zh8ix{(BSU*2;uy`%+Te%f?1dI8pCa#bv$J#b-d3 zf<~;lhwvOJx{}`(z4fH90zu>=F0T5Oe-FIRQULk^D8{>ww#GoGnxBaQCKkGS!BoN& zj`xNKqPt(cEYjcshH0s9ET*s4d12ecynSn~^Cn7FbkvYzeR^91%kb7zTFB5ngWeGC z^qZaa_oP4Vwm2tENL-Nl+IvX4$ZQ%Z`OK%Db51_pYrNy*Nkq=h;18vE_3$D59(_8=LVN5fFMxxyy3Uq%iU zi1f+G=@~#!nj#lwhm3HAw5v9V*3BtW$Lvrt-!hTy!KiKebK;5W!g-DGkgw(1a=}M~NCPh?(jtT8lhUCwxvz$Uj zT1>-P_pcM3C9cR+xP$wp#bA&)TbO~8#0L;|wpXyDl&O^;*AX4AS&F7*-3FF0cKc=- z(E(arZEg9s8Yds*F%gkjaZ|lO_nK#O!Wnb?It~8>b*N@)TP4&nsF!sE)2W0S8)mnw zdCd_-EG~gq`DhdC#vQ>y4z{bLA^~%4xL2XcS0`@O9Qw4P|SxZSlIofQ*uXv6wlf9YxtC+3sC?xzxki zMIK3BYPy~yw~~YCasIszcyl-xbMdZsykU=_d!{;b&Yb6~bK3D{h4JdnG&r6>@e*mTdh zO0+WVTUKItvaLt{^io7;4miqmrntTT(f&5wJUg9Qgx$u2EYku{Raf21RB=dgqjzJe zgN56;v?DB-c%YQL7v6cY%wpLb06dbMqsJk#@5go@H%gwTo$i5khOFR>xGl%5!`JF; zqg5ak_%@+N%paohe?zMG4sdLJ+%!dhR8x5dC~w}Lf^L#tbe9Bwl9~U#m`rdmG4gn+ zu}#P!2x}JCkmKU?O~GEjQK8KrdU%-=02hQGmq+gFE&C%9yoUMZPJ;|rRzY=VKM`X1 z4{CHwCd`X#1{*!I`ab_4y*G*zgu&p?iC$$(cBr-((~j4bMJ1*~mW5nYLD7c^5TsYr zmeQ%{D!t@nyk}Q2MaAfaHYTW|apzTQ{a9hTNa}TysN_gE7BTn*A#q%fwUvISRbTQW_lrJb5Jt;;FXkq=BB#FsKyh1bI6 zf93i{9tJ2XtVyeWi>nNiN!eGQ`@KqIZ&gjT)jmk>ynCQ4R7GMYs)hc2lXyF>aQ5*d zUtPvxbIgI2kqCJ|f*@)T;-6`LsGo0aV-sS4o931BZB*=3&t^Y6`}H4;A_hwrE9bn3B|CIX4%!Ds>Rz?>=qzus$J zYk5tPhh+%w?b9vsz8QN*yH+B=bg0*?mQzlcA(Q8os_V_VU_IUIV{{G+P*l>Ns2*~P z1|_|*O6QWS3j0=9Wm9?+FO_ur@u0}F`{(Gm5^u^!ogo-jDo-1{M1+yoo7ObTKpz@` zqP17yl2NRJAPQZ0BhFZtEA-dDgj;GV6cx{s=R9Z9sHi{LFkVu8Td?M|jy(K$MK~{I zWiZ(h=OmXqgCRRCl{Tt2pUxUQ*)SBQg#`nf6uA>w_Z9O5XW?Kdb^{y>lj#C<_kX>a zh(49|y)1ewC|Zx`DS~ZPY$YvC|6XEDCc6%)@@UO1<7+#6Q;AC~8s~wo`mPRv={7SA z*P`cs3fe}A%G-F5!@Q(Ua2KSxOWnB=50z~soK0P9ZvYVb^EPthNKWW*cjQf2U@die^_X;LsITeqP>%jsv_M*4Depy`m&mrA9`50LE+cXT+x|K zmyE|Q_4MJ>Gyuy!AJgevtCnc&Y-sph2a$wIK-=!zaQXone|l z)u5j;5I>Ax&0iz}O5qXMKJ775s2eiA@ENSe21}I#?O||hZY3`&=L~vakrS$=UCw z3ll&c^4b^fI}5K5ezdfn=V?-y{dObhPbhRkrnQsE^OKE#tJPlFi2Mt zHMUlW_P}Zy+18R-6d*56o%Lx~>g}ZNm`fe>6=G4tB)(q5Oze`weElVe9llc}FQv4$ zmp}@w_l92Gi^$XQrZ?9P;W&D(9@Ye2t_GKd&t}*yRHE_`jO|OD(c4uCrT=JJP}85B zArz0wRuYd7sqU(|trmX<&_wEy;by-I-N~ZBESYpn;Qqa#)?1Ed#wAs$T|G!I7x1B; ztmq{Sc_g^8Z{wo$&yCOG0H5(3-KXWu!ra_&-GRs?KH0PT*n@LAuY3Es0zoRCH_w2T ztZTJ}OXDC1@r`5rDi?)>(q};Nhif%!&o~~TPN1#Htb1b<1E`1I3spT&r|HnZH(_0V zxy7H!S$w#*w4&wfPL(oC^@+6;`_yD58h$b@0 z!YaWsav`QAKXRj08t}7mzH(Oh&MncowtTK7&9yY`Q=ZjEt4v^^rOk{=)puT|(3(Kk z8!Fo)?oZUfqDmy`Oc~+Q)=_Q;mQ4n;9`)3Ced6L$`#G!*YpQk0sxf=+J6VVbtV3P=6yEA~sk^bLOLdYn`$OVo%X2Dj)?wSF+aP2XvCu$0n5-+V z$=@5;sKw4%$trmOo%qBFyW)`~G6YeW?A+G8=vfjZ+BEp`GqiikRg}g|=$vlwqfW1B zNDI{5&+UNlTbKfdX0=G^#7{JVT72IS7f?fcG{(4Tcb9I7hzDZ?P<$Ci7bUjT&;%+N z5(Ga}foK%Rdg)VorRaZgr_cASP5`J&%qvVCXP%ToqFjj7B1R?QLF_yBJWkGm$1UIN z*1p&=v?@|z^Pt31eVxBD?Kw%E1y$6!5XoWZ(Wn!&QiPZz&iUy-m9+@eGTq0d#uJ}i zZ|cWx`Pv0Xp{Itf=Kb>}~*L&ImnF9=t@P4@DVF5d;%s4z`{EFT1zHN?_WiND4 z5iJ>w25DQ1<|c=CCN=erNw%4FdTxOvoD^b$WLhYn@(UwI`iZ*dwz%I5lj!@m3Tosd zm}(7j4{1lt4|doSrXYe(F}`ov@84u^AJbh>PXU_%bBPb;W=xM+UC%Ep&>~UXzop9k z3vT(Jvv#bUKreWiR9jGOQrZ)0_-^z#m~oQ*U6t!MH0Em;^{2Ifz8?HGd~)#^;^GK5*hzk1ZnCmN;&7+CB7FRKhxzTaNDh$D4erl@s0_Rih!Gui`3!G^F|FP^E})aZQX8 zJ}s#Z&WI>D6bbZxjF#TkZd?W1UIgny5S0WGA>mX-W2reI07)NyZ%;K8n5&}Ux6#RI zHupHf-1qkOD%oBFUp4)zLng-Yi#-hsl-b~J z7bHl{dQSy~Tl5kHs@mZIzu<}0uP~$R`l%!rn~?bu^UQXBTT3=1Zg^w7C|z3PYei$# z!v~&V3xmPIz{*9Rm{H)dO>F}K5JbTV2(s0*`ooDX&GV@WD#WLaWhI1 zu_V?thYWlVO^7DgL#tq~>6KC7Sz?C_9yIKjr*=GJZcqF7G_}N8HEj4n*?YcB4iWW!a|#0h#P6qQO^L(v*|loGI!@J z6ShX7pwj4PK%edlf8e{wG4;u0rO>TZzuxXQug$5K9+#@Rv79A)$lWZz$PqkSowu09 zAUjP?5NmzfMQ>_(@BSh&R2r%N5Qc45=S9R4+>CgJN=4_*Of;j(%5U_2Dj<)$I$^d1^X+f0luxU6uefqnFYlvKg3%~=b`}( zH*oi&t!XV%D1@_BMnNvoXkdb#s)}h+Bt*iDr*VxM#PhQnlW?mV+GcMRT+#4H7SG}> z8S6+DX1kSnj=rObUt9HwbKpTH4MT;grx2ZW0QXkI?(C>J^V_+!dw-G}5U#HTQ4CV9 z8y?=NbX{#I`@Yt0zhk_%qjfgY#&Ucyl?#Da?mw%ByLf*iy zyEdcu>U_Qxts^B5YHw#RNvtP0>Yo9O!u;s;F`rq?;n(ffre6V(k5QOS_Yw_wG$uwQ z>78c=Mb%Z$F3G!z&W z0T6bJ>Fb7SvB{#665IzS)2mO7-}==^k_NbxkF#d)FI+|)cKH#X7^Ee}YTjUPDp@eN z$G)CzJZ!Gk&a>^A35VZtxQ#-X?ZQMt%`!>kDsfXK@|@o{#9#$WsuNIiTjw)H4{ zA&u!b!uD4jU1>8p9kW(fz{)2hSm@8f4g0DeA$P{D$bz<5>aTWAHL0+GgzQl*VXhc2 zrj~?6w;_{Z;>pNQbC%XO1LMFCS6++5RvOw03fd=+Z|s^$TX)5jtmlMArMa^otn;sx zb;B5mC75iv>?dYWZAh?@#KVqk>n_o#=F-P%X0bk}ETmXT^fG-Iks_YRKxQ3qjw^YMA}z!;!kIFrqJ$ncQ@pSa7Bw|#Qsq&NP{QvxOF#c^MguBD3v8Evv4vjsnH1--!aF+(>PW#rjW8xGH_t!)H|?5yGHp6Z ztiVqq*ioUszZ(0S_r3^Y6l;%hbCU?~ebA*=08UD3pjduhmOa8`84xt2&!jnMOu7HEfSbH^9j6KStP^T3BNkKo#mKF&ST zq%bBi9`&=FDC0)L?kj?XJ!7DKk7aQIN&wRcq<+J3k@4#4XN{Wp&|rr({g~$@>LOg$ z6``f`{o~+>!+%2|`I~qNV_LlaI@z4AYJ2L)*5ukmiQUJQ+B6G_Ed-D5#NBye-_f=& zuV_t?)HRnF8<=q2NmpQmn^fw~|%eBg5NPX=zoS}E1`>-6U2v7Z*al~}D+iUeOQh}~A zzn`m`^Qbujts%BEr8pXrS?A7qp@%23cpH6kds<4gr@_xcg|;*Ktc^UH-^xY< zSF?pdO6ZUM-rd6i%*WK@KFZ4#Y(zYoG-bz#21{~zPlc_9Zft00UR;+l_gE}d@mZlq zC#EDDceZ=rE9(EtudL3f;-8wWPUN`YYh6(pnbF}^25BxxASOiQOpY2VD0eqDx>Tue z2{Q9Kvi7l8OtmfeIuLoh=<&%(N_|7l%?*9OuPxp-|IlBrYPvs;>!&0=>VRCw^_mn? zq$WK`sk>hIbr|>7akIR=Od;8?)WFIfQB0j3QV(3cf|R_f;j za_$?olkJzX9Q`jOIrvu-l4_@+l4AcDHZwU2L&QZOC)xMwY-4VIH^iY6Vp{x8A~^{n zcoA#BtIpXACiE+bz(#_(Naaq=`Q(ZpI($DPTql|rJF^jHv|7KzhY-s z!qPF+S@`WZu+`9%(*brH8Kf=oCMF?1chc}%em3f2ePPI90+Fr%BBhbcpRwsWXpf}L zw2S~MDn;0?`AT4ydeS=Tc-5C898+L3OPmfC3ej>2&Qe33&D=Ku9ZOtyzLOM_=%0uA zXfOiOeS2ws$c%;CvQO5R>f0ZmPKxzKM@{%UC`dm^#~pF*IT^n|wx-hx{tW{DH(u@E zKMgPwM0@z06h#xNu@TO#xO&d7cc!g}-#Tc&s|z(cUhLEaaK(H{atA{#an-2ms{989Fki6i^1XhBAf|%5_CA`Q7pRA^{kIUaL_E)8T zTQ{<{?T3k9;O77>_VJ8hQ%zlWzy3FTI_oy&07qRujW!s5hImSqR}p=u>kR$(%pD$d z2DD~pK{#rQQ{l^ZfEU>mXo0FnbI>9pQlGT-%bzLN_inmEz02f6p`+95R>TXJ_wK!f z$sLxGkl=}{MjMWcI6Xom4lcp>xgRdooL#5m$JeyY*`@#E|8Akgvq_x0^)97h&tDbj z&{C-g)s}EL%IYF_zP8oh1};4V#&p%LugdkFFlZ5{&YXMFw*m$QsUzoWR5J?QUUERC z$s8B`EgAYhvyJ|hlN52s6W=zHA}la?vXNfBvJv?Gt5;EwvH3$woGQrNOaOKC~aKczRAZoVt?zl4{CSGnS* zby3EIV?Y{cY4~s@j#Y`__P_- zi^t5J74AaET~k6HUIusnft>g^4cpIw*)j~~c!)BqB?uj#nRRXYkZS6jf%-z@e;nKY zyw3>L26s1cJWE z>5TkGvzKA;ke9g=oFM53+0m5@3Ccm0rlw$W@Ht*32qRX@j9X$t)SgqlWTurdl1S$u zxbt#CK3V#oW?DJ+*uIngDkz77r0oyKT3$UC80 zL76GF6eU`II^fhs>Y5!gFelVYG7t>oM&r_xSPkm`as%cakZ2l*9hahs5-kbhTQ_>S zI4AiOn6*^4blv_i^6<>-+N;!+&C4>yyjd^c-uf&BI_Bv(T)_N>QjMgrIM-A!O4=V$ zVpH3W18?mc|pKlh4sV<9~8`+PBIwz8Sh_abP@|K zi_{DjUFy5@Jp)qho&jEN6Tt#;Peh!>zqzSoC+43Xn4g5oaz4z7FYg(ch;a@Sm<6f6 zp-7+yMjv<}*V)-|lKUeI=m)MXD_$cRwVq1E2wgd%?mq+029%_AG>a;6z@nRP@1rY= z^tn=(Z%n}j(d90o*{H+BSrwsgt<}(G^9VRTS<@HfM<)%k1+06Br0gGG`lILS&KNE1 zsU>pPg@*c->&LI}>GAO4T5A{~1MkHO^!KT6Ij=q!(TCEeB>Wyo&F!5wxp5=ATLLfZ zNwA#7A;}~gbU8l*S}xX>=hW^iMo0{(iff2HvDSs=4X%pHy4Z>2=dY--tH!N|VqMaU z@?xacst+HGu>?OetXp!;?2}d)HqKY0$!|N=nmWnal>4BxAJeVFu@HVw9EX-zof2-} z_;U4dDB_Xu_Hqeqlr4}xA!kl)XG<)3ldFXqY;p|Hmv=_W%S2R3Ry};AN?3-$K5Jdn zOQ_h`TC)Qh8ksg}2vI}8?D7zF$sf?G&B&Ta`Y*>?jxRS?XRW~7SnNUWcyT09#FkU$ z@HaPhOIssY6rkV&RN4vjkaFz&fhe&=)#i;qg6Xr1$7<7Q0eL?Qd59&b-88*J%(&}b zZTal4WHPl1Jry_`#Ibr;CFD1f@nuwM6{28NcG7LaW*Q9wNBQ)inonKv>TcX)FxmJ7 zH5cM8)~QNy?LRPOz6jlw>g1l44fB2OO$z!kP=~9Pf!>)iErm;xWI>w9C!dewN(3j^uDXOla$40xHt#|t(qlnkffJO}8FJlJQ!vayvTYpLdWZ|iywx%G%TaZGX}J98nsxB6&pw2E6YU&E)7=wSMd zJ)WI?k;;N4WzP~{+G9RzI7YY$=;nTpms}7qYw%)z&MV1WIzGpZ=(x{-+)2j=j>GTE zCyesXfUN`mXTT+11aiQv@JqW062FZ#51)6;r_X>1?X(&jwLkyaZuzX|3h-X+w)Sbp z;O-@esy24WWvg<+S&TM2M4%;mCPJMHE7**$_pk%+nMgIOt&fT>=~>B$10S z&wl%3^k|c(ffY}gP2<-Vnp7DX5AE&ubH0G)!<&NPsfM#Msu||n`6h(o{U5{ItXH3t zDnA!lYA*kLvD;@r=z-w!KMmI*j^Z!FO+)5}a-mOYypnd#?1Z80@q2F#`KZ~%s~M`- zB=^0_YQ^j{nvKT?qZHaOd^srMo%bS>YS6?ZeAr{q!f zf39DTqsYeMGfPtbx_vVMj0eqail{+#szyM(RScWzgo`>uTb8(R+l`Y{v-Sq!y|W&; zT}Tz~7JWiIhU#S>LiCf2-c=6kA6mn|2w0_kuc~)jMpu+wbct;n*)S-mcwqfKJ$Tc7 z$vA(NhK#7qM+qVNr32m}%C|iY>y$R46A98+oD@_WR-NuyyMIrJ;tL@W(NTsH6|#vQ z6_)u`RmRP6V!6Z|Q7sw?TkT{r+051q76>#Bbet*q5n_OMUc6t9LNYi`b&NGnugj6~ z^G_2bMT5BE!eof)4<1T-^LkV(s}LHV0qx1hrRXoqlsA4jfDF$pIcPC2?dSZUPpN`Y>)T5~ z%l0C3)~8|no~b|6l|0lDzq-c6g3jCR;78;fMkj>zqPB<~IgOl?qgd9^OSJaSnVwmHuwesA2K@Mjn|` z1)pzY0$X(Pr01_X$250Pfqo_B6TQ;K7*%TQGy zQG^uurySG*DV}D zGqWBzAb8`UF>{=X1g(rmqc=$r@bem=zQr-ol8S};*T6=CSrxk$0w5D#1?%{Iim+9ssmzz;DT6kQ!K4tcqEmm570tp2A$w`C?-YivUg)O+D{n**p zoHr3}s&p`Ul>;&D)*td}F6c;!ed)fIZ)n1KMr*)BC9`Jn_iF4#c(nM=9%WWK0Sn0% zSc2J#I;0^?8%czmA8v8~HA>HpyR@#&JFz}=j+8xZ*-H32DyK**j~8LTD4FS0?s(y% zuA)730_tBcOI1`M&}H(}b#gTxBQZuwF1tAJz9leM5q?;v3FtnHbk&zVDH&`qk(4VW zRticDuj8GjP$-zN#4}+a;dqCdmlIOaHGc%nmXSFw$MjHh`0qHFe}B98HyW~%{2{0MM$&`_?H;rnNxHgkQ$HUjS%*ERFTXOEOraLv<`}f@1xXeKZ~EA#xwWFhp#~i|?+0`js}9iHMb1+c*}E7euHfyN^{|))!-? zh^)Wq7t|N5tkp7~ncx1M78wVwj*wd*<(II~6o@*0=YzS#CGctai*oZ4B&;OYzai!O z_XMPFI#=ztH<_L0kU#FBg!Wi(>MJN?ft7Aov~hoTCi&lZhS1JQ)V0GQXwr8}zpecT zP@lZU=YDg~7(j2Gh|G`^DoJ1_x!yP=^8~Hnu?*+r)My5QNRL~u*CNsk22JQ0-mQ!P z1j2YXi(YN9Y&(|_+BOPb#SwjgL}WI;&&hj{`#@0IXWsj|_dVTWC}hI^h^5pMBx|2L z|C>Zg6LmPeB7Mmvzp^Q!I`jaY0A|uzL2CJV&%g`&*k-A1DiEj(l{2 zW4TD9snMKA^uV$eGb@v)#sWb`RDO<_v!Ds|k}YFr4xMyK83gje~{D5XY) zqoq8XABC3fADY^Se>UD=yk{(fdYW!)U{DCr1Shkk^!4u1S+t>*fDSH62LP^2y#9=;(Ioe%D+h9L*^gcs|BkQuA;S*mjMI1o2Sq zHL-k8VGb>0@X+>pdfZ1ls70~HRz8I$ESf{K;1igyc_JWirO?Ip?6CmB11$5%j%CTJ z1=;i>^TY)+-V&Am zBCMA1Z8Mx_@HH>9r@p4}YdeNx<$3BLnyMkxhLdfA44culmo`sTMhEIjt5nZ`aQ+;I zXMo>J{IcAk7GH6yP)Mu~#mLq^hJW|{)}hxOZxB|#QFi?WBlYIzicF&5!DBZ(atV+M z9_iMxIGjKtxn2mdYMhe%f=eNR1PB%!3QHxyLV(~N+}#}l z72JZm1PER@6z*=pEjYnFxaQUE?t5qE&Fy*J)AN4JKhD{EovKZ(@7sHyz1Fveo>4sa z2-g3S>lDu&0(Z40ZeMzO+eMgF&j)}Rja+9m(sb`tr1bXbsxZ45W@yu!qF2CI04Og3 zYi=>BUOgx}^=)QTKj=oG&K2yQA!}`Xy!@1IW zz&VQbUe@e_pRBwrj-m{uvCEfenlMX{wxq9`=Ahe~O8JHznr4?-V3rVo0#G3*-#FV_ z-#y|SV!tM@p`nIGV(8V!P13z*Uf}3xT$CJLGwD!nOR0Ut4Ow2C#WR?o)+TFalV_&t zr7dDNG~Y%+fmeebv-tT?#CZM4sHvE8V-ppTn17y9R6xdn2h30ETC)-l3sQx{9jYr1 z-%&CRU*#q(iAaViPY?BQj>8|Pu&s>g+jXGrvw1SN?6Fv1n%4kry6pDp3EB$mHRw7| zKA2B^<^eq0Ow%5W;n0)jL)CFH_Ij0&$hAtW1RfLDmAe!O!yTiS2FGT9zjmj#dZbQ{ z&GpsEmZS;RQ;ePA*_q2$e`q~L`@^}s!4=D(jT3+K^X4*9+Gj|sR%k$~R_%~#5W(Q2 zRd%7(ZA~J(-jdk~Xqrd!GOVuhkQ5`>jt}m(zmmJ-00Uwu-^^PK%w;l|aF0J*CSgav zV^>z?aW~Z6)?=}tfAc8Ssp*Qj&)f~kDH}SM%9d0jAc^u z^Mp}Cy*9auDm;Y2Z5g32sZR3lcIz-K!?}=WjAF)WM zIxgywH+%Z{7){RX+U0R#kyjQMXM0K0c^C^^OU9t@u0OdhT2khajhR%tAYI(5J{@pK zNj%-;lWf@we1YGCy*(Ya4JZe7h7OY9S5ZKj_6PDF39mvYl@ay!j7ETt!ylV$sXVWM zKQT1hbTOy7B~@zD>c~~!Sq%g`eb1B*;-V4Nmm!(8G@I3YC{H^&{8Y_ISIw%91jApVG( zo-F7zUb5AQNu4FEXAsF+HhN0$6fzv?lH8L`8UfssUFuxaZ^BdEYf%hHN=r>W2fbn! zZL9w$)-3=2_3Q6uc;LE9X3L5UEA0A@kDc~*SA9yWY}$C68@nPrrn;+EKoJ8gY}RAH z6&)7IPYuVf%)k_uxK7|0K0P+H=5uH+4#&?>wZ^oh?@!)N3&4Ms}h}!qlJB z6;;`8oJI)s+UB4V(8w9hFT7%67NuD#2w(p|Jf_cx!;=L}!r9u+MH}C=PoI-t5caF5nlKMC+7x=}ib*28bg^FJp zn&bY)m)T|r9D~Q#h{Z5iEpX7>w7AFEA9L_Wj7ea%y(qoUC8VNWyw=F&P{WpeRUkl1 zV^~SF%l=7Q0b82Uc2*?$^N%q~dQM~c6{dF;iG~FHT@=7vl4(%9Jy)AlI3+H-a}{a%B!fNB)*N@RM(Qz zu#FUQI!IrWu_6k+o{>KxwnoZm~i|=SNK+6W$$PERx>uwi!##U?24MJ(F#*D#l zSG2JZks*;4m;0&-EQ(&%<5nJxpS6<1E7g}Y51;JmxWJLNc`*W#-j29!=$qURA0Sc? zI#Z=AEz5WA6q?kX8gQg!`;MRn+K*JqTX4mvuK$l^ScP- zl^JhLbb$}Oiw!FCw1YWe1b%ZyBoCzV75p!3c_SuDcJtN--KzBjUdx4Yg8l zHww&Y6VX}VE&-pD==%zG~YvYxNne45B~o%o__2BnL@*PutE z>IpK9D7o3vm_0sNXde<$Tohan1n-@cz)Id$haC|bGlr1sd#**78qQj6rtVy@$P*XR zyH&^GlijW-N3yx%m$Oe~v42f%5;UQ5D5-MK-A1bUR$&l+cA_Euf(>cfxu*FH0%eZ6 z64o6uyFi<5STVQq{Df3@S=(9P#oqO2JoQi9L;m4@OJen7#;=zr-mPjLJ2!c(OX@01 z%X3TYRmTVCiiMPA?DFYy>){=}>e{mO- z)TQdC<|6qrERqC65~PBq?#;KJ{Wpo?qQ;RDvwc{MI^Hyjm?hWIblqz{bb+a2GZ?|xxF|(2iUwWfJ8$ z?KzRjrNQloY*J%H5>5pI<{QFoa?6TxeIl2)00(t5+dBV5kiws>fBi03DqR`(Nx=J4 zD#22tn-eyii8KTF&ezpvB?eWxj97F#&aCi=Z`gO8yAZfLU)&pd5(+<9BZ<>Mc*NvM zou4OK&`(5lFjBq+48?(Zhx`;vO;A}nx_GW5y;&=byhZYMN z4G6cR)BoP%_Cvn2obz7Q>xy8NeIv66n=xCp}pb!YJo`D zV^dbPkw{2`ttBcMS$$qnA&jINUegeavB$FG7_8I~M4mu;m2KkBvp=!T0-g6}`WHDo zUvr2mqvB%JplbEVomwD1abMUQuI?>uykO(i9M&ERaU2%v0m1elI}$2g1}Q0AGZw6s zB!nS+!<2&>wHle`C&GMK^aVgXJ=*2aAu?4xRA}?po6p8K7RTG&VNyB*0q>oR9;=iE zuD|nqxr{Mhw7aLd9l}0Su!xqKYMCk9Os|dc7~C*Wkv-Bw-burky=bvMa?YP02Q@%C z)SODL(%Reg%q{7x_XPd1xn|y$-b%!X(Z<`wSZ#mOs!PJf`Btk^Jgu=+QJizz8L_! zXCsNAkE1iM#QNr*h{ez0DafdFY2#N*K98ZYPRqW>vq!TU=wrsLLo6w5%rg~6m`|;u z!y-j=EH(MWlRd0h-4i2Vj_syt{KOFzNX;h_aM7@=nv1H>sS)Esl%4vvvVQP5{%cjO z;3FD~X|I0&5VAe4&dSANC$J#{W$uygj}qn@)@Ts1e%H1>azaUr<`Pb9iF+eLBE;8h zPEIu=`Q4xl3VbeK*EA^%x}Xw51WS2w5vKhavWBOwC7V*&X+ciwq*ezW^ItZEX{T9 zatOgQWPcDfo*mPmT?)c3iE|0=^qsE6tKOrLv~_SKgMTh=G4bplGFW;AyG}l$ZLT%W zw5Uv=2QgF%j1Ao59@HIv<14nPoOX|_%n&4hLF;!dBY7jrHsd$rHFOz&5L+9N^m9*K z#74I(-!G@z5rx0k8D0Zvn*CsdTfQYpX|E>BXBL_V>Xmi{R1ZYiDzsq;#d8zTNAADS zdZ?Eh{h82N2pciR8MU6n6`KL$1`gK+C#1Zb`LH%9%hw-C#ZUDS3;Xp3$|ehwszYEW z=ey^%ML5Mt^X9LGr42rkCQ{-q&dH-#E*C6+z(zBkcg^cVMdaPyLd#=E)htZ}377kH9r{bK0XQAryOd z7}KQ|k77otto7T%EZ*yDdjfzQh}4i2Df-ro92S>U&^NRwGN0$415+}l( zDnNS~|4jz3V?c5x&__h^0u`K`c4gP5M`r5maa>L&+a&K0!=FKOjL#{9Epz7PRrX+pw=!CbCJzy0`}M# z){hYZvvFe+3M=ts&Z1W_(u~nfn}HX&*1dW64bEA^l;k4{y+KOV!ZGSt^g*`MwWP?y zd1muCiRcSb*lM-5aYc410(z5&9|ab8SvBRS948sft3Zd%@uwvtcdb&7QN~%sBBbba`G@tnElkdz3}cgHL(CPATp?@-m5PexVdt8g_b0z^-v8m5N4)*a zytF{TF=edj@R2EAzhD`Ok%QtG7v_%&^q1OFyL_mgDxFnUP*KCu(3VnCGX7Sg&WDPd zgoRbl7y0>te0*tu>BC)CsABm+s3EZn@6;43VU9Yg!IGa(>3C@gw_Y5eR-@p01{XW` zY1iG_y`?47g)cVS172t8^iA9_yQHPHnM8&Y#YEt~Ng(aw{4>5qNM^k@PbyO$%AHCR zIEkbS5|h(B^yI-Hm$rX}Z=o}If3f)sYvM`UbkF?Tg0gtSEGY5dXKBu z9kvvTTkA+}54M=L%>_qAz{nzs$QM*+C-kEDVNdi^=Y|@V@}HVE%Mcn}#nwQOlBJ_$ zkVR-wyD7WtTGR-XY|RZb)~zNI^=@FK$HDPA7S&R|9O^v_|8U}l^EaNOlmW0+^(BfM zXonP1G*@O+ofK#Dc&wrgs^3^3(z;L~AygUe`^YJ(Q`*z$8 z*yr1q0@Mcdy)S%_EIgypfve{RPD&E4MiC2|KKGUZskL*JGh=Hiym17F-)JIPS*bA5 zd+YUaA#9EaH7!$=F6wg6ew?%N>lNBV1=gp{t%<6Gp>RHS*7FEupi zP2~M}heL6Ba2@+h;A`Uh3wRiJtwgNszx>fnKGb zN|F@-!}(&!HoLq~`j#zr;)UOs*0xEpfnLADg6%7g9YvyR0Uq^N)^m;B==HeqNAfz19~^c~RN$9HSw~nCORZ2;L<1 z?i_bq_T8*ErbD=qx)S{Sv!&^=64t1qubyXd)Jh)RgVfP(Z$qv8u_$|ki%-3FBjamt zx~TI3T;syIE&=;sgpVrsG50UPdoa!<4PvtAO5WFzOrU)AD?iYHiW-|tP}Lb2QW*8_ zJZaRHZC?Ue?2x~%<;V$A#1RiLI*}U{j1hUXk=w3?UzGxQ^kAaqC>C=ORpa7=*W5%0 zcKPf-ots1J=kRg`u<~{1d&A48-4D*sUuYbZ*ub3=^*ZwP%8i?!Y%}GBOz|8AO5nb# zu`K`j+K*P7M?i&^ z-P~)`4i6WbcTeyP=XvYuZW0=0h$c@(GqSn*vxUlR^>2mn?f(4KhM@t7y>T@6Asqwl z=OrS-zQA85Yo+DGef-X-oi2yZz&S%l?aZ#!@&W7@S%AOPqJ`LMhsT1-YhRBYnUL9<~v?qa&(2uzg z$`;o@z){gV$$$EMAQ{~cfr!1{mSZt?tfC5|~_DmFwEX%_b)fOq` zZ>OjXOIzO@>L5@5`r&8W0vw60#vT!G9_##dd~#6#YtIX{g2}(%MWs$uE2qaE>_PGT zQUybp91t*slvACt^aw?UvZT9w0sgIiHaxsB&$%7EE#OUhmNk6K-2X1p0&@;f9}NvC zE1)8og2c^_QqWO>6Zqy#kSD_Q_bo9__M20e@W$WH<>^_Q!};(H`?wm#VI<9sMYY1! z;PtaP-Jy1^$u{}X#yO~8xBvY##6U7pQ!MtvyQoySWvtW5`!;@mhymAC#Lu-iU>1aV zHis7ag3`HaizO40cg{Uu_6^+?zQw%Kco$`Xjn_thCQ`Wa%sJ3g<$9%3>}gnZAi*`~ z%`0ro6$QK>YuBv~>un0uJZA_IqC>SyDAsPc2Pr+a*r_iU4r4M`qw%+E@E8Ade>_Z` zFP{=^Ut*XlHhKX%Shc7#vxxExJ7I`oH`wZ~4ZgTy(H0GNM9ZgozW~x`epg~3Si`qT z?eLaCFZuoAt5w-w06tOYUjNhwE3a)<4gfbSXe^rwDgB+8pxTkY)`OYXhA>fk58X{S z+NT%jnLobOC{AwlB=dyKM~!Qcttw>x2-+i_5XJ9ocw;DY9s{KiW2<)S5!(-tf2Ltw zN>BZn+3VxiG!LS)8W!99l~y!djwlFqG2*F5pjm?_9L;ZJqam>4VR~$?NMT+a;N!UJrGB3 zXc1lNuX%YoZhT@BQV(*Ta~1i2Y0Tg|XosUr9Y9JEzO}yk?=VzqnY7k>XA*-6N16Ty z(DQFyP*BCLe3tK6CM{^wa@y=dk2hZ@XAwG!GXV8{lNyFw?P)WLcN=z(wM7HJOitA` zeI6J`MEETMKSiai6c~2OzxtftQ>-6Q?U0}{9;BO8VCKlC$HNaauafMh&AR;?7@Vj` z2bU|Gz4=m+%gnZGqOuAY9-ikOy`E>I7jGM%hs(fqu#}yXoUM^;W%3;xTytn zN+|@)yB-UTs{G9!{8!${@fbr*gtU7#-?B{nl{j{J@umN-J_`RMUDPHOWP~FEG1D2M z_$Z*;&a0a^g)hvC<{Z%b%Fe7w%T>$?a@@!yCUz5EoE3y+#m_v;3zQ<(izm)p2Aa z?`p>iBc~5ckaXnZul<%@a8^`%#0wqL$9g(k8ccCc>e(hwl4 z5ip~`BhLUiuKV1->T)N4Dq!yIW=~3rgyH)iiG_d2cJ|-M^8a42Z08_oMlhk3r|aH8 z%wBM)<~omYkKi^GK}U|smZ$IJr|B;V(*|`@416kR>T;Y{@WzT@Upg#VG`>|!;sEv( zg#88l_LmrRhuGh{oc?Y>EDNH>3l<#8?yz@vMO)hZM!kn&?y`}(1%B=tPKZ|?flxZb zmA1_ONW)pRyt4r6cA8!nh@>O)_lTjjhU@9!gk+fTpx=8JJY6Ia|58yX05j_7>Xug` ziyAU!t$zrnFE0yCvqer}RGfG}Gd4l}qFvY;<9cLa$u&1)Pe*J1gnoPKw*gozBecs( zBo7(?7@Hr_jdF#A~?vg)zb;j0o>^t zlvx?dBHvi);aeLKnS@ibVvN@DyuO>gj!WbtOu?i_!GtAp&Yf&e=2*?nQ4)rgi1lt+N@VyOzAI`d}9Bi&@Wz z$a&H|NBW>W3zDMuAievp^u_0+qW0`Q^KfK`KY!NpPh=;8>F%e9tF+mDCVCIdU2`2r z1>C{e6UC<4BVDeZ@eY6DNo)Q(maQ*b^UNR2v&>rDYtOSnooQSvoLfF=sooNGW@GqY zZTeB+>v`9`f1x^lmC!7>d;g?{(fmq_Auov_C*{?`LBks~6@r6&*PB5lzGO=GkfT{= zNRC^z0EmP|Ltaf*dxw%cg!63=U+)LB^xfD$9JuIo(A81a4Y||Hw}|NR|3_E&-N`(B z^;Pv}mk0wNGb7H2@+n)$8ADFQu7_D^Peg9wk%QSeMa8>}kv)VZaXqU!B28K-&tn$H zH_y|t8$YhKSlXpM3nft9eSTe-ZoueY%1mFs%Z_{E@xYfiu%t5?AMeEdC=?vjag6Pn zvc>~ezks$ymPFf2UY=W7Wh4HFhuAV+9CrTrYtV%YO%R?3-~abJGZ_6& zvsFv&c1b-nI3@bXlD1)=WkXtOH8;u>=Z8OWwqSk%)<&0mBI9QC@sOm%e}SJQPc0kQ zDy(k6aBJY=q0=InT@y-D6V^t?XZN(V6DfKt0Fl{*TxLF>8-1aPfD;y#}Nt9yvl#^|Eb&W?qAT;f^7qL>|Ia zOnNZ3@6e}h#0xSmQD?^C$ga&^103(_w@mX6-K+e9F~Qj2`K#TdZLlxN;H8Gv?b~p? zcH8?rL>gRe8M_rKK{NJ)b>V31OJ;T}7oyExeF){K?@PKbAgh1JC6RgYCv5l&U}6Nf zoOiBM=55n~B=GRvIHKQ-bh8ZedYxMDL5R#6F)F-7KWQoKD;@?@W3P1Ksf_C1*XZw) z8DlLVAGy_m+ASo;jyD^yq(E}mju&(I$0FE%4=QWZ_r!%lZz7t8T8Ei<)C3jvu6&GP zp$!?ZLr-Xmesnm=Ds0}i{nfusX`MBJ=$pN>W`@+6WW}8S%%u6}aQHhjtO9CuESryM zNan*6F?;3FwK_Qvb4;+o7^#=ua|1SCd$a_4IaFfIV0LNCpK?!`oIeojiql6{jt^3= zGS+e}f@{pFFhbp)%3(vrk$ww)uZ@Q{O`gBAGXvS!Y@UK!UXV1$*S4%=cxa?5$#Sp7 za5v3VY((0+(fb`iK0FpkZZz!qj5ULhkVLRGoe61_@NFsAO_wp0SLyqKr>sSCA6J zI3#Zqfoq$k+x%WOnWgBd(-cviSEaz!H*YE%hU>nU#y*6B3-9%ZierPs)CX%3^=a_= z?hTG!C=)wRIse46*aa~o57&?7lml@=?W%4rzKp9GIi#~0pv?X&(}Hfq3@iS0b?z=R z&?8*e;E!g1UZTVx)1N-%yPV!3e>7uGDt`Fgj`8>AV0s1VKkWV|A1e{KVFT>8M_1N& zis4!Ij(`u56u5b0p*&pvWdv1`ZH@vlNHQ!bGu_V)_ryPv)|Ky$_wjETDMfWqF)jE~ zkJjqMV%xJQT*!pkth;G_r)?D-VQjX#Q;(IRi0~Yh3*l(@#we)UqmY_XuFP?>hiFp^ zsp3B1UPampzvi{*w~4X{nE*dxlreXfBVT7wItCuAMJU>w{e3|S8n>6hd;)-Hz~&W`cs;rr+)U zn~%K-)zEW`A#IK#tx8%O7ok_Uq{339{?9H8wydy7ll?kX5~wkF86mM^6-lx1c##Tx zxaw2 zPF`FDJ!XG}{ZR@Jxdjo0tpandQDH5>D0@S^dcRjL)~vv%FyHw4px6J=_V9d5qO6c# zqng8SDArY6$>{#MbxwP`g#Dw*nLTLGSnj5nQg`0}`@GUGz>${jo$+61Z9D3ksEaTS z!vr=%L~RZ*JN@XCC`^)K%tmx-a(6Ro00CmIIj`i8 zGw$LIO-S9&VvkW?9v#qD)qYp-dJ@ulS|&D!txy~Fe!7!CVjeGFyh_Wuo5F4$A&CoO z)V0&JuL<`7Yl1^`n5s0TTTv+@st0PPHV0ysaFAN%=V2-w8cDm1#Thn1ub;6U_#!@2$L_vCbf^`+qImgErhGFtk?*nc&`;@gJ%A(1h2l zwuWD1wPY6o0Wn3%0;4)wMDeR_Ix~;t9;N!3($+D3ZM;Of>ewwwWdd9H&rz(1w^J#% z$GRZ{gLLq{NsHVWXiuo)2Y*yNk8uwM0@9IzMFUxF(hh-{#AbX;*u~_f1QJ`Mn(gYm z^~n*@2U~0g9-~qw!V38!8>F^gA2K_ZH#JMka4hw75J^r{L)JdFgAO4`n>V)jQqy#E zn`)%1uQ^WE?H_=M0rn$bZh=M9O!#cp;?LATeI-i0oGqTi0Ax%PYC1 ze7u*;SMSEIeLA2|-E?wbt(>}#*A5oy=r>uYd=irtVV3hwmgFeoEV~XgEy8Ky56|ryr5K^j@gUIJC&IOSX00 z?;++>**p;^?{bt)n)3>D%SNM!PW!u*@LT(X*4b(n8^LcKNl|_~#!n-J#_>H$oiw0v zqBBpv!VtpMsIeq`0<(C8wo5f!MMWO-K~s}`MhS}ATP|^+5B6mr3jQQz{5ey_qai*u z`PYJhk~~#u*3cB5tNbvzGzdnN#ZH2T31Tiq$OjECY(171P4_O|_&Wj;C4%NSnVg5h__i*Cj&a1wXQ!2V;wcb}$S{ZU@V@@lhz|LFnwKBm z?T48^*5kEbC7wv=kp1E=Mp_3u=+}}At@Ka6yOnmN^rUX|`9Uct9ahukwo({saZwjV z8QM9^Zf^A@KLcZ;{e!v>&rCJYv8)E|9__uO_&0|lV@V_*FpFj^J`ixE^R`_X_+_3p zGdIaGyLa8JIHVH3n&v+aY<_EAg+-57H$78{SNV|LVEj44Muh2_)uzxS4yx}2a(1T6 z-WVXsA+nUF?5yClXzN>8TVo{=>#Aa*Pv2jziL!XqoMjNqa;#WP*T|Egq)>~&Q%2r>4Gii1O#jxgn zrrvx-e|ucM2ML2Wjw4!xJkmq}`K#R4-beb7m?rkI>E)zSnlQNC?s8Izm7|c4Zh0w9 za*Dc_<&BsJ_Wf1guIpssazr(yt*5U?uaZg9_k01QqvwHM%am??%gN|(V?k!kU#X2H zMfDAR<5A>DE4$+bm!8Go%sj*d!sbyqk=;-1m;B|e>+|SjB-&{iFdC!WG%4XF$Iq5J zn4dMpF1tZbBoZ~E;?SoH&CJ)9iqM8X&B4Gi@@RQUJ#1`xWLrXf-uM|kj)SB! z)eMk!+s9kgq>cMEqoFki_4y{d_&m3R_I@O*Noi@4fDiN8_W=KUxn-~i$@l&5=99DC zRD_-Hsb>5Pn|(?rDcu9tkzX!T5!;WeA&@eCq;AN*slYrTWYP4^7l6HSk4xPj-pNGdrGA1~4n+!Q=S z0MBHF>-ebLW}igh^g+!-_ZItDZH}71Y056sS5H~lCcW1si#FEwi_=gzG)w6ejkQge10HgmPluAK)UvAHh<&3)KD6PU*cm`j2GOsS@#~^-3WWITP}Q$ za~>QahEpuBTIcC~Mmgk?`c`Zp6(Q-;Y=6h7=;M0dx>Rj@d_?dIFi7$3%+ve4{hN9S zqQ>|0WyHl9<=`FT_+L6f&Erac0hn9Q%FbaFci=AHp957BFPFW=fP1|U0;(R+zdSrq z=D`b5PqNv0xO!f-OJ4eVIx_q`I4Ug7Qt}r7AaZ^p>ReV}vVI!x2AZT_hSZY<&J@y` zv%~b@sy9^?u$GlG&xK89GLe9_J>?=6W)>`7jWU9m`|4iZ8*wS~7s$S=MP;(2zW{xR zC@t-;1&}Av6LOI9MRU@#Vj9v7w4^^de{-n6!3kJmO5Vk}d(Fuz zmo>-}_#*?Q4(-kVW?=oVW`%$J%V*W$Luk(}D)WXf=0Y}->9V^`V&0m}V%Zje?gy#Q zekVzuB#aNd%3@a>zW^S%7juVGW)r>V<_-qEhpupVyVo%dF zxboApdY|V7ty8!vYQXOaN6czFjT_Z-dzsc!D8iP5+3P7XnE1J|d!X~*MRzxIx+qqJ z^}joR;uQJPR~}p)7m8^3`4OBIL671Ml`}vUK4tnZzJ@scyMkjJ!FI<`D=Jp z8SH#w3sRAEIJ#QkjLD7NtwohfsyW?ICiL!W^RSYQ^VR)>^H-<2!>Y$ImD1eeQVU;W zB&y#>;fFb&2Hsonn3lY;A93!w9OeJ^bJUjqI929)!dLgQ6gW}nD@0RvJ00-=S`)iA z)Od)pZK)GHA`rXU_{-l=ci&Gp@*}?h@Y_*qzWDh^2*D&oB}2`zvd$6&@>z?$AuTsP zpqZ#UyOMMC+im{TtG8e8R_@jhbn)hmSqvF-&z)gZjKj^Q1A0ocGoUreZ#7F z=O|;q<*1F0&-4zRd9xv<4Q!7^lKlG!fh0nSh|)@c^uAch!k&x;cel#r>C;>Dh!*Sf zH|BPvkLCDP<-Li20d9i%@F+G|0?P&CCI*Fq`fLfeRQWgtC_yDaYh1c;%02ok*EvJE zkdN*b`IA8{>A#Z(#**RCRf{=n=c)!0y`ljlMamhS zs%^0kadpA-e78-L=us)#{D`(p+0b*iWs=O+myBU{`%`nzGPe5nKl*`m+}Cgc3=5~* z``gc2%3!^uf?t3k=M$j;e)vdsrHfVIyJv9Z9t%|U)GqCjTPb3?d__Fm12=nw2(DU? zPOl>JKdk5TcLafe!0c{qcX~lJqdSH8_flI*^~({F56q-%ut~&T)XT-NI@C)u0V}6~ z9f(W29GFJpGw60}ii5VSk0FRmBde+VE9>p8Sa$E=x|#?u;>8eg?LBJQmAK3BPdy>fLm#DK)1*N>)Y`?l z+ZSC8u~smV+tS(c4Ki6o*YMNm-u2ivdkrO&(q-J4 zfNIUfs{IcdS>bimU(*~G4F?Ux*xOub2d=EXw>KQGl)6M~$rPTI<6usX51{HLqI8?NGNmUs)W<*ON?KUzLff%1>dZ-DM6o1U{?JkL z&B9$Yv;j+t$t3Ih8|s&vRKXewPlclq#g=t)kugQG7w~+E$?;ZIF%SABKbe2O=HUD6 zo;mHCei~5wU4E_^O~fdkKm;Z@X2}SLzHxZ<@k$Vq` zBmUdsGx97J21aB4D6?~bC-cM?LjQ~u@}K=qfX~0BxcGr|_KaNcsO(< z-}5yC6Ye(&Y;AS;reRWlH$jb_#`@lPpDV{5Rt&`V%@cxl6pg5uc}U+GTu$U zvJSABO0tWu>AsAyLp1)teu-vI$|Re1B|#DN$TF26Ywz}6X7tV>5*%u`2cZ5wd(Mhc zJya;Efm0I41NF(J7TUb~xa+aA^PHB3?8E~8BxhIv8*aX_6L;_+;UJSDg!1s>%pd;R z(vzn%Rf*@M9>&HPgkKIb(e&qUU`%LqS-UUbv<8ZatI*~piN+Kh2YT|v-Y`O&A4z#F z4wzE)yE$7ujp^w{27Y1zHrLgvxLb?p73G4go)oHVvQgJ|1TE%HTQo2<9Z}^ diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/trajectory_comparison.png b/doc/how_to_guides/pilz_industrial_motion_planner/trajectory_comparison.png new file mode 100644 index 0000000000000000000000000000000000000000..1a4d7545b9efad73edd7a618820c8c10a37b2f21 GIT binary patch literal 79668 zcmeFYWl&t*vM`KWaCaHpZE%-Cf@^RY7$ms6y95myToarC!Gp_#6Cfl=a0?b7f#B~Z z&pGFwTkoy<>Q;U4zXL@vv-VoOx_fo^YTI#|>WWwx*?nTqlNj}+rYv3E;(t+U?b9@b=}5G!jpQQ zi8%Yb`H317thG}1A%75_j4IXhV?na#A@1igzb0)Jx)}Z1PvX27&3&q(zU#DUhNj=` zrEJ)!H}L2T;znNtnYDq0rq5$iS1TLpWfx+h<_fbo#XbzPn>X!r;k5yWdH+D^B3 z{lT9w5;8>J)jB;M2^D@zy{C%Jvq<6BEP?--L6G}wQ*|^rWM#<>dZJ5kN;?P^yH|fHdWhxsD2i4djjMhGvj|R02veiUR4P zwa8XuGi3$Kq(?Ih4QaV@3jc02@N#wgywInIizFqzg3JsdVLb~`E`}tcj@+#;jqsgL`($MoYC5k9N@AC;!3ZOUnELi6DBbw_O+RxDBFuG9fUSUWMJDc z>d+T}lHTR2U(0^B%D5o5t<|=w4LB!JIKLU=TeQcfkArZ?grgw~yw(bPC0r}YO8lw0 z@W&ZWdvKfyM*En>wt+Mex%DE>18Pra3r0GDnKlD_q#5O&6(QOw!eqx*AdQ&%1rnMh z;tT&}b0;|d!m`C>qa(EaWfZQu<=pqECMR$a8qtnpb%bTCgc!ZIWI;OEq;1IlpS!*p z-3kZ6@y+XfM-diA8jgS6eR6SfGWG32V($AXsu_lR0jk=k7C`WP?EwKZP*WAPa&h9a zw042QxO|;l0m%bIP|DZU(#iqmNehM9+B-{tPCI)*wD#5#pcevaJZi3TFgtrCe|MOU zzq+oKzk`*CHAqSlL)=#s0N@1kw50WQa&-0(^_2kqfh!7pej4Tm(f*m@=^z0zP}8K9 zb8&~!g1Nw4Je&|;dv89FBnGXxyS0s|w!FeWKmgw)Kz5#{IW+%QL&6EM{S*p>IcZK;+ce1pFal1O({(11ka8VgeWeE@;7teo^c zm2-z#db+sly0|z>fSypIeOmdi$7+B&SzCHq%3FHE0H8d40;0TpqC5h+y!@hIVNrfQ zb{>9Fo`0L~Vr_5Z_y0BfNqK0+|2}dhdkVEz5b%Ffc+76w?4e~9Zp$L;?IQ2;~v1o@#NBAmj4V17=pr6rWp z(h?@XY5jDR!XjW^;DG--bPpFBPajKnn2asJM}Sv=c>duPEz6&SV*T&4ee7UQrvNaF zlb4V4|7IBXKM3Z2vKjxRSe*O+;)(d53IAqffOUV50mcikh1~x#hX3H%liB%y`16mm z_Z%{I4eeN4oyQuKyJW{#TR#BVGT$u?yqB!YPA(oOtCFDy9NaU4r$2bO+&ofX5YJdXqN6X`S+1Ku$(59?}UIu$1^&iE1rXSlX7I3*6``CPq> z@zpFprNFG7n}zNi!?#qw@?+yyT%0rZ3Ic-Hd?a@^hZ0yxF;OD=EOI>7PFQ z`EDT1|Ia5JMP&b+Lp<}(Pbkmq{;>`v0vY@_1YiImR|?^O9{;n)(11sc9U}kI* z`{VwADUa(mNRxVY#xQAPio&2B8p73~(`(A}TMouUibM4}frPsP^(;#2;Z%%84VeY! zu9>-ZbBI?_|mfeQwF%uatg@`YIZth?K1R+A8|20=B7hA&#Z(WAjry?o|&M)yQ=6S zOX$z82nOYi6@J$}2@<`aJSkU{2sc_c3(Ea-T{NGMht`4Dk1wt65|O*D`&^iR4?NEG z?>xSbHhy%%n!Z=Wva00V&qS^#D+O;O{vzHD!Jbd15WbFqSD;bBjbYuD{Mm3LgX}<~ z|63}o&w|oF(ae=c#Hu*Bf5r8Up+4RXI$NpeCqlawOrCprbZ=9+^19L%QaUw`uDhP( zQbBu*-*4f2GKxef5!QZME=dlnXW)%U<5#quu@iapxbyf)4(*qs8$F|Qew=_x0vzEe zYDG-GzZD!VPzobd(!nY0{@OPlBysTgUQYj*;Rx$>JU3)wl;cm4-O_qZS|ZERK1LiK%(iXD!s-d5Q*p$ z7AKX;+Fo-F$^X29BOA2No2{Grr2uU+VqCF-CVo1-iE?Ssy?<^REY z-v>XjuyMvP&f>N17q4CyX0%nL{0!2m=ZRpoS$p{g#g0g7VRX?~Xr+~^(g$2}vIpdB z(X}Of6_VN%l~Q;($zVK5Zt<50~!Wkj0GS9E|8olF`VL}Kn+o^<1u-k#lO z(GW_Fbon;AS6Pd!`_%di8v=7*KeObKB~`GPLM|LY*N}tcN(*ViVo+lKhnc)n{EjAk z%Z=RRvFs#udIkJ)795AzaKhtqv}c9Bq$1A!EblanXw`JGiHMZKHt12t2FN*#hi01L z^{#$wKJuY7ed^|N^;!v98>-zv>3Smo7s^X+ag5012B_^1fUN)z4ce)CS$wXE;fU*R z4Z3y_*?4%Zikm2l0o%ZT!i`=b?Z7J=Akr~i-us1&;IAO;kGEkl&x6pOz38q%5p~5U zg%KU^;N}+hn!9(-_tI=2GodwcU zlfn1WeDvuH0-@@k)T}S{knWr8F)9GmyRJ`pQM9~zAOHRLjb7JoU@S$?cMIsStdsUg z{*{UEGn9%#FD;72REFOCE6PZA;tH+~;Tv6aWlRP)3?G4E)W@a4ePx0jODqo>f3y`O z#X^qK;7`){@NU@vCwSe#5L=P(Dt6ZwR)34NKW^Ud_~eluvVpoRcsS*yS2EA%>e3s1 zS4WP0Op&k%S}Q3T+~Riwk!+_zH$FH1&P*0|cil530c1t&w8Nmg*wWt`bFmi1XpjE& zOF&H_9+HE=N?PRSdPMXiSc5Y0!bi?JT10O<5UNW+7}}BQ;b;6z6Ymiqkk+Y=n)P`P z!RG_3>YlcY;m)iEx3Z||8a}H>Gs+D=!@_sFB7v-fV7GG;2iG)=E$SS?Qj!K{o*?PABqWAp04oybNHoWAqL>$UJCng>QE-YT~gf@#rwLYbIk@ zu`(HlkY?vm6yOfG zRslBrzTu_EI>Qy!zO#oV8VSnLNnw%9_yOry|Bg0aH2!cXa<4ADZfM3DLLCMNW9VAE z*1N=_UvV)D&zu;v;#rht+o*aC6Wq4rw1x0kk1kuwSpQ+cL5YPbnq&f6REHlqnrceA zNi6{*ofXm+EtX~4=7BPH!mC?t`XMt;JizK57Rwh`V^;Eriz(7@Z;FMNM2v{8F7S(c za`T1mxQeX$wungVOq*|`TH0~-A#z8|uAiZH{;iVJhG%$f=w13gaa#O@*{nq@((fuP z?f8zlxb<}-%@E31ZOp2m-_KAKG)R9eqe}+s$tC3D0(5KegrFO=o%pmb=;N)>WN+5U z+f6FMP1K_Qw8n(9SUfSu`(pR#O_;g~Qq$HYqDXKNXz;I$8+#i)d<>_RviX~T2X%Mz zhL?wgpENPXSeiio3UOa_+8#sRLylB`xKsUtSOy`_;-+-JYxP*4WA)Ma&Iz%)Nez%8 zqR$bFDtqRd&+~XazbXyfoUFlgu2IVUYi|=mFlIPh0gQJXz zNrUD3tHp2S#)X(|2V;{Zs>k{~gfXJ;3jx5!x<_}cjE-mwPic6`TQAgng~YGpT*IzV zTW@)Lk!lygd#&})EP2MExuT|8lO_`uJeOq62L}f|-?+Ie0_TT*pd-7@9M3p&E1Dua zzKR&4ko@dy$70;Ms8OL$+HwGv3gb*OO^FFHle za+V*aWV3x@h+0%HqQH2WE?Q+J>Zv1R%NVVt?RMuwBz_}++@ct0Fk)=bwkww~ez*3Q z1&_B+3>+fK1EQvsO@BjYH;8^jmBZ|6gNsyCwDa)O%lN)Om@-~wAl`rNA!pGL$Kt79IM+9*1Am0aJua?h)yv|Q zMbfRG2wXq})35PjSP3bv9By<~#i7M~74&M_m}(THxu5WaohBXviHJH8_JUuC13|$N zcu?yb*vs{V9*2ORIQN3?WJ-+3;`G45n(L2$wL_A=l-;wvzJKl9_FxMbSSQKBBSsRV z%8#7o6w6WC;wURL(fdKrt(#hu{=qOky^U4^`QX;z4ng}~7as~&(O0CIwV*g{IE>G` zvU$G4(T4h#Uog7#!*@+$0X*H#L7HSZjqW3TijPJ8*EPeBwU{VYiZZ2L7Yg2pg+h2I z%zxxgj=N}F$26^)h99si*?|-NugqKURFTgos#>E(OI2ajAyZCH%KE^$z*W}LC%F~nZl|m^u341)k99U@b z7v^vn!AvO$rTD`nX}ayWQkwJc-~d+H6)q>c-(qMpqFyy0%|@!4&^mSD$Ecmvgn#7n zPQ+u>=fFMpVcYzHhp6?sNPx!jmvgMn^fJ$LHcyqX#rQ^VjiH>iMc4Ck0lR2~p8WOi z)#NL0jv@*BF2sL-OlDBle5Z?x1RqW-o#r`$i5OaUh!zfKpDU|(K_%32dVcQiEvYtl zbO}~#Iy`W%UXUe(uw*=sEkU!-?dM56@!bML(impEsO)p0zP{N#9K#=Fwj?MLG@60y zW7hEG`StCsuJE2{pZt zU$PD#F``C8X-09{taXc6QJUKlr)rWqvp~XTsD*c3QN3zf?+#;22{A%v)Nrp^0XM9{ zkw`OC7)h4cH(|EHuijYsH4u-gmT1f7uz8>GtMeiE}_l$;Aeu88bwvzK;r$;jW}1uMYN^$ zv{kOn@PHd-sZp)$B5>)3t5-&}vxZCN;Mh%Ce zM;#~u@)2w57HUX9ECc;rlT3?-S4TPZg>lhq_P{gdm^3=I9lu~tMvIU%8h(JsBA3b2 zGzMmNwGu1HWD+Dk~>{IoV0!Tq(6w@LPC^EW09(7R`cGVb>p3CZ(OO z!XA`l)x7K!X_+m;fH`bNo84-egd+U-3j+?hHVW;DS2cOQcHihd&ZgWN4?A*7-!P!- z>O~!P9JYP=;AEGZiEf({0pqF|Z~1J>l8e1;OqLy^oJepw7X(%tZxhCp)2-HfTNN*y z)Z{L)3myJQGNT~SH}N<#dBK6>6QT=-cesp?xu(c>CfFE=)>Pb6!1DR#)c{_M^q3BX zdNMl=S;jM{OT3u1P5V8Tfe z!by0L*=T&MSx$XDq6&K(S);k;8l=+L$b&9Cznlau`5&GXsRGB8X$*fklOT829mZ~v zDyLajT9Sg)blU31w-?8Wk&?4hU8g$_ub)v}bZr(>+UtdpHGR3^m z(<`&@n8G6#Y1d_|^(angGa&qEV=^(+9JFaT{@%in7@$ATWfQhUGh>y;Ad_1GsC2X? zEgC{iT^+E~E>wZ*5`xt%=3;SXM3K>vbe-JoETxFSVR9&l2wXUBM|51gO(neRC!|og zR?+GoM%Y~y$o2Ws@UGvHDU|d24PO;kNjuQV!*oYR&$v=?Xw(`#S4Z|)2^?&fm6nJ% zd7^smTsvv!=H`ThZakUd)#e7{2$&nXy7E$?xfN{zS6p?botX<=$TBGzu7PI>=7XK5 zAK!@Jz`dWts#~}xw-IGbRo@d(8yHF;IlEkTv2B^wB7}!aW9UoQkVMzhbK4%p%M*4( zu+OdYC>6`cUOEnpHwdm6wydQ+P%L1?6Ep&%m5v5{f^5|9$jo1Wj#K=`n+>K zz+RG*K!dj9PG+CGd3SvQSgCStR%5?Xy*99#+ujrvAg0wX>TMJhagk=gSkscX9G<2l z0jJ$D4A)(50?7%Ghsnsq!GVvbw$L0^bo>?NwDm*tN6~QF-m|R{{w+YL0n;m-w9&yu zIU+*{aWy4jXJO1yr006-k9+vH7Z|eWmM%)I-C`bdhT|(o1%%_ z1=I_~Z6~Sie^1)&5VP@cD_XUT9G*HqG@a z12N{tw-{=pESzcEUXv9XIXO8pk{8u_^DhN-*@yt6n_;hsC~&r!9Q>0W80)(EUd^LM z0G!RL&)SfVhC~!|fiJ>o_m$ajcIpqUf=|urRnul+o5{lgvM9xZ z_Ow8{W7tzyAt+KE_0^iVcv*f0D-#ow#j>};=W=cIjOUCV5^n>6ThuW}ebKAye2o3~ z=hlx=ry-BGZx>$vUhcU!)~#Mhw2muN4kT#QmM|~4fQM@_a>^e_tzexhkVvQxxjz*4 zIWf^M!Gmb+1_Ktedsx3ZL*V_4`oIULwz>rW?j*qeM_P_L4t?ii?k#)yr9jf#v=*2U0#c}&;30t^f4^tIxD2F zy8a`^0MCz&7#f>btI+SmHf`CFb#;e;r=uZt58f08CZ1vCiTQAOqy()g5<)cf1RQwk z^{ZVeQ2|nygL5l@i!|doGCe&#aJx>nz3Ka69-(Wo^(6`)aD1Kbs$Ml7(2-tj#XP7y zKULpIr>T*BSKnV%)lkJ&@UX;lRE}1K^1BwvnSb~%TPM2;Ajh&^H)N2H#d9$t%C@Dp zpBY|`^BU1S>qV`86QgXSG7g;M^3?a8eZi{M(h)#*dwwVMgqE=U;W3WnZ@4UObAUbo zrx*2RlVjXynXrxftF;k8oH9}?4YGVrRz!eRKytPJ3drxx>lmu>$9YU&yr+sgz5RNT z8k!-Vdt#b;L?Mq?A%$m!FvB+Yo#*<&v&jj1dQqph zzL#HZ-8TA>?Q&73FZkfqs^bCKHk>I*#T()EG@V{?--PkjDo?$(;knERt(zBkP>9b< zX~DB_LXr$^_`Y?SD&Sj-v_nS}%q#;)>0-PV_2;5D7%ASU@ULS8@`BA`mJ?_FMEZ|? zGF|U!s+IC1z7op7@a9QnPx$a?@|ibO87bv=b=eii!>1*#C<_8kM9S=Q+X+0)Jn6X1 zKPCeFvB?@@BJnrX^-$w-Cyh1?q&g;z&7K2KetXtF4R|HaXzhDHskdP&C|1n4lUQ3f z+^4Vz2%N=PZt`a!&*IYT*6hDI6QVFNG#XiLNtzS;fy2QROqD|laVv%zr29LNYaA-|jbb$^Baxs-gi_y^161muHqG{hz za*WnHAJ_9|f~v+tD~i<4U9)}izX(HwCx!|s%rc%c8N90rZ+k&lT%trg^mbyzS{ip+ zrw8qfF$eoe7u&h~uDD_H8c0oIc()>q`QZ&nMBs*Nj9rG&P{OP>tZCzUw0k`8-W0o*ln5D>cP9)0)}{a4Ae!yb$-fAfic4&XsgHxJ6fTi*a0- z5sg-;?;0#=W$t}j4-QA$@lU#JKu2HhHh4&Ecj0o#7_{SzA-pOQjGKil!LW~+Sm=Bz z@*c8;&7M+xU_0YxjBIqOK6@rQ_3A|McGMu)jj!AL`Ol&X`FI)_&t+67b@#f3`>-rb zb(;JI+*3LaNRzGl?P&_sIid{gpci3seC$Ti^WpJcl3izt?Lta^2*y&*2JJJqatT4=WLEyY@$9?;%^gI?c#LKj_MSr#i^~jY*Ui)R)kjz`*@2OI|<% z72OWxHrql><=|%0sx%6Hr$8D_vEq=Mt2E6j38*$%A3tel--wk)nH@Jo3BC-yNDaI( zK{hckF_Z%@y=h1|1bt1JgSN?fR+Bx+?aqA0iEguL*};+dGDV5l&k(E^TX=9*@`f{O zUW*OC+q;7!D;Eedh^G_p8H>;f^R1WIRE;69=36;Y$NV*%Z8Q$-t?!Q{{T!7%BeMJS zl1Y-L!zG`v9$dJh0apPCgLuX;*sPek^b=>;`y9O2Ih)tNt*o8Iuw?JRGnL4(YaqTJ zxQ!cxWaV%rfQ%U2+$H7Dr|5mp&VDk-o0BuDFVmM0JDk3CQ!qKHS$OG68S^+xCdO4j z6T&!rb^+5J?yynlq~2((*FF0tOOS0#ZNv4ja#pS&)}bn{a;KC9n=2i?!@V{j-Wlxl zd?S1(&oxAlZ`0V7Bo7XClyxld;5zSQ`SGqS>HLO_qv(p#-BUY&)rcg2kn{(fJPoQW zoQL$%ncHo?08kVF?t*5nDGeu zf(-HzGLAopRruwbAVBtZ0$)|7wf9BPdW8kGcMWy*$&(d@_APKGr z1Qp2khHck61PPVKnpj1_E0I+QKtaRznAC0!s*DzNa~2n-4O3^Ox!BJnK~p!$S!5L{(b2BWV#DO7lk*C~;W`=K*I2LgC_32Hn) z4Gh<-tK!|;6TLepVU&rcy!;5v?NW6e3F@U{wA)PeD10QPVnHdQ7|Wg z?AG@6)vLmxuMGWD&yj3J6dWW6pHk-ZbCmf%X_YAG_rV>LoYh;R&s%W)zYcv-Cg>=C z%4F=vhAl;6uWIAQnDV_WY;;|9?)@-=2fiHXQ%Pg^+AO2BorajU$2a=R+YiBj!TRis zPo~noqmEV6gt%;Z=r;XO^$M?ae_yZ>2|~C~qM|m)B{;`JDmFaifg<|K*@-2?71xHl z9WG%{ZhD9ikxlR-4n}V6tvN@9?j*u3I^8^~@;N2yy<_;Oz^r>j`@|wc-jIT9BT2OW zvmtrx&EQQapm{;`Mes#l_HPiMas9IwfHI>|PyAls84yB;toCKR2vT+T{FKRSQUE8~ zdt3i)=wK~jChwWnoB1%phL>#7m00`H@xrl|3t%8m&V8>(WdFUm`^zx1)C}$v)~Sd+ z$-;E1j`UQM(zd76SG~;qHE|L-!q4xEnEK0iWK(-#%n(NenxRO#jf?B0JKWwD}6%N6?*k!!K>>*VOp+N7B6y=al}Y;%%ijKIWTl*Yl*Ou zOVTj?V6`uTJPX>0)Ck>XGDgP-m!a-4RaJ%r#S=rXnK`qvV&yDI6N4CwQW2_~WV{O+ z5oylO(Hg|VGk5!4IM=s__=qLXEEfgZs(BHFhUN*FfUI)~oQ>g7oGm?vnR%p--|2Jv zwU#2LhU!read1j!@0)wc{Xl2GYcEyW2Amfd*(=rQnkP) zKD`wJ9Zo9AOWKIz*8A~uu>&;OtXE^whzHGl)C?09rX@`hq5 zE4okQkIsUUcd>@>hZ?g{IZssfY3VQrY6<}h1xCr+IwHMQkoLITKaous*CeiR+vyQ} za%BQ<4sqplfLwmIrf&IdC7j!9z^(S(Om>J3c0sOQ)Sc*lCV$b{$v-)cp0RZ#&n)BE zn|_#kp(LUqpK#KoI`2N&^xI(eo;Hlrg_#?V;k0|SB^Yx!>Dm4}+_;U+t&qddKe){< zv~rR9MIIcp6B^Yq$D^Yh8AhXH@`4%8-BK;-9^=%4{kk|3>^t%pls^+HktYnBrq4Ku_q`t@B7mv3Vt~I;H#mT?3G?)&|e!?Y(Q57&3)d(?Je< z)qV|qN43h8iw5ap^KdBeog(-G+8f)uxY1YolE5C}*Mz)XKsGxu3&xVcwVtiQB%TSt zn4(^#(4BXqMb33WIJUYl2;!2@g|n(u1FD$-=5dM~1{o(7Z^qhC>hmp5wjjP)-nL}C zNn2jlocKkmu27S_Bkx!St~6Jv*nU9`Fp0=QNjlwUm4r&aIGUfNTCQ&@;ESGA8sB{q<%0;=)DJb zF&DOZ>Wh18H#Kop9nv8Yq$iY70F-I=P3ku%AAR6~Ysg}|BTQJyZL{Rnc>@Xr87v3E zhwzMJP~Ug6We&fXy;F@4bD=#r%0raJVr`C8h-4CM9MyUbeWyr`H$MLAUdea@pU4Mp zK08hE+`TM~V{nL%VD=t2iv@;iOu650;V3jb&6pFHidujX(AJ(kMlN3}Tcb?uPy$=b z@ogP_z0a5iQO_J|6km}~Y999}-#Pw7OLQhM4)fj&ps%yxvVrg3TR)n;4|9Kqup$}p z#(}*}qA~hxjyNfwd%!TR^J|$F=A@=&vK^_UcHaaEQ8NXeq+e~^vQ&Q(o)9Ox_Exm` zrk*$0`h_ghHs}+(5z_?0JR}`8V2JORyUAc07XBji0*f;zzSNE^(TT*FofqgP0P5=% zwRKxi6c64U;%Lj>_cdN>D2J;i-}KU@zm(d{9BSUzCxPXREvM>0 zM%`>ta~sp`x@@h^;sk-d7}4=BJVc*e92!LaI??oK9F>8pHMXTO)uD~)ya-s38&5Y6 zSa_ZgxRgK;P#zR}$F31gG!m0gT{JlD=PU?lVqK~EC5x3y(TDH9_bXNGI2A}mY>GrH zthV3A0b((rTV#iU0QeuxNuN?s4t)ufDdy3>GB?C=>@7q_bbUI zu%WJ+Pco4;!Y@q%lY&$IL4#L-5e%nY4^baZlFq|0CR<2BaLu%uFms=6b1XH3NlH$b zhoZaJll`!xVs5>63yf+NduXsqC4&)V~LrEuWyTEjRSJX zAk|?|LCq>>T)IR2Ik}x%0%bYIX?=`5UAKQ?bxeZQ0GDj}1K^Tf)1)_+{xCw93~HJ?R#Ofe z4g}g!+I{8b--ruCs0}h~O&o_gPi(D!`X`l05?yy?f8~}+-q#&R#RqbtwfYHjR3XgrHFX*6 zBj%A3mggFYkP?`-;fl_>6lWnH>BP{)P-owe7Gd9qW0MnB_u#ndi#ER$qCT}CCd3+) zPxta8MkZg!$HOzD1ZuHAHOuZo0ecre`wV;PJ|_-H?0s)by3~H*>8TIOyRib&{rz7{ zZ{Zo6!l#2*WIddbfu@tUG(uWZ&iy5$)wg$F?FRuRu-MHYCSHqQ4>St+5i)bD677dh z?AI^I?If2}$PQXFv;O9=nL#PlZqfq2n_Kfwiu6Fex8tgK zWbKn=|IeS`1~?8ulWg zZ|{o$BNO8V_tc%07)hLY?EpgH^`+UPgu~8T@(HokZRn<1j)QV@eETRgy?E3CDreS% z9syCNf*@Aipu4@?o}x%&#L+Cqmuc)X4qRg>U{%QlaGaj;ogVI2p=N^j%%o5G23Uun zqy@Z*hb!XE(LO+8^LNlR?zFJz71gBSE#QNhhi96@;+Uy8YLU@i2<;W68C2x1mmGwb zj83rc?F%^lkdeI=+A1LQiX9)1+Jw35*_k+Ni4#7Z>K9HfVx1IuIk|0KEt3SSPmtXK z{p;4)^jncxQ2nr5*GcJOiX=G& z2Gqg5-z3C!+Wpdy+|QaGul7Ip!U1KYno=Fu6SqiARJ^&*GenZo1j?reYH7mZQ8Tybno<+~`PWM!o&6}=R7A@7& zUpz#MUP6I&1$(f{5(l}gnCNI8@d;i#RQM;AhcJb&^l~uK&H6gH;UC!yx^nZE6dF*! z9)XP*a~!acPjYI!CtABQbLTzd>9%pRfy=L4JoWq5aayKd%}XPtieNN2mXE7AmEpSA zg0#R^PeM(4^3V|8Iig?u79-Qe`>y~XQFI@PUKVPoRZNDVF6m%(y(LiAbg%qo_{Cl- z6P|Gz!{N*D1Z`gb_Cfdj0@Y^7AQ%1>tvr|5_<2wQzMLIu##J`eHP_Q?TGG7s|Ors>| zrI{LnP(V0rYoi{R=g&oM@P684VW5(=$y%E-RP4aB>v}MME363BW5W?NbxgTxX>M+w zYGlb8e?#8+#%B$vW(i{lt|`{)Z!r!AVeUeAH%%Ig4iBGi?{}DWllgVC+>_s<@N%K- zbeOTHm27dk^TRI3^K3{JK73LTcO+F(!X}$(=9hk8@SoB>W^-1mU1l?XM{Lr$a>d6{wfbImsDV?fEH92M7G( zl>8`_7&)!1tVk&+D1LiklGkFuJ(VKb+SY&^^OR^7B|LvtYQVoqEi4hQk>O^woAz$F`K<7X zNij6mIFU4s3TIY=)}1h`Gd@?}|JCm)F{#nsj7e4Y*RAG1ANE_Ss^S45jf+E91zyGe zaYZk>0dijZ2)wgSZCyE&+%_~FPFbT~i3rikZoZ<+PRL1s$!j%pJ=fV*_Y1EYZSiBY z^}~wZTq~+j)Y@%2V!HAVPAxpg7aF{=5ixshvY(oYr>d@wZLR5ulEr1(|B6CLutpXe z^y&84VfzySSEE=jLhgG-MCLI2kcZ^qucfFIDlUne@gIPGYNqH4ti*gl-d_gj3d&J7 zWtsw1_E5_Qbex19FAEm$X_{^W4`zHTtr}x$tt*hgS4QfxiPFVLS+_Um@9w&w$1UQo zG!q->b=fjF7s__K3tPYWSD(6X*`U(K)^!AiFdg5cKFKSHYsxqSU&O$(5H>Z=K8Y(* zycWMkduMEI^RvS=az&nnoac2OgJ|o|kAOuI92)YwZC+V}wwtgNpl)0QFOC;>ZVAKn z1_sU`{k&r=n%hrG6mS%vki&qhy+(u6Fc(Xiim}-`(IBXydgc04g?gBV7f%%ZlYcxI zB4l;>;3MHZ3uz-C=)U%&DmcBRsF2uMSl)@cAxTw|seU2Wrf(%g3?j@TNmd3xGjiI_F=pD# z8Eqh&`5Jq_`ij1k98L=QGt?PE%*OJH*B`ZDc0|;xN0I1=^>&kD!>$zu$-!z5SwRLDY6NML9h68|Xc% zA`tEJMySLqZo=Q1&2kXF=w!{5x^TPl!nttCd{6J{*3O~9Gahbq(tAS0`T{)rvU=n9 z`9*w7(B|Q|0}J7h4fo>q$!e#t$L_?Qly%Ud)XvwhUr|9vW@4>fR9Rh!Fud-NUcjHq z8yS)o!c*QR&#CmsQYl{A1buu>qoeEHnDb?}3!GG9qu|$~txA-7Sg>=@=;7hvyPc}o zfttSzrt`M6v>bT8UDV&c7W@i7BmVmW)kxT$U(mQV>8-ppMT6UgxvB1VYE|PX`)XHx zXxHs`wrJP9p7I#Dhhw@Ge+T3RUMe6Ld&5hhl>+@483r`9gHeFq{57`*cXnx47du4d z*ql;6OG5O{U~D(Ddt)h~(yT3Bmd0^03SK{YZX*qGO&(0d79&oNBGkX~Phtx1k8GpF zdV?2#iS6TV71&kMa%a7d{YGQKWy5tcG6c2qz+2mm`)>C2iqG6hU)Wi2sp;)c=aj|g z?DjuJ9hc2UjPK1<>hIAuNP2!lG~ibc`B}anrV^wNGHJGd6ax$t2S-D!BpP5$#tujo z6eRMlS5NR{hUh2N+HfET4`!jW{y#4p2f zFnYT>7sk(s>hyuqk$-H5*R zh?jEx&U}UBjdIp#8fhp3kmVbmE;rb3p6M_fV{8+52Rd)^HQDh;x?^i&^F9o09RCvj znomS!JF8cehNCuTk!zD#-nEcM0N3VsVY4Rw38YwRSNYnw3%Kym+^xKR ziJto+LvdF8ruq9etfKs zF>M^6t*$Q}lky#Zp(6Q}u`UM8!3KETm2YL_?|~!yBsArc5)oE1ZT!*9yL4#pvsXTa zA<(RRo0zb6-DAa)`o1q}vYK;>ptgJL@WYsSw|i-TlLqn7ChYlY%8=(b_;9CXM677? zpWSgfh&y}KKc!0+KUR-gGOJfyG)u*opiSDOU;9cuvm2u>-!E%V7FV4x$QD1{I1#r^ zmUPSx;+Jt+f#8<|)!N*5y;W7h-X9ZZRPa3Uvp*n|zq5|ek>BJRBRv-SD0cer25$wX)(yZMFN$b0z}$T4Jru&1(Ixg!>PAKh1Vzc>UHg(A-Nzm~-2+ z8?Q`Es6Q18{qj0-D0nB+bI_I18%%%_pvHdm>q{43NAOApiBRqfRMXeUoR?dpucC4K zOF_XuOKF@~8DHW)ko3^cPK+kdBMEOhn?Kt>^H}9pouESQ_*x1iUY*@9_Xn<$Tipp; zA8O++wJ8Xa4S=^b*0((b6W?R#X%ruX))`V{qQF1|LyiS1v;@vQ3K?cw8bZr8Ajyii zDD_#rS#de)UZydYq|1WX#sxor7eW0~re(Yfha%|w-Y}H-LFqhrtz6m-)Pyi>Qgz-% z*1h=P-b1Gw5j%i78I-A(ECc;{eu?@%Os+6S*e0Nw)U#w=zm+@K3|cDGt#M5|>P9Ij za9J99QZu*@1_5thWPgb7y$;-4%ERgVT8hIQ{*}(;)*$L)L4Z<1DtbmGm5KEe5|BE7 zc%C>{xqub9SPho-j1r=M@NZ|lkF6QSJ76pd=tj|+8B<3;?vnhy9^r*>BXigYzkd2~ za{8ggt=`V!)xP|AWWJC201w|@1OyD=f7<4I@;s5>c7BCO@+D8%jonMi36GKl;nu81 z9=m3{*-QBX)+!ZZzjvdS+|L#LAMdY(CfI#7%^oU4ZYoi8joJ*u@|jb1EY198BL+t} zO0H5vo&PN(wkm!FyiNnW*8;SxD=i5WjhTNQhy@ZYm&e#ZW3;A#^g@T!$t4sC!uw3I zC4QSBLDkK^s&Jhu^6ie%$CBYeP>fNX74>{=>PYIi^PP?97EtNm^kWv=*_k$H_+gf_ znzU7<%jWcEYYMQ~j!6l6EnUt;tS$>myGol)AP;DhRVPhk01DMl2KSdh2$4wowT1Wv z3Tu=#zng~ya!$(2_d4P$_0-*q4UNF-Ob4DolitNyFy0IhEG|nm&Dev1mf8+0D;RrFF>0o6T0*jPDAiP#J`qJI-Y=a~J(*h0X<+O;mLegR@{ ziB0GL&u5s_cplxu$BW$4o7!Hd4-AfCse8{8?kJ)+P{KIPD%uu~`A9!(Nz2!S8XndH8D{NMM-fC94Rk2PqHn*L(K7uC8zS@l^x!%X)cu3{^CA>z?KtWJ^Ev zz=Kiz@>YN}vqPPB%sGZ~Q-jxK(<(mqHXbdoX=>C4&DZCE@?mxdc*`-? z_F)S{y@w}~5Ki0T<_v%Sl%?&GV2U~@yYc<|aG(|TJn?NUeNyOhPn;lbmMR)#P*IHo zWRJ-w=~Z233dT~IO3ci{gu$x~GAc0s%1!!Jw4E!23@Su^ z(rHv)A)%}che*!y@u41Up~P*jctoNXU*wDRb@3Oc+rHG~Xw8QjFudJakimZdF^?xF zZwbFpx>E64N<4dSN?LYp`oMMmDeXKLLt@$rzMIBua32{JC{q9pkENo(3x@MV8u=M$ z>3ebj{;`c69Y6^4x_z=%4Bff=xR);-OJI7F7SHf5&Uu$Mj>NB3%C6~osx-~E--SG^ zAc8i*PESt@XyD4-Mbzk8LLVu8`!Ol=?mTbLOe&{n#lCFbs&%Pw=T{s^uyv=K+Nx9BCFS-~b_cUEQ@4L@n zfAOLFp?x2YzMj?044ETW@dqt?7e|o~?rRC7f6MO0q%uk8;mfMc?>I(p z^N%d<9%h5<@xDPeb;RRO7-y)mAuq2U06EB8~1!qM7Yd|cMji5_{1~dvZa$P;_mIx-<8k{0mv&z z;{&Y#tQ2*pR9MS8X2<@h7c;}R$SGB$<&br{d=5BpY(@EzHNGxe72Not9v5$ zl!Rvgx6iFauev$e-7GQ~V4Ds6Rv)LtOz%%{%Ut zDx_Bv%h4e8l^w0H)=VJo=$!a05~+tE;?>)h(VIm@Y3CX};iZI2XP&_k^}h`aBtVB( z>@)kY_K|PEzE$Krmc1scXcRpm4edWzkN^94C|Kd_&CSkNta`|}uZKOQG9q@gFCSiI zwtMYhV=_r2VuuD9rFw)#qk6R4VOu5buVApQjY*$$E}svcQFOlfnLM802QW>TDupf8 z?roFb9IyVJ0$gy=(-E@6Gcj@sNV)H$VGThoKfKn@GCf^j9s$gfgSEJ5z|MFP- z_1JY(La@aRyrvvlC&8j9l9A)lZsG8avSg_ic8;Rk-o|RS*HlokIlkto*87Ox1<>y` z!WpSrLwg=uF+4x9pDdrHrKPWjVCN|c9S<7k5AqCHFEGQvjg8u);^fl8Qhy;&^v(>= zcK0u4|8y7pre*QSoNy^avBo@i=iP3m&s}P;+w8jig%kG8Zc+5M)4Q2tHU0@TH$dCR z896$h)4l>;>;W0H1!{h}T;*TJ>AJ`9Nv(>u9%>HDubvy;WB5O2@NC69yyLg#qVl94 zZH0cQxoz)kOzC_^o(lZeX^`CPBFnWUSB~bzzYj(D)jFBFE>!9`wXBV2@n^i{Dw25e zaLfZs!i?>vM#{c}rF7>4l2M>uMzXX%-aQuJ`fD`YMOGU}}+|9#Wj`(USDE8uHMC2()#%*UPWiESr>v(&; z^M02KBlRZRrN^x!W@{u4(0VqCQ#z%&`}_)kgB>TcGqh9}Pz+v;N{*C{zAo1s&s1!E zKbX>TESN^kcF*V_pR2fZK4n?~=UFrGCo0499PSypNc}*Sry5}1*PEZ0YSLp_3Em=% zw-B7|xc!l3<6yyXV{#sk(&8Vw*xail<#6kuEVzJo68ZavIEIy&FYMJrL2#kqs%!G- zao$C;5OLt)DMpa{R7W=fWIQlYvW!Is@y*$2$8=t`WX$&~+lCG;?8h@VwFd{J_y&TU zopN;8Jg1Ibx}w~@J6;|sUpTQ5=n1lwWW}fF?tk69Oz+3rlvwl$EZAZ6$wPnm;A)no`l&tUd_Z`cS7nb_+0|^ zFU=@Yu+`5r{Xk61wM6MAd>*cZXDl@yYwza!^=_peIESgF4>K6)23jU z*dw`8_QZv>OBrSnqE^L&d>JHe;F0UV7O)c4s$Yc;ys^+#Kpm!_0>tM)u)tq*!KBKE^@0N@$&1YZ?&eJz*||MeEv z8kdy!69VoH<*V6((O2Uf{p=Ic{xWLt1MFC#CaG#n{76*DyKm?tr#O!p1|t;e-)G(M zI$4PU)}YfO{|$0DQt9%-;cOHRC~O{8$Q}|5(55J(Jl{3Ng7yypex@ zFE4W>)qZ=oy=IL4d(F374zpt^UNyQpW$@VsZ`4BZ!KL}#ABHu~T@{6KSl zaCh(&F+3tBR)ZYtaWkn9oyeA1j0_d>Mjw6<7fmY>7XM>8Y`}~x6cVrL zTfo;mlDV)N%Z3%-+$X05ONfBb9h)=OYIj`!nVzTTu17ng_v9rz;?LJ zPXJ#esFVw|SsbFa2xGU*ffFYVhSN;6GuwB>+&$b>hZ|LLUUb{#?Cod~(fK<`N|sc} z=#I(kQ_0}fQ1YuoXTjW zC7uDFPoHJ7aCzuy{$g6B=Rjv}G6QAV!#~+d9FK2Ofa7iA%gcAB2NJKcLCgifTHHP_ z#4hzd$i-VSTH2}Tt| zt^^WKn-uAi+E`l0>L?4YeaL~|?CY@y8OcZ=DqCl5Q9hH`u_yuG*wZ)ub7=%F0N4o( zOqZ7z%paJ;Wf&|{AmttMqYaE|4GbMb-qp%M4GYcoOpv^_A23u|YV`xPJiwoolYk zOog7QLhbIWGM^}eV>m49C15^I}n^l&UEU4>F&HMyZ%@N$(n}2}aRj zL|ExjDkj3K2;Xg2dy_9i4A7{S5Ov^kJW$q-D*S z-D^>bTV$f4hRnHum1@kgAp(>rADh~%&y;Db4WZCC>k(6-3ox>KkaSfSVPLN`z;-I3 zj69~1eC#gG2nzX!P|d>jrVUoOO2 z7>&r``vSL665~3zKZW%P%FgRowIjPVx0GBlMDtd5;Gzb{Uf-n*UeDL?CbJy#`z3+C? zKBts=y=l5;@?!jGVDe9bV59*nTBaf1u{u0DI@+Ft&KLXs-5c`(al9TE01MWyH;m?* zx|CT5hVM$`^y1dg|1IH6DySEdN6LpvoN!8=w^euK^A!L1n7?Yjm2Q=DFgBFwwD9@C zi>xuCmSB+112j>=AaQHZ5jcQW**4c6$ojbvzBH11_D^Nl(6{LR}J|+qM8(X6YL`dt`yRYl!of zeBo?w6kB&Ivk05)%8Fa>?p>7(e?MKDoaut?2#hV@t zT1re`07e{`SdBanitMoC*?Jy1?bkZn3K1ow9sVd7{iT?PX02u4}xoD z$+oM*-}>PV$P}zPWue>i9kT>dEX1cUCB75NJ$(RnRlh53zb42{TR5+_wl;8)cG|2r zWLZ<4xw^i0GfLQ=iiS zZMdDA=Jxh>W^tGJqbH+H-NDgO*=9fC=mmnqJdmF7uV08h_~P3c3g4fwzkYZXTZ z*FW{TM}FIM*)3I^@~?l{wQ{s>VqD}9wb>#g9UQIL8~z`gWd;P<+FMyI7a%>Py}E|l z(}~xgFpWOakLiG-pB@SjAorZKwlmCjv*c$Z-@6^dG0hX&)F=b%yKa{?r!0v~f%Z%T zLC=1W1(eiwizSAa?R;4R$@nAaK*|P2G>K#fu_ki zZ~JN>eEIQt(QBT9Z?3`Ma?GcqtGuG)M^#f(oOA|JoaJyv9TDa*&u%@Tw@x5T=0F>~ zao8Dh;D^UeM3GxDEG)^|K|aymm&;B;#;mcty9UO8>gw1Cr>|HNWvFBHiS4S^D%vZU z8klY#s1Fr;t*Vi-Uo{sJLtnU@&W)53;{-*NqoxT9E5Vp(G zCG%~kQ7J4ezN%lcLdJF9lS7vr_+Qs8o66jY?tOH=U;acDtqA$zQ-hf66(@WRpW%-y z6oMlAanE|jQlJwu6rj9^4MPJF%Q(WQ$SvwiUW>KU8DrYYv&mV!k$549I=oGI+l{HI z`Q9~*8za%oWceMunEw{0oBqJd z&!8IFG{m~3(OCKsZZI)kpJg=IAfcpV5>V||{JQnv!J4Ej9&Bsc2q(q>fAOuBS#Y&v?L1JB}2ZELFWpFOjA3YBNF7Zi)a z71j1aSjL$;^~3}RmZI&$>1%A~_rXYWMn4+w6>+7{Nvx)_7HjX@u~luF^z?nj8dK-$ z(jV&mJ9Jpi@2z5o1e?`nj34Co>1>zmf`-)GWKrIP&cJ7~niX<5SJk8ALl;~F>AqbW z6L{*k6J>4i8D5LQ6F5_ff$!W@t`Dd_+&o%r&`(6BK5bdFwSTZ0Puyck2wbgc%IN;o zMzVB#T`ly%4L-oW)6Ddj0j4X=wX;7j!jZK95Hsu21uWj0?CrvfcRp82bMD)|BTfi- zD9%mF$vEv8Y!y*nI@BmOc4w$9&2b18pRc}&Tgza>&Dp*$JbkFOd(GB$ zIhXn~v+GYkDxhnZUOZ1gsh4%B=U^$)#`~PyiTVcmH%pTcogaCHV#Pe!tg{N7(%i{$ zWl+@lWr$CaAf(b*y3^jxWEn%NP4YWGQR~-jbw8x`iu*PYVA{GRA(5DuPL#bbX(ox% zedszKT)$#Zx5JpETHiJe!rc!eT=jUl?q&C?u*48-&e}}atQ{<_y$)*wc9ZkuUuNh_ zl_+xh)3CBnX}Yxq$Tq1dq#nKnf|%4jEY=onb~AlUZ;lFT(@(6W2|i4)qBu~~GcsE1+M7^bOt`)yHkBFJS3?iWX)*pm1CRPr`0h7H+>akW zIv%s-3`vit6+^>k=s69OQs0Ke!!Rm1hAB0e1_&#_j(s%E|ABVzXFIQe|0~tP!*Y*fRWzpG?Z8cux$UKu4%aum>9M~`n90BDd}etasNA?o9(2g2y~`)++|%HN zkV39Jix2Z5^DzIFkku`Qoll?Hs% z@%apmkrRO&YSN<)o*a24`1Nm%Y{!tg&;{5-o=jjPNohnY1TGI}anZ;A;*h^jeD~GH z|1?dNhd8Dq$E-s=d;p=uyi9oDB*`KjDk?(3lG8R5vL`8u#=Wc0@JGFUgkScKP%Qz{ zCqCbZ_iTNxxcs@k$eLRiqtp#Aw%&EFGCo05IE_|v=J~^^c(xt;R|U<{@N=z-w;QpN zW=RDM@ifRPf@hLT8{L{>aailDg2f_9O)OFkE4=j@`>QK6U1mrwJB>lV&j_=NU^x7F z;l3u|Ywf{RdkYTtDZ@@s>2c2%D-e!4;+g(bc|i&5>KV*pla?ms78dYBkM6H-)2E|u zH0pNqT-h)IC7eYu1oHs>C{cTOTS%|huMmQtH0`guke0%U>#@(XUVg7cnKbj-+Mjl* zJmqkG-jpK_C1@eeSyG3z!a9DOp0SLRiZvZTCqXVexXuOZ$mNUXVn9yq7n5B7Av z_Mx&4cuCN2Smt&kmUwo{Yd`kJV<~1*<}qS@mL=MAlkA_N|7Fnm$a;VHBGZGr)}FNiEmtsL7;0a6fIjXDS&FduR+-*TN}eGBiE*9-Jhs_%ea&l ze_@z`IkNQsDLAq@BD60??UIW)hGfY&PzmKU>`n+tIg;}JiF8tVe-NYdx!#SO{6&jV=3vA` zlbUi~yIJJCP0h%jk_zIgAW7QGD`8HQ3Sza%PsxgjZtwo^^0%*5c!|S}oJLKPLC_*mT|P89tXang#ufxh~qTF0ofFJZRKUnODx1(;h!{87l;1n;1z$ zRVr_Um3A8>@tTP;hkceJlYNEWMe(6Uogzx`%+c4Ax=&n}n)_%S*>M`Cft%82GxjdM zL%dU_&Ewgu(p{73pOi%}QxRH>jU)HlKZwG=y!^#vkV`gkm1(@E;LnoeYG~mP+;c+W zKXNl5)9-Y`1OtbgVm^*?b*1uLsYE6MPUYlA&|&=WB$iYlwHUnx4l68W&{oo9N?l}B z1%xUAH8K6|h`fxkHn9iMPb|Kj65t?yKw6VagrB}ZkVL!|)Yf$MH^5oZW44jh zkC~Ha&yFyt&~LSk4`^k2oaO4(_wDH^tN{5pth{` zi2GY5v9)ubr2dpM+*7>iU+>MgOPvQ|94BAVVe^E@VO06*g{nWMS%}SZw^j?VcV}pc zg3U+yKBE{tSvcPApjcEd8zYdy5XQPGqpEGZUXoav2}&JFvwslG0%L(~rM{HUfMNhu zdLLDuk%idkGuQQVZT4Bjd3zK@M%kqr%oAW$wr3T&puNUcAhXfM7cpt(3&-S!VJJqL zR_<<5<`VT1_FqmgcBbzbdH1o2_+Q+OWv31SwXteh@k=E2SZU@a_-AVqYP5mIqu61w z_GJGlggI7Xc!dUeQJqBI%Ae^~WyMe|@s)@McqOa|Yl-il)%99*vkVS>#jqTY7B~#r zT_6hZ(Iz)mjH|Yg^;#CnJIbcREK!kdq}@o~=O4O?KD=S~Cg|DHo1jr28v5aPYODhC z?3zb-F~|hNK}H4zZB(#JLXsBrDp|BXk~5ub2u?_DHi7OHT(abk;*N?%j=IVc?nTUY z=Iob7*Wa>fZ@39(QQ?#_ke!M((F=NUQ|P1o*KY2hJ;sY@?CZ?w#SRT4^a@wTu$d#* z2xr?OSGfL~30N<5vfO|*05b-a?i=5l=c(1fMO4g+Y`nvQ* zu}oDW9`Ql#)ZRteG1jWBtSpz3cm$_7Ozc;hMSc;jJ{<=fN}J`ucYQMy6H5XKQlXtP zOJOO^YlUM^A*ck7m;19`>SWe)-^d;&1Ao=l)f_UCy*?u>BEUX3%jmS-5R-cFMjxl= zSIvz8RqPU~m|xzjmbzsnn)~~!!xxKOrmxEx00 zb{NVObgZ8Ei5($X?*6&w*2}&Pz(z#-qdaGRkqf| zIV&CGGz;e_6KVlN0rU{Pl-gw}`MXTg7HD3%l?FgU65?_*;)-N56$UAPFtc{`%EcCx z>ig?5SIgss{h=76TX(@$1{FGj{4IKym3xGn?R7gE&*#5S5I#g7N|jM|B~Lj>&|y2f z(kB>gWM9j-du`RIO7jS{Up6Rgq`oCux|K8PM<#^K>b8u1!Yxo= zd3hOXw*qLE?o-U{Sg#uQELW$x*==qg!WpD0Q_Dxbr95bB_p61smxZtAb|; zkQ?U_gt$ZPw<%ws>xdkg47zfC9Fk5+@`81A`_nH?jBqd(C5Dx!%J3&?3s!2U@rBuU z87sNqRU{K0I9Y1ald&FDIc~;1ioqY;O4b?gD73Hw_aA)q3d91#aVpytRUQhtVzwOu z1GqzL)5Y{47G81-s808M`^D1jE)t1f19EViD`V|FX=qsn9KQ@fCl|U%c^xTm<4y^3 z!z`Y449I>;eo0x~f%goPG+nFdtsG^DWd~fmO{V-E!Y%>RDDg zJwDBUd+}QLV1WFwk9=@vJdH=G7itrpf5Tis8PcuvxhDyanSL5GN02_}@vbpHliT%^ z%HLIm0+HK|7vTlr2CQkRAF(=VzbK4ySJBM7&Q`Lyq#80D#}8f?qkT#v++`AD52=bM zb_yM`xaX+M<#u97upr7Pw&OKR3mH39iWhSKLs48(!t*BD7CsJ&%dxP0xqr=$=E1kB zOg&?hexu@JFnkOp#aQZym;BJ>`BqbCe@Orifkk#+RE{TL=IzW;ZwkxHEhD-!bT3wX zS>2ROQds2=Xz}WJ&ibhqgrNcBX>27-L(;wO)MD*pJojsm#GXYdnu?$4nu7atna*t! zD&dHPmGsXmb{q4W|EC2gBD)D#+o8GN=nDe+Dh521(H-X(gtT&VqSw)^3DktcI9y9z zK~K8l#jL2Gq5TZ_hX>L_CRE5?nWR_}Yb}rr_nXzvPPc!4z3DUNzdl_T5zSl7r@vv& zvn>t|!sj}_6CByfmd*=kntW)x**}Sv2*c=eA^{z2Py zhDS!~KA##H^!WNnL=Ib)m{wVgPBUEv3wq^*eN0J16C5qg9;JhGqn0$$=yQ!7>PVH` zbLQJ`&v}=CErSsVp`n(QKSsK)`b@?-_xg)BMOMA={j+tO=T(Lql#`yg1$2Kzy$H-$246S_2*E_IbD+ ztDQ&Uwpmk|3mxpt9XUaV``&1QgWmX6E2ebb<%yVb?(23C1MMXYK5;8#hD7=+1ZU#j zaxUf_JVnHkxR=H}di3QCZ2hx>$Qk`Py400ARju#xkX+vJc(26tb@xPHw`li{UPt z$s>h_^HD3U20sY|H^gMdiQSMAm7^Wn!= zc!xq>*XHF@uSu=C@#$)QY~)Dgfoklq{mYjx8}xn3G&2Je4+J%>E1iA>VS64RG7Rjf zGEGu7o^WD?AmRg*lH*Y8FpT^1T)M4G%&Np0T7n~4J-yYu;}qHUD0}g-k67lUqIgn7 zFb?$_@g_`zArhLJE8RY?K_=gqtgMx}t*6I}>8;;CDl*}=uiCqG;j(vT<#|f6dRg(K zvIIqfzldNOcnt)sBB_Z~775QpX#+X_e!;f~H8%^u66jTh8n7aYVa=i5vGfJ9elmVt zus9OG-l*D#1GyL0JD?NOKc2l+#0;d2S>ZlOboIZ?iHA~4v|EdXXyrz9Wt$LwNl)*) z>3Q}!TJ31slOhZS?wb)HjD8m~a)^D%f>!Lri<;!KJ~B8654OF09^}Fo$BkOlYi)1$ zse@NGBO1$6ORhMA&M;~O?k%i2an=Eb&Ckc&?p!Utg-fCe*@nRk1eEdx4QUK$b6jueJbPLvSwkBsuQky`nSEEI2Su@d};&D#wEhjy=O zzYNhWRfS&_(*-9Bicn5AR*@;S%3a4L+hMh!OQ~&m7~LDmkzW4$aJ;A?bdw{?+B*Q{ zq$_P@4w+p$4Sai7KiaV80hEph@Wiqc4-V1Qn@4`{U|`6-!!mD9uk&6bMZhWbX66XX z260q)VqsAl%Qjo}WmNTzmv>Psg@X!hW4wHxhE{f6MHQ`vSj9Ce^K(Kg-d@U+(U= z$L{RxC@Rc9^qIhvLJwbi<}}@F)MqS1nF~<^DPC~_=Id0#0}qKCCcHa#PIB(aPSXGh zj^}iJGGTh}y)o@aL|9ny(lHf$WV$$NQTflYxHHA`A-d&=RlPIvh^X@1ZI)q$@gul% zvbZ+&?6XEc;Y-K1#=JB%Up3oFq*?%$C;!LCsxsphg)CtoelELKBC1LI7Nezjf7d#l zZR0Lnq|4Gc*@Mk0Xgm8jCw__HzH4v#mc4ApTiKWf3tfl`${WerB1i5iOAAC@Dy1}q z+Npz~>(@D%05pFx^L5f<6KE#!h2J6hhXOaF=>LGXjMG;8_ zS_{A*b(=_;QB!1%?;s=}H+_$}3g=eH3-gHb%o$0ECB;+mX%4$jPPs1pVu8#-(zvVN zD@Z@n@n#gs!4UdhTrO<}max}cPjjjtUOaG-g%TV4r?c!g9CjU+Z_Z1jACas$m=1;C z*~p?2ZQlXg$JHT}gOjtKmRGT2N+y=1Z(?FXwSJ=f&+9((=C83=9zY$sbyg^y7xz~Y z5phcIiS6aaBDQI(_2jhJ7xJy#@2oHFwDOC>QnCE0uOQswKUE5B2M%F8tS zrMRwnVs%Kd0{1?Y>dHM>QsH0Qs6G_rJ~IMD8-ZOmar2Fp{}9#- zKfrSQ9k0%5R%w=-YVMq|Ca%8PX1|Fh&G+0(C$F4}nGWozS5k7v%SiaM3-W(u(!PT5 zQ6}gmjZR>Ti|%WE`@T(k{N38^^yUh)63n>;#p^KAG^LK$3GI88dUi`35tj$I-92w~ z3>feb{bJm_KHjSukR6~CQsychvSywH2+`n=$bWJx-ej9NQ&jnn|uu> zlcpbm<>jS6q(R7VESUhp0Jqcj0?$o(TwL5TPN$xxX_isF)VHco9<(pe%x+nSfy6!avcW#ju#i>7 za7imhLM*OU`sWk6ng3=)|r`j9R}9#Afi@lJ?VRWrN#lMI1i3HdV`+c>yWqpjBGqn z#KV4HL`(Jlo9JBVQK=Ji+F=C~r-qVLnE{Bd168W~?*l8WP)cGSRU<>gfaOoK_AO3V z-?;UTF^FS^eL5V_ylMayA0utHY9^Z2Qz=s{S4CP@w`JV*f=zFo!|B*vUD=8aF??%K zJ=y&{lW-3aLI5I4=#`yVENk7Hen?mRSo*#Vy$U>*;84PywESevHYFYYR-qn}YZW^Z z#~yGp#oT&5Okw@vGeQ{*)ALt1U53a=`KCxcI~r2*it^w7e8OiB=JUb&unPk)AFI^L zU7olO(Uq9Vg8af>^u7+6g$Ylb!_-av)h|UDQmRqGixqmi@r@f0AVRpiSEDT~;}Gbb zG(n@uhSEnWIl0K8QWZfrX_viME06669kczT$p{@py}B42pSqV@UhVYNeKB*w$9EWv z2%>v9e2Not%h{{);;19yRQkAlc*Q@mC6g^`74VMet7#xq_GF2zltm)-Rj?RR>F19v zU;lpZLuahLfmz5r6P)6_C3p!doT8j;P9#>7W?#sF(r#$g8xjQbm1XR}j(8uUa=;sV zcF8rp@f}wsZ~lNH)(rf3L8>d*4Mjz?VDp3G9wd~4-}1%+5j&4XWKUyb@X*kZt0wyW zsmba^WWmNvzQm(K*Fd4u+TdRTDFEefzIgiiyeiqMvyt;i62*s)*|&+AD-c$a>&bMi zPZT-^_VuybYbTPD0fWdPDi^~KH@wlYv8E6RGAb&n&8AZ-wcJlTP0beXKq~qfOzg%V z<)9k)sEYOi)W2W;ruirB84}Bla3QGMNv;|@IKVqbsDpJ;M@xJ72{PNLPekG%x_=mZ zgX7(O;lQx*G8`=GHoJWU+ht_}T#8VL9@uh!UXX`6g;lyeY<&oOsU}Es7rPuzGmbRy zby)~02sUK!LJ)8yAe0rPY2V#>R903RySl!rKJ32`1nUD9M7_*KW&SIG)W9$PCt|T{ z-iBwZIH3c@77#2tE<`3kZ~p-zexLhvs({8a-K4q!pJB!^vZ=^&a^(p!n5F;AV+N@r zP9*=T;byzSMcd--cIcs4>JB>Y9*ZDCe8d>b3C6&-0c%U~F`d6QThtfPX!HKdes*w{v0J@PS(j(ct71^6yaRrIA5HNe z+%6r4EUXg}P;}nd7!WNkTY$8FG5-?XDf;I}RA{x~z~iH!_d4hc09g;##)$;9)j+I5 zd(dXkBOQ;PbMN)I`5$FqfNd#-U~25NG&C<_wNb^kCJAd$x2ZEx_hrbmC$5X;umzYx zv?^YXH~~6Xa9W~eIfO1U_ir)(4yOSH zVwBgEYl1z|1-)WkJRuOhQGGh+)ClJ?B&CErCLDYM0!pgkGF)Ir+xasXVa8~Db00&= zbQ$N;=kJHkx8 z^9;BB*{IoJ!C7oX$fpR`eACE3M_+@3bRwBL6CAarz<7zY3z8^kpXq!f01c;M0D6xl zJKqV{8`ec4`c~6jIe1FlKLo<_^3*fOPbW^miS7hDDJhB9X%jxjW0xp8F3!x`n*_uv z%y7RU#TA%%#~7P*RxO4_fhNJi!jo_c-9Zi(+XvhucdAYw_Hu`5n z%GI$7*R*$!n-n)te3YKDsGs_wU{-^T^sLjyaiD) z1cN)pyyztqPO!ii%j}sqmU5i)`gl1kDy`&w6cxT?3)sNV?w07xt*(b!{CX{VRUkYc z2!Uyh3I*LhXebMmlEuyHq8Rgtf1xG1mkra81Z$$xiGe>~2MVlizt|Cg_QwMO00j&H z2W(h3a%ZSXx=**Z$C3b!(tCT$Yvg?)3n@V_@4M24s`fSu{WPb#SfuQU$? znFS1i)rW$gMv*V^18;~Bx%Q~P?3lM)XK}I%2_Tx7MEj}7$x5mP`#fC#G9!N=EG{l~ z+~|b`k>YqLA>BOIhycC8lHzb(CL|>_e1A+>>|R+Eh$RJZVHcAHdkd>im`hpp2~8el z8USnp2#eg4?$}vW0mIWVF9wL%66@4q5ufMASQF$d{6}%##CD9Y6dC<~vD)1mhdE*z zJEW^4$j=`Mippa*4q@R~2j7d#gCXR;Ep{}-KkmN1WFX;P4KM#(m6gR^5FftXd8sdg zTun7c75fEXr7d;gOc5P?&*&oI$SFJC57e`KKXmoprY7%em==x#-voxL?0a(B{q7Gz zz5T7-6A6+!P#wCi@IAZ8&<12}Mu4=n=J~#6i!1j|k&bY!=GW8xew&Brx-GgP$q1Gt zwvNPV-fP|cXWE{S4u7Gvag&d~vAQp^PtjNu8)NXEB*>u0ZlHt(5ojj5_%|#&2?%Ea zmO;0o7h+8Rs-g9mA@6mJCakL+c2h5ui*0)pU-OaIQ?7f%5wR0#<`w z@~2sHfIIwJYO;y9;JX?#KlVi%=q3OAi+uB+1oRKo?+L2^b3;s?kW8x*l8rZVvr1-0 zhyY@50QVA*VYGrI+wfH{@oOVv>8gF<^06s6MUM)TFJe9`E{Gfzddw>*@X9vsy?|Ny zob|7!VPUD(st7MY0@Fi~;704SP+kv`dwuBzV?8t8paq)u+qN0(N@n2h$Aqk+v5P5b z6o!>=A9C`eVrUDKnF0{6tc-gu}7 z$gSIu^v}#Hon&s%YiJPfyIFN?=)TM-B?}e>&HVb!tTnegN&;g01Uff9QMQ z&o92}6-{)rd6%kIu0bTVX>Vas@_l!9x%$UJ6@>pB6nc&`4=U@$^I@0I;VCH;NTA+j zM+*vii)rv+^-_yA@Z){$YgjEyZx#cX-)&Ei8;;;M%ffEYF?J%Mj|tuu!eTqB+>0q- z=!(SB3zrf`tnQ zh476JxSRmKvQexVS>tnT^KW9y{SABkB#Ij+KF7JAL11;yJol>*aY~_K7i!85(YYuX zHBhLENU5>&@Py6Is@bY?EG2IN7Bz}o}l4v%y z$w>*_{$!lusqQQBv5+rd7v6L7&t7EfWkyiQ{2Lt$zAdv~UT})}!y;vfc>f9y zdXYOhfZ`E@t0&Y1?YpxpKdJZ0r`&%ilv)LCE^3_|b+2g9i`Vdqg43@V=qY+lb@8hW z+Bh}d=wP-U=y6fVeRku|wo`e3&_TY?@Guz0wWpw7z&%Bli4&i?sl#xy2!9wY6Ii|K=aLEu9O{%~LPLA=Wd%t`_r zXCAjG7X0JRhrhI7)PlEm*O6s0$E<(Ct12yK+$@Ok-M?`mK#k9VyD@r^=(4cCp!0l6 zIM=KUA-yD4iq#iPore*>ug<<(NqsLt`zKV0W#=rSMEJATPr~jOPEHd$1YY}oQ`$Fv0HgIm zU((MMX4Q?Aa}nZi`$E~e0wN0t5k@Qkz!aB`YRK*20i=@mvPgcheyYo)|IQg;k|3Z! zD?vDgHy9fe1}^%ZhmM}*YfCOTI+mFk(aSjnHgru8e)9!_#z4|;nvY4YRf>Ij+klvWnwNbVYAkI z?6Ed63Ho)8sG)imG0h*B;sLf2-*|N>shMRxNEx3g;IqO>Nzy(W9hFj^q;O$;95MSs zi|m!d4qBP-x$vF$nt$c&K9TS`!ho@g<>f#srub@${P~O=*yQUiDBhvTW=!tRaFhF_ zbSLZq&&KFsWr}n(`O+SioiWN!QVU5%5$5|aPA9`p)X5{;ji^rHJj0 zlnPoJe>VxHXr@22JBShBwl=kVEu}UWMLN&@zCa<0*yb09Qmbwj9Zd!|{rLtwKUb_D z)8Oc@K~#S2B(>Z*$BoJeTyi$!x7}kRRd$g;vjhf~d@1I0G;N^2TYsEf2U!%WH;1!I z3@ox10UX(zOB0`x_HKZFngP%J=BHQW7iHSD5vRwwv~GA!O+=XVmmdMQx%2%wMXSLY zPAMnsBx|p(qu-v6KxOb{#3O=#`bC!Dr+>H6D1$cN}LDb5tm9w0|IHjy%$#y{g$ z7N2F>|J|K}8`V~ATtDK{MEk2SM8V2{9txyPe9chOAn|ZqL+B?OK?8v{gk>wx0l*kun7M%bGkuFv`hNmlTXnHN>=bcw$>)V2;x5jx2*aAgzY zsj16TisP_&@Bg|BuH-eB0aU6@T}isd{#RiAs}X;6wWSr1_Ye+VtwfW5^OT%E%1MEV zIWJD>(Inh+5H&St53dk>K_>yGd41oNPo&v)ZVRY(s`sCddDndkX8YK;T_VYRHtL(K zv8jFiM&}hW2aFZpU=dWm_mL3KH=GxAnQQngT6ix(=K`v+`Gc?NqCj$R=qaByb_kvn zcu$yCf*KcNO>>vj7w&HG)3LSe$KqJL6i;oZ7c z)}{Fe+_&#^a0Q{|TV6ALfp>Z%20UoI%`pb7VPNc#XC)3T^&#IuD8+~qxCb;em27gy z96^$!NrvUeDoN4w>x^Q7;W4VQ!%MO!>nxtSXDMteVW~UOXN6b74rJT^I(9RTxNMm` z*p1C++J2@Eo!f5I1{M>irI1x5r^C({?-xe?ZS}J=r|k<5hDc6s3-=nv&MUl^*G=uK ztYGd`dYPc@<<&v;9)NP!F@FZhuh@KaS`Z#`YP=q|>nos9Q0LD``@ULLv@|n-HChLF z%(8pze0K=UGX`mq%F4>A#9Zci2QgHxe^-^HI>XHG5?B20N58kfPOQkb%^E?#B~C zn>?6&usNCWe_8+)5DS{WOXxf_35N*Fn#gHjU@$nihUj`mYfe#L%PQ~iby>hhU}<3S z#s|pL9KGvBll~eor^xdUYpW%9JSrU6$xV{g>6xC=Gll;*SC2F!k3qh?`j0#JX4&+$ zYHod^gIyMydIYQ@Tcf{+@_)z!*z9H_*w*3&ukwR{>Iq;~n}nm;dcWf?c5#tgP#fiz z9N$=&fc6<$^Pz{$)&F}qdV}b>ASURhKgS47F0oxdyFi^uMy%guA{E?LN7ZbX`+Cg< z>xQv0qbvA3a>Y7{`{jZ&w4!o`!(OFTk^VN?hLp>cS!ymsx3K3xD%Bf*Fpc~0t*luT zjT`_O4ulcJdOJqR0{|m~;GGwN8n%k2>Nf{U=zlLMxNO9_c?9gj%B@JgE2|pK&=TRQ z5Hn;uZ;W6(4>nVRGYLSD`6PQC>x@wQmJVc?D8%CRgko;zABu5Bw8jPHOu}aoDrlN~ zp}q-3^Y;KtZ&~+!4ZyMW+T*$6x3ON{Q|?inO3P2Nw$8T5xAh|1zHXTSOZ(6Bi48AS z?g{K3@0#PM$LlKt_8bj)T=xKbk+VmM1PA8%Ew?xTWDp>0pc?}x0BBZ(>Ep6rS7N$U zr?yhXDAG1%tswqG7D0_Fn7H7Ca(VWQ2c9MwhHE(vRy;mKioHptxaNwCusy(g#^(JC)ux>8 zQd8j2hXn}^OqSc+q+0X2F?7jdjm`Dm3?Ln_HD15{G_z&4h!oU8FyDIvE|rakzlN^S z+n;}4%qr2xCK)8V{nyjjw`6t`z%5ArKdQb0s>*E(chf1|T@r${v~)L0OGtNjcc*}W zbclpf0@B?jB_Sax-QB#k&%O7(^Tyu8adhmn_xjhGYp%KG{Jw8eQ^(M@1|}Wsgyn0q zz(T;KD`S)%ct7VxGEk2d$W|^3J)ZLdh|OfV&>Y-O`{PxC|1MOu35x5hi{R8ZY}aGk83wGvV3a)740^+o3N!esBY!@4FF$CPA-RS%kwd{kA2p zPt)3c4Yj{nk(gUpOu^^?D~LA%=M7_YRa4VYbvo|$zT+l71V)G8b4MDtrJmGw(Z-U4xxmPLL*EXuRe)CwXr^)xcaD2nm=080q8s4Ao0$K`LOik5wFJZOA zk%2Fe?C2LfYN@ee;X#MXR<`JH$W64kty9k83xc*Z1C|l=6LQ3l5Tj)a0{78Ojx{33 z1JEhnI}qYZh_9Wc>YxBNF0?Hlh<5p0x3K`~0BBw*PLZ)&vwf6@&iFq)2>Sr&18TVB zT^p!bk0Q_daa>?WEvpmacmKAX@PnE(zf=kU%AxQ73jitq6OG( zzP8sGaUYnTX-Wm_d{{{luifY#3;q8}qhUdG(`~LFe2Y5hzWt49lxju%m-Q zz|SoH5H5?KpLb}Mucnxn4Jy-k^0CYSki~mlI>*{O!?bm;L z%>l^eF|Gp=Kplpdl6-rGQ0QLIDP$e03T*e`ip9K)Tl?Fw~TvAHB?uSA`7sLWJx?};Kh(( zMC)fkzFDr=4T~lgcy!D$msKBsYpcJP-rKJ8kp+C^Mkd86udSg8_9>Bvsq2H~N4pB& z{i+fbE5;*@srD__3vfR&x@@H|e`*bJj>olxZV;quBB<&AA?EPv>*(CVV{C$aebHS< zOEm*bBHgPPhMObM6O%BJl8BS@+h)CLb4GmUZDu^n2{1rJ?VlclBQ6w)t zM967(@K^s^JgJ^Y>ZnQ4`8V4kO}`xCsl6re!mtpqVXO$KcSiZd@p`SAF7A#DrLo}Q z$d5lOf6z=CnA7P00nQ4XqJeRvE5V|{E?JfsXuC=1kpu0XcroDLZ{YP8AE2Y|Q8YC* zuTknHx`@uW(h%0V^8eELC%W?yOo1{9NJ{{P13Hd*c$5>-|GQw+J1MH^Sc>(Az2HK)XciO)CMX2_AGcm~p2V|Y;-2Q+Uu zsNo!Q>RhFjNn+hGU^_^$uV2`q`Ci4Iz>Yj&U0$$c zF9A88NN5S&%JE@6n;X|ZGQ1hmIv#cK=hD}%r}<8w#2+65v@~%*f946xl|ssg?Nlbp zY3q+6ml)A~g7o{8mlG{JMbF9T0RL_=9-gZ|VM@8r_>zov>V&MHxWnu=t9Z=kR`?C& z%d6`2mLKbU+X6f^O5KkScPF_4t6a@EF>?10%TFLDrkv*?&F5k>D{#lbFup*phF9d~ z@%HUoK)VO%LQwt!m62BYF`72Wv5Cl~iH-0R`vTc5za`a)AEgu7Isl+Uk$2NywLqMc z1J(#cf9V++T_XnzmJ1k?YCRy$Ab=m;LZKt1uAv~93Sf)&M5U)R3OJ_G8@LFe@C*0{ zcOFfD{6u8&<3OI+Ez1>V*Hz%S<@1*+5HIb`65>2JAG;>X@!uWEFeA>{T5=ORg%e?) zTlHr%Bj;waNDz@jXumsb25$3*-8$*=H6lF&Lv_HDKR^+!OyxeFzxL|~J-72!R~QyB zq7Pewdzs0#@rf&NVN&AsJ;cQLwYHFUu)EhTjG3#hnZYVl^cde3gqVQI5Tw~;y#O?+ z$Q#CR4Y`qfDY-yK)H#<)QJacqcLi`78+6`Z3$S@*7b}pf)xeNl z(kHU_?|^-0@v#n46C-UA&s?@TM2+-$-|A_1FZU7jRhvO39du?31Vs* zX=E4Hn^Bh`#LZ5a4y03)7fsHXZcq5OUx z$)!;2&Pq2m3@9J~ZF=?FBJk*d*O{-%m1sZ!X9g=13cyKb2Rs8m;aEF-M0i?H>&)U{)kz+T~x zVq^y0a5BkwDDdA!3u{Y|C{jqDcaRp6{P%&-AI|Bt(;jGC- zJW#6gJgA#>+?jlSzd!cKA~P$)C&UnJ9lc`*ArdJyxre8U=7>!SySegVj2(>ZMpi@S zV-~HL3Cc;UIv0!WDv2AI#rC8=FNhtF$n@MA(of^UOxZqKo{FrZ!29EV^zU zIWLCd1n-(EiPs-wASh|`Q^pG?Fi!#t;oG8h;detRk5`f_(d^6=SpAL*98|9Po32!_ z^JsRzFs!ObvF|G)^+qL#dLm(|P`$^|Xf*BbMEASPhLD$#4Yb6KSg4nRkRp@d3hDA| zu)1948I>51o3Ss;BZ;Ce*WaH@{P#))fBV>F^`{gD2ZBtK_xE`$nWmaZnbCe|JR`jK zS0MEodl{U-2yajBs47w*F&t&d2CseF(YaxT8$?KbDy4UwJIl_g7W&57DAkn3Z(Oog zU6QB=6iZicc~Tubwf%=htMvi}CW3Pasc#YOTXym+W2x|(+57yimEk?)!d^V56G~}9 zZXwDzw@f?*O#$u~#~#R_u|3f72Nmt@CVwrsZrz=lgIJ^YvVm!k`m(ZLuEl(BN8f); zgeeN~c2FaeFtZVRQykqp~yj}lQpR< zAus2*xoim$luQ0kDAeQGMerfzW$0g%SO|lWd(=2>rBV?82P;g}Dk0c_c`#iUpE%>=HyQA+YAIEm>$K6vDSi0Y_OV3)pE?w1pTho=DaaCC z4q!3BQxn`4n}F}(pc)c2tBmH8Cwb@mir5MMT$kEZU-Td`e0o8cK9>{gh69#O+O0i& zqEKMSM+3eUIf$_H+YoyU&QLP{wSDOLu+ilkOkHJ3D?O=|A6sp(!3}InjB4rC3^)19{&`I;aKlOo(52#x5-H zb>Wpc3J-J({R$`KW9LSjZQsj#Q$m~4#NO`*s!fc$v`o}jOUO;Ob~h)lz0VniA5Rk2 zcZzfSz>NoJp-u=VO16UHbomoahXTQ;(o%`*;@PL?*$U{&WA*h;Tm2OMkm?sHL-S4!B~hKgL*FY6@G$w z%?F-ZNXO(Ur|;M>S^aGZxaWc>d#CHBKH#qYx_tTeWqehF_Ag~R_}~=B4Qoy?qXxXe zWiggNJqI+*2AYt4_yZZ?%;ltQenuG6^{_`9*P8onSfkP*Y_mkDa>ICw0Y_=Mc&;{I zD4G(enVYA{f-w3n%KEDgjX0ZhCAs*R0#=WyU=3Y9_XjM8+4#II$sUds4_eu>$jQ*8 zvcD)W7}yAbpOFU=2Ee}h{vuB`4VZF|8oCZHmM1Da2etW46RZzEb>mG_Y*#wEnj&(h z#s})?Kq^%BVVnXgon%M{%dn~vj1dH2w3jrIYgojF6#(iiQ5`0qP;3Gr-Hcd`NMcOE zQ84Pd=C-bzulxb)KLG%^jbwlw-%;m{mi-q}*zcOcaOk=r9}U3nL=tS#s&3e7M6?_~ zT0r4&*Xti*!feb4x{pLxL%bBRG2Rp>OxiCLvg%@#=eur+>Sd!Qhr+QC^n*HLW^FDLx@JVqi<9JS($@`tMh_xWBFGfZ?WoXEQuzUfH5#k)VFBF=r0lZ{gCg5D=Bcx8s0!s=$mSYoGi-+Zl$n=J#jU>xoiU8$_VlN$oggP zW|3(HAfW-G<%|mI+%bm7yb9i9f#@>PBvX*`0T48VGj?QZW=@cG=GKsCo)&j0LJ`BN zYN!f?rivoPDT5iiJba?w%NkbG{x@l%@q;82!R;So)8_Gn{7*D=ap)Hi=T|6YOkGD( z<1E;kI?^jr023{VjV0BAX)@51{_DL*@&TSiC?l*91cY|e^2jB?aujgx4c15s(rF~+ zWRWZAIv8ag53mX#B~6hH0f#TZ$FQ((sU_tCQ8c5ljh@W5C#c(y40cj`9=dOT-rLvK0t^16esDTnhD3O%h-y@GMmgIOxxy$$a zjzj2TwI40!0`A$|CbypK03nNHQ+!wjlEzzXK@L1EDR3oQ^STLof5J5;6vC+3mwo3) zh@m0pTOnhu(b8X?-oGxHm(7nr_@shcXF;|Rz+^>JJA^{Db0Y}BJvS~vy!HQpGKUfz z$QONA4^u-!dv3h3hniZ^h~lVacHN46gN@>p!bsEW^a{qfB%Oa*>L3wu8Y_RB#+eq? zeEFbDD33-fEq^P?yAtZsSO({=T$kfz5KUhO9`%4gV_+6P)IM}E61@kOPDAt}5LFCv zZxFkwgn2;=D~}s>R9Ayzd|ndH2$4@lEx=0m9TK&fkug#aO2y@HV?`<^rqN2y-(ndt z*j-Iz5g!}G3WY=nVLQP?u&uR>@%oay9oh*yt$v)G%#W>)eBzp`cUTUGX`Ya+m?tD8 z1O?~J^l6!ijM7#kF_nH@Hb2RC^QEX*^b^#)!x30*^jDjMhf5qVLv4w)*FM*U5HgkYT)WW_aGvUhj+=+b+~4-~PH zgCWk8=RmuOz1o8fn&*w9HIVrx+g9AgmrkFb--WD$cz< z{8-fc4HINz=QqDcA!W~Lj&WclIV6#j0`o|_bmStr*Zg&&sA;yP10y9NJF|ZUn5psf zWq&>xEZ4~)(uhdckLONs@(h)hK}FL6a9gY={b5bXSy=2=*2DO z>Iegc2n&XVbhV5ZVr0uaj@rQE0q`?0;4qSic?Bpp^iKr>a?Ps*y%;+Ml@&M7M&=h0ITXQCQ&DeYKU`D z8F^Wb#1yrVlTK>?EBzqN2TD2Ncwha#F7EeubfD%JoKiyZQ4ZgnUyUQSAcb2x_47t> z0hL$^?(;q?L?Bees8R;bnG0HybKmc+H8>qD{sd!6LJ{7r7#bS02(i=C8hXv{&lD6C zKx)oTlgiC>-+>@q?hNtdH`%6|yoY*?*rl2p9d_A0>o1cgZ;LRMzo6o_T0HYH0y ztD~mMLO>loNXIfcia|$fYxXz3H>u1Ti;+{A_n_*|9FSXM)PcXPpKyH!>X4DiVN9_} z7>*hMpXSsaBCIx8L(hZp7N5er3hjK{MKcu&PytZ3mWRs)o8U`jPeUO_a zjPE!bhuqN1MR)kwDAnJ^#(%#=*fUF3ypT|bpBu$Wq7!9{e4y_lstb9cC)l-X`^LE7 zZ%>a{x9o0ywmEV$vFVIx{iYvsLEw-uKKSlwesBwf*TG-mmH@ZR4Vk1EjDw+w<3*SM z#rWQ&>wO}4@5lH`a(7{1*}c_e%-W-W8bfsOu@G^@DYcu{#5ttYFPV^AB{^hCByglU zbx^Q8Ie={xV?)H>6cRRIw^+kd1un--80^0z3Uey+y>8`$*&&MTlKg-b`uT$tRx$$p zA+DVmq^W!(G`{Qe4C}5*hFTKU*QhdbZ@HTIoV2`c8dIgf8XWPlm{R$dk+9x&DALq& ze$fv(I2wfcM6k6j@I9hNiehBFa>?>c)Q4(B-3A1zL>gEP9ABOyqSK-&JO2<~7HG3z zC?bwT#}Kj=Ojv$qs^yEHiU+yu*(2-J$vZ1ZvEbLi2UA;?-{Ffg_EVaYI;j#p5!|^d z`#C~mAyyey*-ITXf$3fqV#m+dt=AdDsZcYOGcmjqq?zXW@u()U|CG9=FhUaESE4?6 zRUrKdKY6OT`XZ8)b@gc_nON(Ojs>OZD@--I=Sgd-sr{*?#0x&7uq1J>Ol&;NtD4~! z3ibC7(|ToT{q%^?whh_QwU0?+s%1W#4sw3R7s8n#(J5e56OxP`H9y-1LTP1tKZm$D zX-q^+MJoMoG)*-%-89_D+mRU6HO)=U)lK`(gir1(TAW1w_?{_2Yj#6F`XS}dF?ri4 z^Qtww_i15BY(9Lt4p&@`b=)4g3A;2n7MAF+=iaim9`q?vlpjN;rQ? zP$bZ9T9me$>D?UlH*lXj%&(c2nA?_lSfq-XkzRD@*4jO4UN^@|`Cd{f9oY>ZlXgqi z0)F4QVtLiXB|qkrm{5lyNCbOe^u=ecVGvsJ)^l#u!9;Dhkmm3(qN>G?Nxm{aSIj%MgAW;E;y+MAL zx0Rb*pU^?!hE>1Gw8D6uFMP}Ei)GK1pD8CXpce!&2e88CY<;RKaFsMIeB3A33Ob^$ ztayF{K=pj_Ci9oabqov)O4JHi@a=ReG2E!plXp?;~(H z&A%)dfA;~~)SsB-Zvm}720;%Q@9CeY1|ZwtsMm+9A`}EA2+Gg*4~F@-2G-4@HF&$% zjLAS~YFB6ySamIzFI9!tVNp~K5AuZ;B<5^rb;}AI+hPo|r0(3YtEa@Rei#Cwsz|jA zIjlbFCIx)FqnKNJ*Drx_btLjrtlqDY4$6s&b|~hTFbaxZRQOeft)-yx4w|_5q4k!6 z+RyT+@h%MEK~>ncJHFhww9#bH0&~F+9hn=&;Huvq(F})I*(E`Gy<*L&5XXrFx?_4>uwjb0V}{550(pd+OC@4Z%^e>Iu z!Sop4Knbz4b*H1PWt(a|d z;oZZFYd*v;l~1z`N4!T|t%6g4Js6qE>p(&nvLP>y9t;6Ru4quxdQVR)7o0jq%QQt! zEtcHz{KLYP(>vlnib@jf=X*I2|Cblr+fEnBO6K?5OH|A2(`^5SR|W}Ef$ z=!)}U0kUESsnlX$K!7x%i6Y`(e|ofoSi%h$kxU#2s=b1&zNCsly=Mt53Ebwvf&wEm?P{D zDi-WOhfFczy7euj>Q}%>H=Z|nM!K*-Cd4e=!=jnB-X`W?CTRIK?FsK{saWqD^aXoM z5w!L@a!-&!wt_d#vr%OOGOl0p-VVl5HEMt3y~mN_2Fe7mqfEH?AFXv~hVcu6Uzulgj zok(isnh`%_%Vzhqb#*xtrcMS-IpHKnjw#QMw;dBBP5It55hW$cy&p*?bw5?0x$>iI z6nq)4?f8~8EskrA4})ih7pN*}w78wn2#xiBs0YZvD*eFAqZyy6%8uh;PuJ?Hw6G&+*q;&-hX2o3W$O*2k-_JQPyIGdBH2g)JeU6 z&@ZN3V@aFP8(QBLL})QI=s#b7&7x;pn3UPutc>;%N#YmjGrCcTcWgZDSFUY_rgJ+U3nf_>iIsl_JDXS5@Ap)U)^b&dI2F;tM#si5&lllu zZ=5UkGTMDwb1YMqxr{j5>@zZ{^n>i{1&{0XUkVQyZC`kUf($^6f0Qpen%p`Ap)%0j zY&+XJ33!-z;@9MeTw93}1SAANg<5{Rtgrvz4z!qUDqGD7jKbDxSE3kl*w@q=wex|c z>T$ ze&SRAvAd3xRbUAb^@g+Q6Fu;Z2ljAY?U9+kg&rpYo{)hEPTcT&+^eCXXnt&+Ut+vL zCZ?lio!JBuoE`~1cF9HPXz?^}ny-6)PMCb;z6!x#iC+ih`>V57sggHN4w3J0_|UW| zWS!jFu3C={wE2ouv$*Nxf@LVwSTz}e!_{2G<*>Jxd02=?I^PY9fGjB+`g+XV@kiJ} zFoiCOD148_B!2J&+1uK_2hBGZ?Uzrc9n$P zgh%|SIY%bEFL`hwqnf0^55?&|%W3vo_RwYQ>r`ugq4L#v8FK@c64VZSyes@-hQ9E}qt{_Iy_0LFB4fjzpK>&jj99H}*t4c_ z-MGy<{OOvayo%fR)M_4_xMivFcciK$rSD*4Z3|-%KEJNWrq!`ybAWreABdpz z_oTWy1a-LUh4zPc&uzp0W5doT)uDY_$|%CuotPQHAGy1LuEQqkwA-D@8^2{1P|iY#924IF8MBOSDL2dI_1nD_NDA~(q*9Ix&0 zQK91pzkzDm`=RINZ0i}!0!U~sMEd4EBs7dx(Y&Mf+fgu_4DsnYwrPJP^+8p_xcdot zkiYi$TA81~-+Dg8^TWu0q$20ELHxut)@gc1JTpe(UY)l`Al1@ zLA7=dU^{GXZl15aNQwCvgFn>!A`f4N5^yPHljx=|z~o4vWX4CJ6HcC_=jQf5og4`l zgP$)@uUIKcGnl_P3$Ig!4ICVlJ9t$F2L4|YCc}iPfvCSAUaM32UR!|gMY%vfDAZEV z)?SEo`8mMhl6}%$d%H^gMgE)8lD+(Y{f|%zGH4(OaJ;t-BaJoWn1ASvhWj3__69xH zPIkXm9_;Piv{g?3`PV{D^n-<_@V{RD<)}myE)kW}e$%ZfM|S`KUJ{sxDE&4fPd7O^ z7WJy~N$~&l6Et#n*Tnn=Ch5O^!l{;ngCj_hKE$B1{-C<{F)4mMU5|;FwN|B%vi+F$ zbpr!g?ql|Hqs?S004o9lQtO^m+ka;IAAf7v8`R~d4=Okt&VplFX88bJ+_$ts$Fk!I z>2P@1bXa3xd(_4}M(K@VYYDtsURqw1?{{K<{W{LM@f#Aa)pCFcpv&x<&>e7heOVXlQbxP*1>cJZ z5jy)&eCRDg8W--beMPkYN`Q;Yg{qPg9tNr_HvK?s zZhd6*xiyza^HT+%(EgT1;-w$Zn*=U^axHfDG0eBjR zr~X-R2i6a9C*GdXW#A#9#4>An%=mvTi=@b+EdlUKrTiXhcy_e5Iq$`=(sK$?dzWzP z>FoNQR7=&*I~f0Ewzyzzl%AVIw%wac8PbpLkb~b_4%3Ah^M=})7#q{PiY-@Vgod># zF&d)G@#tmKFZ4X_)jb3#fI{tyQ?2xbPHJ!As11KrB>mn0wK`>TxM!i+`Q)4-%o!~JXY zWG}%U70<7FNk$aD3NeD)^<>1rWYHt$Q5XOBr%+B)L&>B*+yL)^^J6WK-8NXaTKiW> z;lDQf>+ck=jAR8UE>XUylHtwmX|~(^YdSwjRBKD}WQOfEEhytHUwOC+oqv8qhNm|R z0DHT>|9dc~X(!a`&r0!RF7eRw#HD}yjE{tHvjjGKn7A0qyZ^hr2&uf0m09=YG(qC5 z?TD0Dk^!6P5WiMi{(qnNsfu(PN-Kv0BoADI&%Imiv!=k$p!$Pt; zzBGFL`!U69eoH3NMXnR6;eEnI3QYR3HjYBN9f9W4N&%`NKYsieAu@sfHgs~q!GHrk zIckmzupLH3pzjEk9FA#?&Uzq(gj1bN$Y{!K@4_1};J_9DTzPND{~l6nCTIs;PT~N{ z2{^owE?Yl4&xF7#^2Oh2DS1S`lkt3kkx}*Oin#wIaNX%({?#w*SFdINHOL9j;h>Au zp(W^SYpn21DLVI_g~*#vXhnw+#_ib{I!jA?7vq-PRn^r&q`dYkfTl>F_5bfRXjW&@ zW7!WV@&M^2z_@TCn@Z-6U$=X9|FH$1r|(92paAc2^hg`T%RtZ;^sfM3?s(p&a`j@? za2D?CzvlHdNS#CFuL1j6k~Iw&3AfUeP793+&rYzV!@!h6hgE1x+U(XGKT|&u7Ds&!-IgcCO}?cpv&pO&u)-pp{27@_ z$<@b``m!d7E&-MBFfxJxit#wmnSV_T4)*`Nz<%jR0-6oW4~HHAJ^o?Tyt<_&R*~Lh zV8MxuPR>}DWf0ei;WVimB5h|QVvft%t@KHe{=&_a1O7@d&h_u(ew~=mQr;3xc?N$R z`&F{!-|EE5VLz)n-R4J1es9n8!Vf&i!C|W4q+PNHh-|O}?w6Jy$f1;B%Nl>EA%oX- z4;3J~k6DIwF?GubpJGobm(K1HpB}mjm}i3H%e}dkO>5k0>POSkp{$2g(s9WFfXxH- z6usG3tE#hZCmkV}aoKMhs@r%(jjfaw3Mbg_k_fDybz?zPOO>gR@2le#c%!Rot04VO z<9ioa{Tyq2JdM`(R`m;x`W|EbmWxu{2ik+PNB5B9!aRhP6)dF6tDskpXR86PZ+72rA@}CLYabWtpAinr z`RyBYQVcEGdt~xyu?lAcpMtj*$NPtm<4K`;Ng70@Al?GVfAB06KKByW47vBkChdJ6 zJ(fGCua>!JJ|eunOi;3y6+krqr$?%>{t_^9#}XUsJ{UVghCEQuD4}8dV7yr{7|%(eP)pzzdRoh9|rsX zndA4-{uaNdFeJw(IL!FbUXh2B1jmP6jZh=LL|#P$d!EcM0jB^9-NmkMApCdyL?(Lu z0ikW3PobY?wETI6Ve=1W1`EB2h>eFXG?Dq~$F$++HAi}M+s^PEQDk%6;Fuio?r=ls2(0E{DVP4|X9&Q>^0zGkaQ()aIT?TIXO~CWL+IqH z6b|CSpTH{udBwrO!JriE&1Z zp3G@Hj4*L07A*K6?DS^*aT%-aHK1Pwf)Q4|26o1bL&xtKB;XsPP0(iDR`1%FSos4U zh3uEx;?#H?d7JJoUpJFi`dkcsBoE`)->R#7mBsIZ2qLkZs_(rY!TOVF0OgZ(Hf%)ZR3D74152=5DfB(mtvs)fM)EN+{;Ss;d1e11qdrR&tm|l5d zAI1d&VvgV{pM@shZ{_8yA(Z!2hs{UAFSS8IsXsos<~Iu%YapOLygu3IYaH__f2iK4}pdth$mMn7p2!@A;k&<+cnsEhJ2a9tSr}j=G zV!8m*(kz-*ZXW16I+5`Kau(3K#f{)NcF^`-0xD;9d$VgDIF}o#FHdJ?W`Hp?2Kf*F zGvU>eU_Ew>+Ugsf}h#Z)`DTi zV_Jp3S$KG7P705n0vNT*Kx*T9-q7!vDB_s^8gA*Bj;Q{0bubYnWa=f+>AsXUq#;A;pLvVz1fo~%J#(DEEWIVw@|=2;5d82 z?Ah38ztdlu_)SDO@&p$+zljJPu7%+v=i|z9k=*jym)-P3*b$OX$QW2rI+%F$cC9&TmQFVGEhhaDSX>$9<_zVp0uZP zl?dmP1qXdH*`nkp%%wd#IRIf#O-%)lU7Ynz6$CYXhJOTulM6JOkk}qJq=4LU;{kti z^4ovr6N+WWG|f#HM1mOJ&Ceb;viV|DdTxC9WyjWb;%!|WONN~@Y95z2BV-BIGo_O$ zl(X#W>gndL!T(@al@(-(+Wp?&NeKHt-fYP@p9rS?;ml%2LpIZWPu35|d?ib-B7sG2B&fhGc75IVO;h;YsJLGt}(jOn%s3~kLU^S+6 zq4gq$_sz1_p~#@&pe|TEw<@jI&z>=T4mj;XlW64I<7@D}IfXnOXzA)F(Rm&=ZXE;t zSIoa_!)bp=B8`W#Y%_Crq{qg_XyZ*@z4~Vqm_|fvtyh0Y9bel{8Z@}!#?;#v2~g%f zbrGJ#Iry%3Tpj@h-(A%%|Dz?3armk+EtA2qfYr~v zAyUdu^}57Py`gxjXyS&uZw6c3@8HmiznNuL}6Bqn#aM-|KFb?TGfV^vvc! zT|3-5T_wzL=W62wur7ACw%bJ|!@F$0Qqgz2&wn9Bt%t&)D!Q{b} zkGZX(XIIN2V9d9bPb5%6RP#aI70nlqwKe9Wwi+d&VRekmgu%hd>juvgCC{8<%15TZ z#&)I+m|BW1E`*LJYiudsj$pQ3Ws`mkHc#2FkIn|fTRfdO*!w(gwH-?dU0j=Zo(?iV zb&>38cb9Ok052{fvtDbGJYm=YGqI+%@_PtUz0qF};D(D7(hzU;nJM*|20nJK$Q<7Pkm(T`hOkaWz6g8Ukhl7&EUK!E$n3r-Kv8BB_S1vhCzd3+$Gj4ZJ_zd*$jbMr8N>PuG+u zi!Ni&{;pk2f3&+`uqt(JSReqh&>V=)tk-h=MS%PY%NbT(_m4}4Pt|u{ z(xdiFil)1J!nVjt|BJ6ae{z8(W8~gl8Or+YKY%!M{`6E%nO z%0EfREkWf0bz7g0oP%E=ZS%hv;^D~E z<(-;E!v8q1tsnnP;wC`DA$WQGIKj>uGJO z^eAm?3+B8z;PWb>gCWI>9Ne#&;RoXbey(I7pWET45A+WVDlG`;dt09$0T1y}USr`8 z6CrarvgH@YxvZ>B*@$c&gPY%D$IO867tz(rTVWt(jzlXFZSAvcX6XNl8=6c?2-I|? z^n-bcqS8cB7_ALinTfMO7PJ$(&Brvcwnl|iwY7y)-ftbP=SNV?|9I%@3vUFH=k)aS zKkUxxwsN|kPTL=jHjgeYUbT4KaQ@)oeRI|6&TTq}C2EZtk#yM_=Dr6mz~~WpSymzH zlYBR~AFsx(>W}joas^ab+iw5(l+5x(L@#qkcxmUH+1ohaF{FV}74wnbi`H%(PDs@+ zEYW|Ch}x_*PKm3VhT%1aZWxi!+WyX>`h7a1ea(UG+}+4i+yZ}mVSGRKa|fk=o+$%Qk-vs~o4eBs zt9Qam&sOGozf+?dJ)Ya>WxX1uR(DycNitK%PrpT?;^%0ZefS;y&aRn~r}3^0bNT8bM5GHN@}EhUFi8xFxCjv*v0N>w zC*Bms?WOY}eoj?)`{Qa8?lp%(P>*LPy`6w*wbhWh`%-)cOhr!5PgbJfe zs@0Y=JymgI@Vkv4vQF+@C{on=t0aWrez(ea1RYjEunu(w3?u+GwtcatE_1~m7i0AP z=XZS{<6@)4G_$d-T1p6zoD36(dHZ(i7J;uw&v(~3&%$Ety}LUBkQl09we82dxFyh= zU6QtJCiZE4$N6;KFA@)^x+7y_M?)WXphdNT$oEVs2Y!?@@=^H{)^6e=_avgah>VCZA}xUbd?qJ1ytL`=np4O)iTRk~ zQthJ~sjunUe!Dw-J1WqJ-0hgRY?*Pbh*r52N9qiy&-%DuM$!r+;|q}GlF(abs_q3Z zL+SH*GoRrb_oEZCwOP$qS=D3wT}x(B2lVfV=)GEX6yy4(Fc22HkM@Eb9ca=WZ}K0S zHDA1vX#$gr6Pd$Tk?JWP%V3bY8XZ-_pDa#~QE7oI$6sQYJt5i@URaxRA_E#*KqbH5 z38X*W^6q!+YZ07sL=^ED)Acc$C@t( z(b4Db!)}pphap{4XF@==VAc)P)Z8x&maqGG!MIqift1#P`vS80Dc4OpV#HF2$Y^@C zOEZ3PLX1jn;0)qD11?Yo1GFAxniLVRWT2FJ<4cjV1@dj6C1bx6x>0;g1ckR{Uer@V z1=7`5koBlmWC)E1(!iU-g1oxn5^glBC%smbT?Kl+-&ei<@KC>O1WyIZJSoFKMj=p- z)uTjDF~^KVI*AS>`RL_|`Z=1GD!gJhk)AL=F~2PCwZ>lE*<8bA%BzEU8bk~;ou6+1 zr$I1Khk$0^pqXjnPSDd>Z&nGvuuyL&Dk|z%sa9bkxPwNH#R~x*XZOx z;tz3G?pnb2B~#ALW6P+x*l*%NH~nl$Pw_@iJ>J_nw137`-|ZWuPY5b+fK>_ytAkTR zXDvVxzrIqZW!SqIh8DTru*|@TzWQSU4%V+&trkb?PXMJF9^h6Ionm%7W_}$}#|TH1 z`}Ik&uU7liFCg%^aZKQ0*HnOt0g%KRuU$d1IK3q2=q@~g7=ezGi-d6$eN&l|n@}Mi z$V{#9{e?ABvXOihFeT2 zK0D=9f|+&0%!;A(*?^;$3K3$F;zFq2YXUA8+^xeyh&fELJwd((A#}d$a07M6X;L7* zC~yXAbqA4r`_m_4P;-&!`5x7-w1_wPM)WD+>DKU>(9!Ze<`YS)fkR$F7A#LR%~^K} z8jek?LI3XVi`|P`Q5e)P&LdjiWf`JyxL)Q+&)66N~&h|Khe-dv*&*aw#Un3Di`MNd=nDZBrptP!}r1VLMyJ>`u2ZuvW zC#eZ<-u)!zwNwmE+QNW6k*$OJi;w7opiFE>n%8xX9&Il`;SPhE+rI@ChC6dK=+DGF zk}k+p^T~tk2bfHd%Gei;pmTnHlOC)aZDI9(VA;y=#B2-Axn6%fjSl5Y@m*nET52jH zXj_?OE->Nx>F@Xp=jwgp(Sy&7_3z?eDAP+9xsjp4lv9g`ff}YQvX=V{)!>`JA+@=r zUuJK8o2`Uh));f-N}M|rr%E6|HH+A}e0C4+%Wv2Ty%<#2sr;2@Kp!S&n z<$Qx7bbQvZ-tO)*=|r4%%9jd1;+_eo6?~d9vxAdRhNO_aBsc!;ARvbWCIbcn`ZV)X z#p(pm-24X4O1B)QP%{1|wfxXj9_dO4NiUm%+OF7*%1^ypFgzl z{Y}I1o>UHy%9&BUrvZ0NqS4!h_;#=nQw*6`Vh^M&Y$NH$;)`$s4EG zhrRSH3dy1`XdJ!GzLev9CK-Q{8h2B)PD6;mj~(;Wd>IT-BFyoq+bqcorb^L@QHg86 zDPmsorzLh}##g!~4|cnc`QCsW9LQ}tg02`rLgxIxfny2WypIaSwgfWNb|0F(2;sjrHPPJMwzFpo*W}neMffSp8rR7afLFH6f%C&f^6Qq>`;a)D8EV!;dem5ic(*EM?$QN_DCDO|G26{+DFY!@) zM`j-lN{z2pihpxGv}-T-i_VpQvu??rH2)l>4L4^7QC$vW z^d%*n#&R{k7R5(EmyKJpCz}NKQw$6Lr-jeND1u6tHD_5?*0ONoB&eLz5?|Z^daq#G z+6cgCM12=Zy&*sN*PV}1XAuwKngbctMVH?eOMuZh0spOtUq^mvqD+oZMt)l;dnx3Q z$1WwVj8^NCT*RoNfLkr)3Xl{Mn6E=Yk$o92XO3El-|qj=bQMrlZCzKoLqNJ4>5v8i z0m&<&ba!``(j|=`TslRhn@dPZTpH_o{!24#G6*mH30RRJl?MwBlFNrVNgDabrhsI}(6X1#ptc z(8~L!YO04ii*fD0(=ph|q+QxT^X|(B$+xvL`1xi+d0#B@74%S=JYHBtB@{t6J|(26 z-IDgTddMkMdT18;G#R3|@)T=e(ER?6b_&|I1@jJ>a#CEvwIuZ(PC7;1fhN-NqSXHd z*pMxLw^~lYVmdmkn=LiM!KUPtBXLU+H-DX9)VXiC0E+!+S@>vna&>hT{7_5f!uG?m zh>z1yEf)Qq6pg5W?3cMIk{Qo9EcU)qMrq6g0gY6y>LZzyfNf!IUz)+3cof4=^~By_ zYWb6ru=@@+z*I!XQW&i-$FjJdJ{z`J8$0<{-VW#kF1yO_6u2{#|te^sW=8C4S|jC5o#gbv|PprVkF5KvL%8&A-Kkk?Z^OK$d% z2iI1GR*!jtM2RsfKs`5d%-r1xE41KIi}hyW`{au#lPa+(KSCTW=8~i!sHqLl`TmiA zh{jd2&bkv65s5~l_IaXRW%Ob!Np87zGcrK+uW_vuA9SQZYq1v~nCyQng&h(9Z1f4? z-K*~GZ~>iy4bYw$2Yb|*2mJ3q))%CCPE8=W!e)cti_WvILb4OfXlkp&k)Old26(G$ ztLi8>=wr#Y4_rHe-cAoNLjq!h0Mghro1@Q^V+Wgrg9|(MPe%d}8tW1Ee#U|Y+9nUc zPN3Ok9bk0=p$h13#gqn2`lG%%LbPey$T}Gi61k_~zqF~;jIuHoy4O0%mgvukj2OHU z1nbk-C`cRCqMGRsL0f>30L*fzzZ8EIphbW8*0SO;A7}ORwaVAQE1`9-VfGmT%@#m1 zQ3Gk_*e<98K33P4g30|Oo}BCrI(?3bKw3rqPld})c=$~mACjiZih5-D(r|qxbHTDx z4Aj&uK0o_cUuxdx>LBmWqG(1;`-pzJa(`Et2M$}nTMqo9><2;+JG>c$s*=nv7rAOw zV2LPUk5v|cz^S7Ml$t~<*wI^bV{8E3g)6XHPsbGERW~n?g7-+6>uU$TO+kX@9_ z6$)@D)tZ|^+dN*Y0kJb;H6PD z3v_EP;dzLDCy#xF*VMj5pmOB`^t|bPHA5-Cfa`!n8s%~&3m06|xSCRT9SMNiCtEKuBjzZYHXKPI*cIdJS?ifhG^Qa7 zzl;$$|8%0tm%gh4;3(j|(&#dPD4QX~it@f`QLaL3Y82yf4JA+*T!1UVeBf#t|M?zWhkj@RinNIe23zKo=!>LK$9^bfg)QatJa4%fa{9NF ze@JFs$L$)_DzsFa6FFBb@YG^VVXLJ_vPGT;w85H;@Ff@s9ZUFsU6M@Faf$!oV5y77 zo1f?JSI_mlJLGNRBgyog|0M%xM$c}@frzCJ2l*K#*c|VfR|oUiwnSh)V@|J>OgU7; zSYuQ~(H1j@{GQ#m5}kQDKL~KGEG&?JenvZs>Z`w_55K9Hw#)pHkLV|E6Q$8gI+KNKLQ%Of)j9CsaM()&KTNmpa&J3$#Sz+r3>8SimB z+mgKYlK_h4I8-^H6U-ius8>P!{8J3?3kzN$-#3{0`?$)HvpeP)g0uS`!>bzNbpueU zl;1fYA-II&Za{!nt$aE{9*N0&(R>j0SeeBW6Mp@$GQSU^(8d>huY5J0Fh>&fl5K)T zr$|nveJKS5obTw?tz*OO2OgqGSO|kDVUD}6;8-6R6@eMY!ck*}jPUSP;#kt%x1vD5 z|FUMVwMwGYW{L+8*c%lS)6SXwU&4tC__9OyDOB3?@^%hdD(z+49KX$lZ$I);z%D4A zBID7YYz=d1U;Fp!^#fp_0Ac)b?oiCVBMXo;_o*XB3#7xN*#biee@zYO5fm^w=qvEc z_AglzSF6cRg@eQq-LiEZ+jya11wxlpaYR~KPeKec3EvvEH6Rxi5A4|*kmOl*gXa|y1iyi(q;=0*ffoLoUayu9ntq- z+z^vIniqzyw<}%{fhQ?J-KTUUl*cs2uei7-lh$PliUQ9cSL{~_SOGwX5?mIx_$99w zE3&w^=D6r-bw+#pd0E)TM(ypCWyuF`LvPv!h+B<-poQ~8MMXvMKemy%#DlOlXLt80 z;k6h|j>ptg_!ofmfu`4K;41dJd@Sj6is>=_kvLSIansP=5tsaX&gjn&G=ELFZK#*M zg#H|8$c>DQ{4^S0f@sw$YZuKPfPhXm``Yz94?G!{iAUwz=Z^gRq%Z2k42q_|4D8Wr ziuj1dn}cv-P7Sy!Q%li=RN@2 zjzE9bj{&?5?d`Gp%v?<_8`|R}!pFV*d|&psf*PCyHQ?L413mUD!X0xV+*V3#<3AnF zqHY60KW&|`6iJ_e6M)8ryS3*chV}**8B}J?fp?AbczuIUN5LJp86jV2s=+qU?`F`% zL7v*CBB{(iS?H6t@8N*5;2=06$7HVzMAZT1I!WXhYxR{I>*|~9@||XX*mjwL&{lY` zfFNj8{3kUT5<~_`0cCLhhHwZKTfiy}t@L7Gn#ExM{Lbhx8mB%{QuDqCczvL`32s^8 zcpQ-_j8fLdDefXoy2z^W+qD7{?HJ|KFsu&}h~kO_M?FA5#OmEAnVr4Xb^ zq1h*ZOTsz!b_8^EW#|4Qr2vbo+IbFemZMSmK82NeY9Pa3$hcLW-2GT?JkUN2q|vhY zqTZ#+_}^DP2Cb|T{zwmg#+LbwjL~4qK2Cor{#{6;vKh5U;e-^pj7+;^@_BfSmTn## zr!b1A%tBGZu~ioebh!kVUcFdr|4i{Z zq~xxxrpC0D44hWfR?s92kbKEw0YAp3@8iEsLkYLHw@3Pyurzx7oIV%c4?c1Cf1j8I zBTKEX;3=6?3bKRuQlf=Y5<8X6JX-674WKuf+uOsV44<$P$3FHbvY2ca45fT>AO0@w z0&g*;rCRi)rs6`J?;Owj%+x#a`&EPiz5>aNDjEDfki|hjX=OLiW+NgSKI&dKPq`+V zN#;sPF>&advo0mNkj!s66mj^ii>BZ8W3*77evE&;Ic99JE z*Fvq+c4Q>r#UFP(FafAM0Q0E@ptffK`U^!R=M$8Qn`SXVJMIY~5=C;5PSs>&u%?-M z-jm3eAO-#V8r)!6vI8*=qT`Ilm|K8x7M0!U+v$+asL#wB2bL16L2sl!$NU!{NeLqA z#dwKasU4?q$k$+D9$ftqbRFrG7^B$pw=4AoY!blL0cGCwTK^LO*gQTlu}YP>`it<| zVOM56>KL#Mi)IUFON6C`E!9{&KP>Pq@salFwgO*$uFDqpYCc#IoaE{f}g1 zM5zG@6RZRj3I*F2z`G#Z2lO(1T*39$RGkqpQTR{=Y=(=KM zqbYYefy(~(SxgGB{rJfCU3{y)tjd&>{Fv#DW*A>_C{iWqvnBB0J3A#$%RnpfegNS) zQ9XxUs@z=id!}@7snf^tVGabQvC-Pf9o$1j7M>TpiTbbtXLSzW5DtE~;IQYs`%`fv zrCnZe$s=F4zFU0nv8YJk!B+oYJ_~xL)YK>fi%T_wokRzf2jnafqx{iJu9To-p#cVjMhP%Hr^ytA=_0s6diIkG2m9{x;ar;110(wS`c`^{|B((jWH0~x zX(elxsZD#xArq~C&wmu!xo@W_1-fMPDT9ENNigp)L-aKHUa`o7`#0&}CnSA^UX{Bw z#tOg^9C>OQ6OmoT@;VXzw3WlcR)GA!rpxnPtAhdzK=E4Tj_gAW(R@{-)O5;j*5qj69-!XZ*eD<))8|T`0QW1X8SG7) zRFX$|Y0@`4ENxPXR-KwgE~fmFhBjVHt`cv2i#YKR)zkT+#(FFQ_9$3LG;9>|XOw14 zzH?5zLj!qR8z3qJUK#>|s(XlmveCx^n-8(`aN`o+flk|^B2UeYlX~@S4Udb+?5v;B zfFP_!NdZDRfJdfgGvX1j&J`B;{^>^GE6#z<3f3K5GlGvTIY6WXQ%TUELZZrhF+~E+ z@$Q?n6jaM~x@c(2cr9(xF~(p977~gO3Ch^T$Hd)`>V}4J9_&xeU@s&+u~&RNGF_S< zktf>{*?de%Gl}B0$}I~%-Uh4?dDJB)Rw;8?WnR!8Dh@8)zq5 zxnFN|`y31Gm1hsod(^UR9?5fOi0n=J6=`h9rp;anGP4uhmxo`s3xZTJ!Swl`^l z4s!9=%&tH$84Ps&&rNe3^b!D{6l|~`4>U;Q2N)^+=+tkrYh z8rupgC%ulE^2b>$P~L(3ToJCLqx0x64(INC6wCnqTmT>e6oWn;PR5lc0teLDJk4Z@ zGOgCZ>v58uw{_@hG3y3g*1tv25vN?ExkU9Z6#u4gEO;6|lAM9wEkI2E$h`#{ADd+l zEcz=o?D=^HjT=NUZJ(+|1<>`(lJF-6=&F_Ir(NGib|_%rf;w}w&Vi|4G0fq|SYo!r z7j7}DYL|#GrF>wm2wJ@=y!k5ACOMu>i!Z8Pm4=S6P)|S~mvoaSj ze2nO^q_MX3ap~M6rC4VyVXF=LAqWI3(W&f22ErQz+{Uq{kO6}f0KMZ5g08?n=YarB zo@AjGfEm9Mi3Fh9i32Xu)4=yqQhc92Xx|UN6vKYnuHT)oN%|j}x^h?rK&&=0zTyAS zOhD+hmi3xi`|SuVVnTrbaxAeKpWq_GlxHOL&>;0owS9l{wfg_L0F>E~etgkraZr!m zJwrwS4H(eWc;uA=?>U9+ zsrjVi4i)oUxDv_*rXB%RpE>T88}Abay}`a({$vT#@Ffmatn(n)vf#aP4>&^ZPrGN= zw`9-Tw@fNACO@x>)&j!zqmklG;D6(TDLZz+7jv;W1FR*OgYxrRh?0qsPex(cO!{U? z*Uux9CLz$@x7<2^eK$|V4jgv|yirY-urs`eSI;*-BrFCNw2ak8CH{*Yw#5y30;2J( zDYvGmu$u{xdlm{TBeS{`AA6e&Dj85zWI1wifkp(l0O#iBq+rWh=US}sJb2ukoMhD3 zkEYnTpmhw~+`#_bX)8S#?krYFZD~%v`=Qu0hqW5-mc{h1_+f0@%{NafQ%1Lv7iS=%s;dFsOcX0OWu2n^o5Kq!Xn%ZY=L+OJ_|ePk?oGafw((cZEuJvCfX1wHt#W40 zkS*5e%*u#1m%JWYnA5;YUhOX1Ae7OLu##w2JjWxuB{%C^pShw?m|O%$foU^8NJb{R z9!ku?=LYovvd7X3aB;sw5zhc*b z+Wa|S&;y5@f~dbO*FKrjglS65A{|>-oVBm5tvS&^g)p>0&#eZ`ne~i|TQ$*rf(Yt= zI@jUleDp^Kg2Z492F$4Zq<{7JrXK)v9GI+<3jqS3xtEt$9%rJ5siK;L+E_fnWcc>Q zA*O}zvt0R-LUgaD#S_bQGvf&X#Nw$gbGqy+f#kGJ)Be?c7j z@h+|H)o7k@ntb>c0j!up#1GioIQh(Uyzl(|8-#CA%Pcm3zFpiBGm<_1JV1o&zd`Ff z#gSx|x&LgkjQQo%6H`R&t=eC96O9z1{ z9SCvXejZzlrK?Fd>vjznJlPGCKIT42Q5Pgb*mB)y?fJ*;$oj00+t)~5$uh<;Geeqp z_?U7jO$O?Cv}fmzNGH++X0UR{D4ce!!PG>9-j6v@4uZ7?3{yVI%Y3}DeAg=EOThY* zz>LWcdl-L(mvMe(r5OomCz*TTCx<=q66AR ziUV6>#zNNv$YOT_MM|>l9|K~(niQDG2>|{bu2;X_0lDFq-vfby1Pk00YcG~$^=Dxo z>34vy12p)!^Is6i0B{VZHC+^I(@c34RhG0c95@3a24K7u zX=5HTl^Dix!jd#cC&QMbsIWQ zcE*Gxk7V7v?wjH}ho;U#sWdrG1E1Rf0uVf29P{goot=QzKS;^-OkH0BKw4#`UM7F; zB?t*n1PB0!L0qE5hfj{vvYalZwXxg3Vay#|oQ(Ul;hp8>71`CPamr86>>jhN;JDum z|2smotU(0dJ(KjkXT*cgrgx{Gba{Drtq8nMOo=RRP74ng#B(>kg$4j3iHa*7tQw@h zz{`apWiU^NV*`yalsB<0VbIGLQs6ugLR(}b3c%&A{}B-`859kNMqrJ+)JuG*Z!_! zo`=nY&njRW^XNFOM;yL)Z#-MXiD{a@o8^#aWNDKCu^J7E)M5H z5}Z)67z$bWY-t%?pX>y+jw&r-_WgZK{K15@bc5ataXYpowU^3?|8Ey z$ZvtS`LMR^nhS%@f+W}Kr)Oq!)2(Zkr{zztmLcTz|$`$~wfC1|#bj)!4Xo zvX+yO%Fc;UE@^)NMM}>=6u@rNu1XH`DBhVq;Rbj z>Jb+Tx$*%HMySoslym{(q-kiJ?vuKVtl5@gtqN$FFIWNkOf+4qAddZNDk9ZPJcgcw zgX7DG$L(ixCN3f2xD*ef9jIhmIp@Mz+c?8(sIHal$E5)1Vl()-1!}s7$$~$$xO^UYbDieGZeYrH+ihND@$1{?psNQofiysA zc}QSNYUbxh4oa=ZF%I+Ad1)E9`0OT!)t84S0{p!YRZ=GT8|5zxRpu8J0a;+?qEhe# zcXMs|_{6B$V5YUGg3#lJEyj{OyPbN$R&dMUmO2?u5%*|A3o35K8xtqc1rr5z+vOJc zadXb6TbZE7ALXaG(k`DyK;R6ol+e?|6jH>ToKLhcdqbD{5a+GDAeOWllmtiwugam` zVrKVFG<76Yt=|KT^g8klvK+Ku?JOzEuuQm%i4DU$#yd`+U8uk*W7;mG%{E-7hF?ot zn^#1{Hq0F#84#E|PJl#0w+aQNmBt)WN>RS)jX>JQh~(>|QRyC)2$*WzT%C#Qvf;(4 z6UvzpvcN14+lTG5orgj$a*Lt_`}mRRYkPp?fkYl;Uv)QC2*J= zn<2k@Cpomu2c#EV^QL@s+^V;wZyhz(qmg2T1&&?t7jGbR(__LBIEL_8hdSsYr#V zLAsm|{*0;pE_`S_Is1p{KgX1$Beg}5J~0te?*lt*iiKqP!`kY2!aRA-Ct@NbVi*hU z$*?RX*4Ws|uo{)Y#D3`*Td|i3$XqOxZbTIvF{a0c#TwFu6KW)S`J_moiC%(Q{PuZ< zjMKH~&QX0wUz=m8ks?=Pizei#&e*((J7)6ixGA{X}YJFNVV{*ExH=)#mE(t1qsb0mkzQB941$hK2MZOMe|KEXIt?En5`;wW4r> zbnOsO3Z8$$mwO6M3>e-0f(Y<9v(E2HxkTgG6gzGrujV*rNVQm5*`t`E=j5K+GE^2H z)KJ`*QzrT2qeQ#8lD#|RI}SSB?F&|^AtlCDAsh!FNWv+TFaL{IkZCtV5^$AOXxW24 zAs7182hg=5Xp*Txn#@Q-_5GWCuP#al9$#svmI2LRszloSBeozvkUlFhMn zz2N6Jm*syQS^Gh4XTA98b@e57i=m#*7?)X6VDV9ENGR=gcEq=jA)CTtUTJfx>#NI& z9t+(jkyl=R@kGP651?0&L}@yDSI8Q&>kBj>m}xTm*c~c=p1vl#L4!<=1j{4 zk^s5lu5tN7H>Tc{!RCe#Ejs~b%+PnE@ghfl{9N*`u0~OxxOlE#MU=TV`z?SpE7704 zTJV@uD%P+gPXtfef?o{J8rzM_=%OKZSFTKz$achS@b6s=NF-KO;a9vi)kCgYX`o$8A_s3RL8Ibp(E#I133DpLK}5Zh?^JmR6V$g|w6UItfveM`poX&Pvp z*!(wN#D0yrBRREi;*%)S;lV`On9i8EqcMlVA%1&=c~U>*D8}t<5VC-mOribVnvbjv znEoyzUpAAb51*u6PEp32=IW9M!#!|CIt(#AGJ5*Y>c4ZxlJ2MS{u{jz2efF=NM*HU zCt{PS)+qbD;i&t*TMudMqLGZSM{i>OJ>G$tfP?rIPq0^$xL9Q(O=J7gG4Nay!KYr~ zo{;zkC;W$3qW4kMs0Xv(Qh%Zzi*|<7m7b335pdF5p0<1OUyBR&blgKwCxCWJ2t=5& zw|vNwDoYC$DO>Nn^!je9l}=54r#G9KHZj*=DBK*^?ymFY3e*h=*VYVELR*17GSLB* zD$|LOI>tZ3@gv=1yP!Mj)P&XVs`BzoCf{W&0V?B41QZ-%`U+g}eW?d8MdyRfKkHa6 ze4yH1EYq_5{A3AFQet3lqkSVqz5QxxMgZD$B>nDME;KNoQAEe9d}DWnCP>@IVGfZS z`xV0%07ckpmV?3MIR>EBFtlCkD&iAT6G-JRgC?Dr>BReOo3csq;9cg7#$eEqE5?mc z_-=g2hn2yjq_{iB*;QQjg}^o@(^A8qbDGtpg8+#_$`+Y}HBQ?B;~!IibOKxLgM$OT z?*(e;YOE>#w<&`b!!0tAqDO6MSJ<{aU*)g1(r@6G!R^f{k%NQ%!I4L41-2y5dh9fd zus9h4+~Y7{%!yX%Su zBaU;+K02C`b>dE4dE{qk^t+xu&w0E-(TTr~v!xb|uhErS|L6FmA6=6HX2*3Wcg&7R9~4Vd+^KX@+|*tTfhlYV2W3AmXNphA`IgzV z&`I50)N#btWZ2c0yPK5i1WoG%n5XFBKd}mQxuAFrjs&+1`E8{k0Xzavd}J_)0C=L8 zkvlgrBz7J}&oEJjqnt|Y6&POOI+{8EHJyNEk8Y|{wrO6TGG3fWVb-P(bd1P?vFxF)+1Rb;6&AUU3_)( z=3sTq3MiuDdI7|xxW==HW5a4lC-VcuJ(1~k0{^7{+>yH6hBtiLo1yJ!@XOsuS5HLl;X7Hp zgRolY1Jw)v;HK?NFu$T#k+yE`#y{&WGG9CI@JkV-2Q~WDopsq?>D*VJe^Ro;+cQ1d zk9c~?dJb_{xZYSf_WbqJX~n*&1-99^1zY?#4H>MC_7Wn&D5NB~UAcCKOeXJB47aDO zR)9I7nworHfLKyNlGMp_l=-~Vju_^{&EH;*5j(-Q^IdOmoP>v+8hjIlS#hcR;tI1i zmfNiKO5@aXp&Wm9o1KF?fA=`DHg5{g1U+^MUvb4EE*^*%t(vil2Tv()+kLHP0O0LmpO3Q#2OP7wT8l-umoXvP6WWaKP=e zCf~>3+q+#x4Q;HOHwqDiA}dh2aF#O9JQ>%fEc&T!3*_hkah1bE&$U5e_0DX03!1Q4 z*s6G2E}@Axtg4o3PuOa*Iie4e8@Xjd_Abr$YI5&CX{)*IXvf@CKAMb|n~i)*6p4JJ z*FD5xp&Ym^(Ah;>y$$K;zsn&EMn}&d+TZ?4aL3*c0BmkqcOtpP)+U}J0HLFb$hl!T zU&!dldrgkct6$-69=}?!r+Mam?u6NZ2Ms;CjH{RFZvQ5|c~3($3aIA+f50UrX`X4x zm+fR=Z2-=iD;l5SD_n@FPvq^}p080S%vC_?&StaTY7r}5)1Ddj#wIhb0~#A!A8qY0 z_ojv`+a>~U>X9JvZ*`^VxY5&a8L}e8U9c@2haE-Iagin4Gb4l&*lH@qtp#z?F; zCSXxoABeY9PW72z@=o53riT6Dy6Qw)5NpJR zYR*I)jCJh(XuZ!N<&Z5YcnT8s`mkZu@g1FW#fO6~pG{_R;uxM`Kz? zn7qT{Ip}+CsUE4sC2Q!-uUs`+Tr02-5+|?4gHAg2Sx4} zt9t+Gpnl}QIPH6lq9l9zKSsq3YGvfs3W1ITv3-r=-u-#|1vn-Z)1;;p@1I zl^+K!(YtNYhAK|fvVZw^We+;{10=bxzLJ8UBPf;3$nGAb&ah2U+C&1rC%E5=UT#M&co49zIG6FS4Hk1%3=C{SD>t#Zq+UyaTgu4p2cq_BSPUYACF?4cHSk8fPB5V=VA) z*Yx^S(xo~QqneZ8uck(90Sg8{PFqTyDA_WDqB&SU)n(YKP6K&V5V=O_?Vap$D`>5Y zRsNB5pilMAi0D%Hb%D~MpZR%^Fy2o86&Nk?pVeSGSbHWZk}kP({jqFT~6bf(}?&;v6ot-&$_J&(76i zk@!-vom_l6Yb?}Vo!O`>?|K6LDS2=cb|5T07cgPPL%NcuSD{2CS6M@0LN~H_ED15C zYd=ZyfL3Ca&!E%n99rAOs;HG{pShFJ54VocDe6~h?2`-D73bb2zZm+^zOD#?sBDPtzITfWDm&n_`e z1z}aja_O%*#k|v(J3k6to-LkUmOKzc-QZj;7lO)sPX6ud|M2ctrG)SPK+eU}IpB5+bOI_E&! zoVzW4<~wj)gySoYM@`f|LrMuE@-OcK2QQYg-v}qT;J$#4DE|oG8GIM2@mrFVPEzRZ zYaoHpgmaB*?nnnIrytct`y1`2qtJVmb|db-Xg5)UUk7q4$QYkL2!fMH?}Au!(M5wl zrZNd1@O+0`|3=`h_slaZ!IQBrP8l{>)D}n-4DFqByc4@cu6ORH%d+P9V_=VVmSvd% z;wwu|S6-rJMr>VZbXQNsrEjx?)TAiyHxa)K;b}^rXIvdzuPgbqU0|^)w@`vD_=@@J zpT^f7T@}0&S?C5TKRc)KS)_P+({jkIlg_>s9p!Xbas8(fC!1Fk= z%Y+rMb_ZY61a57EAzK3@Zanw%BWykrd!(MGlr2KHfWulkE+M)cp?L(D;z}EiC!k6^Wx_8-4qtZ;mGv-CHrDE}Ir<{e^ccDVNJ69unq z(rb}9cx88$%o4o!qD1>rvdOUj-{H`0vn_{zTsd*EYBqkmun8O=M*N%Rt5!Kde~tU> zaIhfhJs>%42&WlU?M@1R?;kjkQzYt`Y2%QWrr>>A$lJ?ycM0KoLq+|IsOD_M^rj2!ujiR4h!(^TJ z?Up#)TO;ZSb;#-qP0Bna(si}`TJnRaWPJ-HzqbyrGdaPoIs+WfAD zAi|-h;TgQt3B{`?uw|(DSn;%7%Z|QECKAp54=3u({1!h#!p*Om3Qc{?SsVH!0iKIZ zR|{UZpP^9}#)_M*H}T59X!Gd4xVnBSDKjuI&_RsEu<7wsCkn?#McTi)n>_Mbp0;f_ z^4_Kp#>i-sp6P(N&?p|%;vD&L*uUN4gdZf%G;058MGkQn2;8`2ruta^_xQjpZzk!2 zuizTP-78Oh6afKjK3R1O{Rq?^@~oVkA)pw&Hwv|?W2>82spVi-O}dD-LAU+rwv)~0 z=*OW9U+cfbI6G)EkTbUJl@+P^rWmKnWO2CtB zQ!yC`9rIK{1K-RV(&vU?w*p~z)w5hEs-lD2ljGXq6y*+VRYrPe`__K9f{rsyNwnxo(UB>MaJJ9Y85|jH>VNVF4Y6J< z=Xq0Yth{}Dr-c7G>i3XgtkTbvquL+`ZK?xp2`w>-LkK6~lpn=2UV}No;R}NeVXxy0 z7vcJpVUxKhySuyK+itC`NrliRf=y$a32qax{WrB;>?^cVz{Ppx_n_g67B5#ofMw<7 zeH(CtF=7c*(_YVcr|Fatd4Ay~OK*+hFZVMXW8jqQA|Hf1OQ z?v8otxSTp;&$=3FXmGX#xLsjD&-MI#TN%hr5+DbIl>@v~5D&nPy7F5NillCKQ@|p4xV%4=oNKG&Y=B*m$({>tFv&9-^3hhRn zy^aP}kvUu8cHOZ^f_gt*ivIl`n7`IIy?`nM5X)l5G&YuW;CCq>4k@drFaJ#kjn)(cp(Y7qWz z-~ZLC@G5IbT()WNDTN=;3A4s@ORO}a{&?IHctYQ1iP0WK^_}(nCk3%0;L5#|1wYcBSn1 zG;sck7|s-Q{jv~y{Po@%2wFD za?W1gJZPEtffs8dnFa+VC785hQq?4jlP6}dLtJo~5`Ov8yO{FGOCMlND$Ins9K;&s z(?#HF<<KD$`CDXVv{ok1O{&ndzFIWELKU+W1L+@JSRDcDs2wugx4xxb$;Pq zv^a2?mvN^!Q^g@?oSgNqKiZpTVcz@v?7)N|EoO;A(ys!s$< zg$B=kC}HR3op_tlp0VZIYp!M;W3{~wqFmSYavW<(D|Lx%NcM*u6=ts5(Isob@d$lj zoayG_vGpr2vL_#?hO)(Ux6rvrx?sy%Ht2D-OmYm=BjNOivQXK%O46 z8{wZ70*}trd>g>^{uXY$1vJhgi){Ti-$$xu<-A)=m&_mT?5tu8T_q%*X_cppoehxm z-Vlj52fM}1&+j?6aYsGjpvfEph$ibp!qpT}KaK=cmmzf67*WRPwmU`w&-mV~r70hN ze(%ZfTa?h;(5kHpBR-t|qMA7Fw}e$)#ywElS!Tm?-u&k5_bmu7{YCMCXGG1nqC^q0 z6N+YGMFJ4BM#sjs_x1)L^x#DoWr^g@!N{)yh{HxzEMP1-`y2XiXF;eFta{nWxK%Gg z6X)p>oZ|YEDNoDV=K@x+as6Nw>2VK6EMGja^@}xJEBVFf47zLBY>yFVZ4=LM0w$0v zxCuO#^O^0L?ScY&8Ny9jNk~ZK=TLj%5ndIpp1=!VCoqn=+X_M}i*RA@zeLNQV3v{w z$C~=sXod!xU*Q%w;adNlCOL(kR(Is}>mkIiV|j8NHDhqCL^wBz%xJ?7V+(tDeH(imMnqIJS+9aw8ecfFWolmmJZB2l)8kGZ4)6j> z<u&*10cRh;&8h{9&a5u&SL^ODnWki-2QTb5wys$yC{676!0ci!usu8l4HPt*zSeo61T^K7XO{=CQ^2Vnez6)+L!Ybut%m#6J!LPEQ7}qIC97J5-qoMIae zG^&Cz;&FcSwNHWz|F&oLH70^G|FqOTqNUAg8|YSt%^C+@O~;}4m3uT*(Yv*y?3L#u zB{B3vm%RhxZ%~WkP8f>*ZEeZ^1?NdInbE5jyfH^X=fkx=SwjE$ymfAiJ2{glVA+7I zfEY{L53R%U=}17K`7e(R)C*CsTwxh!-O)2q>YbB|Q#^DVgZj`&-$?AUjHbRO?RlK7 z7jdct#e7fapb=L+d?F_ z9wq=WbKvfdL$!4uLPdWz`XZB%t}>(TYEKs*JAR@-m+*ym-koSuMqc#`vWWaUNm&N; zxUSyzqqG%A>2!-d&R1SpSJ$-MIy&QPdWBOIhAaL3{meNy5&FHcB;1Uun!e{-(O?6O zfAWZm0<(yK$q2z`2qFsL(1@>@+IBMd_fentJ?knUO#6;yM!uloC8_Hf>gJ6%?-%(K zLT&8a(-U<$b?{x)o#%ToYX>8a;oWd2x1@C!b`P5T4-38|nxNlZy>*~E>Dc)FTL+Zu zW0H5Ed~olLO95pbxaSkK%HPpL;tdfqTvY4dkcJZJ%9h$bm&SJxcU9xYZCy!s&vt#6 z&?+h!@t!)PAI3cA*mwPvnfmDWo)uxc1o{oywy?_vxPd`N39=<0aWJX*yvn%K>*@qG zbp2@U@KEKkvN+r9KQDdxpooiy2a>bq9HO7EdNQnVBM3)Aa0jWfesrm1$_IyMzpPUrZ^V{NEt=4>Q$K&g*R#JZohUTJD#wz;98u&l3|Tb$Tx;d2XAvN301p#qMnXiES*7$HP~84SkHa~vzN!m zo!<+bR6ShW_!>}g&=d#@q~GuoZ~2Jd$=~Y+lI%ZM_8B8qpkMNE0e0?^T(2v~>id7~ z;2*gG=h2|urz8qKwpKZlZkl4#BB#g%DCwppxEa{8Z_5r2rPj(L!cTYoHVCm4@t;xd zvBp>kkbklZp)08&yWoUx2Im~4%C z67#w9Nq$#e1A1kad>INva`6{a0-R^Rdm{0e;y2@3ez%H@X}@@VS)}juaZ8qgF@ZLO zOOarg2dV>FIzDJ;K!;U1XZIY)Z8Vn(xJfal5GGlCV)j8!CI`SquY#2JBS7T$~6o zb>c-|U-*_U7bu{PZ(h_m@GJ#B#)#dQ|JdH&Z_;cxbv`&oANZi*%SWt;AiZ>ZA0x=y ze8vgq1EL!2Xa=|ETQBe~wxrPq_dR~0@<+F2D1X>hOqSjGzm~4V5z6*!Co&`3NXBH# z+GgLkNwyTCs5jJPNo9>0Tce*uqd_tfWnV*j%TC6UENOTdO9-V!BP08mvPAlh`uqW& zXYS{|&vl*aI_KQ%IzULcsM`fPv*)6Gh6#!)hn|Zt$2>@aci)lqC=5sE7uOZy+FL`` z=l_kEUs+#P!90H*Wbhy-{AU98`tD9ZaI4U4{DJR|e&``-`wL0YKMi~2L_({EcBq#Q z7-$i`i5;dCGXls!ga*D`w1`=49V_|oJSSL*s|@6Am)IL*E~NeDryOyH2C4AcLxTlTr6c1 z;qkaTHfEeM$Rgkn=|#4DqyqhI4)8k(t(c>C1FCFn;)6 zka8rRRm7M5W-&flrWa{QB`k0HLk<8ETvJR;gEoe5!KkN)TOqGI>~6Ow-{F6Uyn)vH zs7<(8H}WFF$;9r;6W3pS{LiwaaXq@ME_P25cZg_(rVgak8yh%u+-=S6MFYh_Ex%c` zginV={VV?$t!J`LSe}0&HDdGA?_aeqc*#EFqg6#=tai~#2n@jYlx{DRj+^Ym8}w2_vS_gHgu^V*%{g`B^+8CjRz(5Qm$?E1r=M*;*U%h)Od{x58}=} zjy^*en*t^<+eQK`s(|H@-h2G5#z&ILj9{dtx<-bb&By(bsjn5}JX&A2#TeM7?}7?sq#Sq|a8 zXB=)8D~*oYzf;2@AOMy-U@Ruf)OOreS3ChqBPApxl;Y7}k%p6(C?#e&7U@O1jwS-e zE=?jxkr25cbT3WyKZ^Is=H~{UY#0rZ6h^Ms&J=G>JxZ|p;R^F7>t2GAaP)nouahww zEek^qOjw)0)(d6!H~!NpWMx1~`XHh*e&CMj8?6UgHkZ{f9njmiC1)Lf@2WOt`6sWY z|1>)(|BB0L0&9k?GK{wuz+j5cJHI{AL5}v9Rk|ypquWdm-7HFQ*ORyt(*fnecjNeh z0WIjj|AhW0Ti9Vw&tGxtKE0hJjhDrgBDl1zuzjCfLyPe0)r>sL%nyF0(cE@zGA0cE z>HPjM7}8uxcw5}!sx~VQnbf|LvrnrPJL)7 zDwg7&*30a1G?6;8l${uj&9YU1aSHugi?U*7{wQ34!pX!u3WGLGtB022FPwh7*@j&jklX`SBtD1JJwW{V{Yf`7aP8N^P1Sgd zHbYCbE)9=!<;E6!cc$~UB%%fmkOq=2jpp{HZB7NYusmnU#7PY-)}_#1-K-6Obuk>K z+^_wdDfPaTIfP((QM1r=J9-6M$Es)O-ejxN{HucK6*F}+P#Rs$=gf!eZs7#8@Xx9#Z*sd8P zKEB*ojPU}$>l#OBc2|FYB8;0&X@nau3!TdhOD~Dm0SmDtQ(-WvmlSR){N(~=X#P1x zVF&Z#F;x7Q5%nk}ZH94XpQaYyI{DuhJIEQWu4?zTzCN%S+}i*NTH(P^d{pRntt6#P zcge`)BCk#b4!uf>4sxs92{BrvZg5mkgr3TN zkswg_PO0g>(ZTRtlLTm60vzpvpui%|T6nO{jdj$dy=Br_d7*lIW*&OwUM-V5LWJDT zM7-Cx;jx*(6z?$N7JY>N`E6ifF2QSr*O4cB{52sgObO&S#X25TgVV!0<$8!PCa7fZ zRFlCIJrae3ezmH%SA3QxIXF-QtLar%iVv(h<1GT+Fyy7LDZfu{GH-4s{89%Rk<|_~ z0=`Sv(Ecqd35{`qoQ2jjO31PXFn9!xv~bxz?6SLYWW8|v&n_KKdI7|R;lcvN?1 z>*!>Mfv;PB<0W7q@FlMsAwyohZ&6Uk@R1v0Z>-;MZk{v#0bD{JnP8FoPlyAM#Y~%VPqTz-IiDBgc5aOU1Y}o zJsJc?I8{E=WoHZD_Gnia#8UcEj7ySMkrAdX7BA0drYpot;&e0@nqy5wOQ!x zBQMNswW7521fN(QDBSj48ht^B)>bjn-Is*a=N1eevAn;f4q8AIEtGM@THq#ZEbqjm zieCj2nz$lFhWWH24n2`L`;QjpgS(KY8+y8MFdOHe03*E{oVBO{PiJsYg+j8K^XRs- zMC7(6i^eRWT8Ix%jTtU4KdHugpkI3yzg5v=#+{ua@+4GS7gu!^|HNh4cp~jGySK z{X%Q2DYrFK@VNy7qrWpn={a)y1YP8KF6m@+!qUe|V}8&%|5?l=W@Vx;DoAdH=W9}_ z&O?5+7p8Z3Go|fEBd;vI)$WrHppF_)_nM}&t;a1+K0cjt(?BZW1JiD|{&@T_v;t>| zb1uDRq~6;)oIU0EVCoTK(v)ue+CpKxro#?2T5ol+u1$E1>T#c59E*V{kf_ z_&*vdTK~LLpE#czQ}mNf|IxuZ>CHA3qSt^+ZP(WALU2x}Nx>@QLb! zJE}OE+tjQUe@cJ%sYwTpV1(!u|NG^g;L8JngnHqp7Z~?>?)|9bM%#=jJ=3R~3G1H3 zzEU>a3&#>7RY6Z2GF!Mz8@U}IfX9bAX7LetL+Q4IM}LKXBJ4SN=|}u8bRF(p-suN@ zDfy4)h|;`9Ikt~wWqV$^9!t;iZ4^LWu?_lSzgw|N6I|X#wru^U1#95{l`=p%W7tOwE)}0^cY)V_juBH!M9CbAj zmkn;x|7Nt^$XSPy9mP7`kyQazQkgwEV)m2=5Cwu!9n6lkN zjfk-5-P!b3B?!e;xX{AlUdS&J_d1y=a~0>iRqMh|rC$M-2QE`{9rrssS5`MAdLHGW z(aXlYn+vftX6wlA4*)JZ{0vGigh!R?WjgxLbTB$9@SjPl+fK=qoHo2m1pqMOxL7^# zEm@2`5qCdj(@S>`p8~$_M4Q_5{;W8P}fPOrK6<^WM z5PRMJhbzV@b>U()olqW$Oa}LGK!Cx-#mG9z`5^!%x3K zE$n3swZvR$H+Y;9C{j!LHQdwf0kf%&9P5qjCJSKtm_sI>hf4sB{pa9B2XROA-X{`N)=;%2!RP9M)AA9mTa1Mn# zvMX%393k1PIPkladCflm8$#Pexf0?_%;o&x>8iLfUmZ!&KzH2~|5dTIhYtn`T#}@A zbw1uybQm8oUEbzLJ@YeqaTrKxR&NKDbu{!2=)34~^+1msmH(`-pG$uajWB~~iR zcc?=XG&96gCcd{yDG4%OF#n*yNvX@KVE*ZElJxKC?uKpKxbc?eCTHHpad90%;tch0 zn(=neEylP>ZZ1@eLNM+>jz`-}Q@ivXKmXiELmwUISH>da1NU23INYV$C#Za_as~J6P zjK>BHH3V1bYkQn1=&WO=?rIo5f6n>}aqZrY3l^~%lZIEljc3tE?Yxa9aGpJ6i)Ew# z#`FgE76$pA!N=}R3B|Kzd3{|fkr$7%f*)S~|GmPQOxWU~PoB-h_TOy{CZf7$$y0N$ zMtvuvN&#*Uy?QHy6H-Dd6*+NLY0?Gw!nxz<7c1~za(t+)$fG;s=-<9Q*#c>z&w)Gn zT8=wHyWYhvKN#_%r5ybMRa8gXTK8GnWf)3H{uyAN42wy?*RN1h5Nl^h(;g# z2VWxI@@+J+*KnXXT>f*CM{Ytw0DMWsg2!}dxcf`s?x5uR0?X0GLtmWyWda5zk>Y7Z z8^p%ka^j>{Z2ht=@6D{!ciw~4x3ci5_U2Af%i>uowcit@g5X^Tkt%e%679Y-r8Ppf-@uCAe(`+A~?Qz@MIpVKAY?=AD z>^bB7*Xg3}OmX$6?sNFP*$IXfPR3Ql*M!Ea9UsP5B_`q+)Q4h^XjZR zh5`3Kg10#QtI{}h!_+W;nar~Iak?v$Q=q!^ygMSQGqGLE|9wSOYwOw@OP0?;XvBdE zKdVGbq6G3Xwa-9RBo3)7S}9IaHbv9x_o-6cQ@XriyVTO#fk(VqSV?&uH|K)p6rOcleE>YfQ0-bXcHZ=YINBuoSPK*`hniq?vPFd3MvGZE_d_w%?k zN5XuO!v0a*WV3vad}n{itkRT;qLOQ{q*RPZlwdx&_)6a0G0#u(Du)aE9GvqLd}_`W zE)08X@8RPv73hc43m% zDZZ;#Cx{&)ao)-JTy$YDiQ14FffxE#5_Z|&e|NfBzlh4Tfyk2Ev5QX z2R4Y(9?lr)u^(q;qSTo8RK$PNUn0y68Vv9*VA%k*cz1*h^zt9TgSu-A*}^G!&tOfd zC^Zk&Dz6r&egkDr6*Y6ia0-1Z^qQMteU9OnbEN;dom%~GlZZ!)@9%yOTNXs#KZM8a zW@6D35EMFES|Z;U4ala~PDo#=QJf3BnKr1Olbj`x7;sf9JB9OCg{!N1t(0;X%QjPc zr%i=Y*ct)4Aa&?kys;AI6M5DP8+=T9yjXogXo8-B3;!FKm@clYLaU5&7*1M_C z$K6(vcdn$~cQd5nf`(=gmxN*Ox$0Xk!E$?f-KmX@Y}!5~Z7gD$k7G@kf)omc4Ar~`st zD0#gV9p@*R$mNjE$RSRPJU3ynH}o7)j zX;1S0cX&k2H99S0XYj)#l*sXxBXJ)=(691D2)fJHQA$b0uNmX&K^q6a*xRb#O7X7b dU)aBSWXbi&+M}aWbKBt0@~EwOsj2I&{{w24&S(Gt literal 0 HcmV?d00001 From fd37f42ef54584a726f1bee637cf36828c172e88 Mon Sep 17 00:00:00 2001 From: AimanHaidar Date: Fri, 5 Dec 2025 15:54:19 +0300 Subject: [PATCH 2/2] fix rst warning --- .../pilz_industrial_motion_planner.rst | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst index 25a4f8878c..bab32b3b62 100644 --- a/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst +++ b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst @@ -266,7 +266,7 @@ CIRC Planning Result in ``moveit_msg::MotionPlanResponse`` - ``error_code/val``: error code of the motion planning The POLYLINE motion command ----------------------- +--------------------------------- This planner generates a continuous Cartesian trajectory passing through a sequence of waypoints. The generated path is a combination of linear segments connected by @@ -282,7 +282,7 @@ the Cartesian velocity/acceleration scaling factor if the motion plan fails due the planner will fail if three or more consecutive waypoints are collinear. POLYLINE Input Parameters in ``moveit_msgs::MotionPlanRequest`` -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - ``planner_id``: ``"POLYLINE"`` - ``group_name``: the name of the planning group @@ -294,9 +294,10 @@ POLYLINE Input Parameters in ``moveit_msgs::MotionPlanRequest`` - ``start_state/joint_state/(name, position and velocity``: joint name/position of the start state. - ``path_constraints``: a list of position constraints to be followed in - Cartesian space. Each waypoint is defined as a ``moveit_msgs::msg::PositionConstraint``. + Cartesian space. Each waypoint is defined as a ``moveit_msgs::msg::PositionConstraint`` + - ``path_constraints/position_constraints/constraint_region/primitive_poses/point``: - pose of the point + pose of the point - ``goal_constraints`` (the last goal point) - ``goal_constraints/position_constraints/header/frame_id``: frame this data is associated with