From 4336a53501061fd0cd4a9fc651fd8c182ff39506 Mon Sep 17 00:00:00 2001 From: Jacob Larsen Date: Mon, 12 Jan 2026 08:20:14 +0000 Subject: [PATCH 1/8] dual arm tutorial documentation --- my_dual_robot_cell/doc/assemble_urdf.rst | 113 +++++++++++++ .../doc/build_moveit_config.rst | 154 ++++++++++++++++++ my_dual_robot_cell/doc/conf.py | 82 ++++++++++ my_dual_robot_cell/doc/figures/rviz.png | Bin 0 -> 175401 bytes my_dual_robot_cell/doc/index.rst | 22 +++ my_dual_robot_cell/doc/start_ur_driver.rst | 135 +++++++++++++++ .../programs/default.installation | Bin 2558 -> 2483 bytes .../programs/default.installation.problem | Bin 0 -> 2558 bytes .../programs/default.variables | Bin 84 -> 84 bytes .../programs/default.variables.problem | Bin 0 -> 84 bytes .../programs/default.installation | Bin 2544 -> 2469 bytes .../programs/default.installation.problem | Bin 0 -> 2544 bytes .../programs/default.variables | Bin 84 -> 84 bytes .../programs/default.variables.problem | Bin 0 -> 84 bytes .../launch/rsp.launch.py | 2 +- .../launch/view_robot.launch.py | 4 +- .../urdf/my_dual_robot_cell_macro.xacro | 2 +- my_robot_cell/doc/assemble_urdf.rst | 2 +- 18 files changed, 511 insertions(+), 5 deletions(-) create mode 100644 my_dual_robot_cell/doc/assemble_urdf.rst create mode 100644 my_dual_robot_cell/doc/build_moveit_config.rst create mode 100644 my_dual_robot_cell/doc/conf.py create mode 100644 my_dual_robot_cell/doc/figures/rviz.png create mode 100644 my_dual_robot_cell/doc/index.rst create mode 100644 my_dual_robot_cell/doc/start_ur_driver.rst create mode 100644 my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_alice/programs/default.installation.problem create mode 100644 my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_alice/programs/default.variables.problem create mode 100644 my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.installation.problem create mode 100644 my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.variables.problem diff --git a/my_dual_robot_cell/doc/assemble_urdf.rst b/my_dual_robot_cell/doc/assemble_urdf.rst new file mode 100644 index 0000000..47223f7 --- /dev/null +++ b/my_dual_robot_cell/doc/assemble_urdf.rst @@ -0,0 +1,113 @@ +:github_url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Tutorials/blob/main/my_dual_robot_cell/doc/assemble_urdf.rst + +Assembling the URDF +=================== + +The `ur_description `_ package provides `macro files `_ to generate an instance of a Universal Robots arm. +We'll use this to create a custom workcell with two robots in it, both a UR3e (called Alice) and a UR5e (called Bob). In this section we will only go into +detail about the URDF / xacro files, not the complete package structure. Please see the +`description package source code +`_ for all other files assembling the description package. + +Workcell description +-------------------- + +.. literalinclude:: ../my_dual_robot_cell_description/urdf/my_dual_robot_cell.urdf.xacro + :language: xml + :linenos: + :caption: my_robot_cell_description/urdf/my_robot_cell.urdf.xacro + +Let's break it down: + +First, we'll have to **include** the macro to generate our custom workcell: + +.. literalinclude:: ../my_dual_robot_cell_description/urdf/my_dual_robot_cell.urdf.xacro + :language: xml + :start-at: + :end-at: + :caption: my_dual_robot_cell_description/urdf/my_dual_robot_cell.urdf.xacro + +This line only loads the macro for generating the robot workcell. + +We will need to provide some parameters to our workcell in order to parametrize the arms. Therefore, +we need to declare certain arguments that must be passed to the macro. + +.. literalinclude:: ../my_dual_robot_cell_description/urdf/my_dual_robot_cell.urdf.xacro + :language: xml + :start-at: + :end-at: + :caption: my_dual_robot_cell_description/urdf/my_dual_robot_cell.urdf.xacro + +The workspace macro contains all items within the workcell including the robot arm. If you are not +experienced in writing URDFs, you may want to refer to this `tutorial +`_. The macro's content +is generated using + +.. literalinclude:: ../my_dual_robot_cell_description/urdf/my_dual_robot_cell.urdf.xacro + :language: xml + :start-at: + :end-at: + :caption: my_dual_robot_cell_description/urdf/my_dual_robot_cell.urdf.xacro + +Here, a ``world`` link is created, and the robot workcell is created relative to the ``world`` link. + +Workcell macro +-------------- + +The workcell macro is defined in the following manner: + +.. literalinclude:: ../my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro + :language: xml + :linenos: + :caption: my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro + +This macro provides an example of what a custom workcell could resemble. Your workspace will likely +vary from this one. Please feel free to modify this portion of the URDF to match your own setup. In +this instance, our workspace comprises a table in front of a wall, featuring a monitor, and the +two robot arms mounted on top. + +Ensure that your custom workcell includes the parent link, which must be passed to the **ur_robot** +macro. In this example, we chose to create two links, one named **alice_robot_mount** and one named **bob_robot_mount**. + +.. literalinclude:: ../my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro + :language: xml + :start-at: + :end-before: + :linenos: + :caption: my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro + +After that we are finally able to actually **create the robot arms** by calling the macro. + +.. literalinclude:: ../my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro + :language: xml + :start-at: + :end-before: + :linenos: + :caption: my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro + +Note that the **origin** argument is transmitted in a different manner than the other arguments. + +Before we can test our code, it's essential to build and source our Colcon workspace: + +.. code-block:: bash + + #cd to your colcon workspace root + cd ~/colcon_ws + + #source and build your workspace + colcon build + source install/setup.bash + + +We can view our custom workspace by running: + +.. code-block:: bash + + #launch rviz + ros2 launch my_dual_robot_cell_description view_robot.launch.py + +Use the sliders of the ``joint_state_puplisher_gui`` to move the virtual robots around. +It should look something like this: + +.. image:: rviz.png + :alt: RViz window showing the custom workspace diff --git a/my_dual_robot_cell/doc/build_moveit_config.rst b/my_dual_robot_cell/doc/build_moveit_config.rst new file mode 100644 index 0000000..cd242d2 --- /dev/null +++ b/my_dual_robot_cell/doc/build_moveit_config.rst @@ -0,0 +1,154 @@ +:github_url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Tutorials/blob/main/my_dual_robot_cell/doc/build_moveit_config.rst + + +======================== +Build the MoveIt! config +======================== + +At this point, you should be able to run the ``ur_robot_driver`` for your custom UR setup. +Now, we are only one last step away from actually planning and executing trajectories. + +To utilize MoveIt! 2 for this purpose, which will handle trajectory planning for us, we need to set up a MoveIt! configuration package. +To create such a MoveIt! `configuration package `_, MoveIt! provides a very useful Setup Assistant. + +Setup Assistant +--------------- + +We can start the MoveIt! Setup Assistant by running: + +.. code-block:: bash + + ros2 launch moveit_setup_assistant setup_assistant.launch.py + +Please note that MoveIt! itself provides a detailed `tutorial `_ on how to use the Setup Assistant, so you may want to go through that. +Although the Setup Assistant is very straightforward, there are some tips and tricks we want to discuss in the following sections. + +The first task the MoveIt! Setup Assistant asks us to do is to load the URDF with the optional xacro arguments. If you would like to change the ``ur_type`` for example, you could also specify that here. For this demonstration we'll go with our description's default values. + +.. image:: load_urdf.png + :alt: Load a URDF + +Next, make sure that the generated **self-collisions** are detected correctly. In our example the robot +is positioned on the table in such a way, that it collides with the monitor on the table when all +joints are in the 0 position. Hence, the collision is allowed as "Collision by default". We remove +that tick, since we don't want that collision to be ignored. + +.. image:: self_collisions.png + :alt: Adjust self-collisions - Remove the tick for the collision between monitor and ur20_upper_arm_link. + + +We skip adding virtual joints for now and continue with our **planning group(s)**. +We add a planning group called **ur_arm**. A reasonable and error-resistant approach is to define +it as a kinematic chain in the following manner: + +.. image:: planning_group_kinematics.png + :alt: Kinematic setup for our planning group + +.. image:: planning_group_chain.png + :alt: Kinematic Chain + +Your planning groups should look something like this: + +.. image:: planning_groups.png + :alt: Planning Groups + +We'll skip setting up ros2_control related points, since we've already configured that in our +control package. + +In the **MoveIt Controllers** step we setup our desired controller to match the name +"scaled_joint_trajectory_controller": + +.. image:: moveit_controllers.png + :alt: MoveIt! coontrollers configuration + +We skip **perception** as we don't have any cameras setup in our scenario. + +In the next step we modify the **launch files** being generated by the assistant. We only generate +"RViz Launch and Config", "MoveGroup Launch" and "Setup Assistant Launch". The other launch files +are for starting a demo using mock hardware, which would basically be a duplication of what we +already did in our control package. Since we also do not use the Warehouse feature for now, we also +skip that file. + +.. image:: launch_files.png + :alt: Select the launch files to be generated + +After the **Author information** we select which configuration files to generate. Again, we strip +down all the files needed for mock hardware startup. + +.. image:: config_files.png + :alt: Select the config files to be generated + +With all the information entered, you can **generate** the package and close the setup assistant. + +Manual adaptions +---------------- + +Before we can actually use our package we have to adapt the joint limits. Since MoveIt! requires +joint acceleration limits to be specified but the description doesn't contain those, we need to +specify these inside the generated ``config/joint_limits.yaml`` file. + +They are not part of the arm's description since there are no physical acceleration limits, as +those are highly dependent on the robot's current pose and TCP force (e.g. induced by the weight +carried at the TCP). Setting the acceleration limits to ``5.0`` for all joints should be a +conservative value. Higher values might lead to unwanted slowdowns during execution or even +protective stops, while lower values will result in slower motions due to slow ramp-up and +ramp-down parts of the trajectory. + +.. literalinclude:: ../my_dual_robot_cell_moveit_config/config/joint_limits.yaml + :language: yaml + :linenos: + :caption: my_dual_robot_cell_moveit_config/config/joint_limits.yaml + +Please note that you could also change the default velocity and acceleration scaling in this file. +Also, if you want to specify any limits (position or velocity) that differ from your description, you +can set them here. Remember that these will only be used for planning trajectories, not necessarily +for execution. If you send trajectories from another source than MoveIt!, those limits will not +apply! + + +Usage +----- + +Before we can test our code, it's essential to build and source our Colcon workspace: + +.. code-block:: bash + + #cd to your colcon workspace root + cd ~/colcon_ws + + #source and build your workspace + colcon build + source install/setup.bash + + +Now you are ready to use MoveIt! with two actual robot arms, MoveIt! itself also provides you with the opportunity to start a robot with mock hardware. + +To startup the complete system, you'll have to start three launch files in three individual +terminals. + +First, we need to start a robot, simulated or real. If you start a real robot, make sure that the +*external_control* program is active on the robot. + +.. code-block:: bash + + # You can switch to real hardware if you prefer + ros2 launch my_dual_robot_cell_control start_robots.launch.py bob_use_mock_hardware:=true alice_use_mock_hardware:=true + + + +Second, we can start the move_group node by running the launch file the setup assistant created for us: + +.. code-block:: bash + + ros2 launch my_dual_robot_cell_moveit_config move_group.launch.py + +If everything went well you should see the output: **"You can start planning now!"**. + +To interact with the MoveIt! setup, you can start RViz with the correct setup file: + +.. code-block:: bash + + ros2 launch my_dual_robot_cell_moveit_config moveit_rviz.launch.py + +From that setup you can start developing your application involving a custom move_group interface +or similar. Please refer to the MoveIt! documentation for further reading. diff --git a/my_dual_robot_cell/doc/conf.py b/my_dual_robot_cell/doc/conf.py new file mode 100644 index 0000000..4e7828c --- /dev/null +++ b/my_dual_robot_cell/doc/conf.py @@ -0,0 +1,82 @@ +project = "ur_dual_arm_tutorial" +copyright = "2025, Universal Robots A/S" +author = "Jacob Larsen" + +# The short X.Y version +version = "" +# The full version, including alpha/beta/rc tags +release = "" + +# -- General configuration --------------------------------------------------- + +# If your documentation needs a minimal Sphinx version, state it here. +# +# needs_sphinx = '1.0' + +# Add any Sphinx extension module names here, as strings. They can be +# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom +# ones. +extensions = [] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ["_templates"] + +# The suffix(es) of source filenames. +# You can specify multiple suffix as a list of string: +# +source_suffix = [".rst"] + +# The master toctree document. +master_doc = "index" + +numfig = True + +# The language for content autogenerated by Sphinx. Refer to documentation +# for a list of supported languages. +# +# This is also used if you do content translation via gettext catalogs. +# Usually you set "language" from the command line for these cases. +language = "en" + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +# This pattern also affects html_static_path and html_extra_path. +exclude_patterns = ["_build", "Thumbs.db", ".DS_Store", "migration/*.rst"] + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = None + + +# -- Options for HTML output ------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +# +html_theme = "alabaster" + +# Theme options are theme-specific and customize the look and feel of a theme +# further. For a list of options available for each theme, see the +# documentation. +# +# html_theme_options = {} + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +# html_static_path = ["_static"] + +# Custom sidebar templates, must be a dictionary that maps document names +# to template names. +# +# The default sidebars (for documents that don't match any pattern) are +# defined by theme itself. Builtin themes are using these templates by +# default: ``['localtoc.html', 'relations.html', 'sourcelink.html', +# 'searchbox.html']``. +# +# html_sidebars = {} + + +# -- Options for HTMLHelp output --------------------------------------------- + +# Output file base name for HTML help builder. +htmlhelp_basename = "ur_dual_arm_tutorial_doc" diff --git a/my_dual_robot_cell/doc/figures/rviz.png b/my_dual_robot_cell/doc/figures/rviz.png new file mode 100644 index 0000000000000000000000000000000000000000..4503938ade505f224e81b8fa238ba54567f8b1d4 GIT binary patch literal 175401 zcmcG$1yCIA^Dash65I(awjsEC&;W~TaCg_>4oPqb7IY!NhX+}lB{&2Ym*DR1?sg`> zb0Nd+c5Gw*cw+x~217!6qJ#1n zI5SX7H3lq#+`z9^ZE7tXy+1KAbfS_U0>QFe(Cy zaG(5n>boh7{~w<5zgYmVU(C?ZP#W34rrKS_zb5PXuMwlg{y#OMZPD+C@tw{0h`1ew zJ^yQE(wdt8@lWsnwz~g!{`o%|cgDiS#RYjV>VMo6-k1=uYrFoh=lN|M)+qk^xGahC z|Lpqz?bfXBUPy(9&YUNgTK;l$N^F2@==a;}G6v zt7<2j6AF>SJqb=FpQhMeXpzgpuXO7+XD50?_vcY%d*|vH6_wDD*Hqv>QSj>hkm_}+ z$&`Ci#M?a#i96h857V|_s;uhQ6%Wx4Olt>Rx0cB|wBUelC0kZH>VPRj_T;`Z7ELy& z9A&P-B;lQR$c&e${>uQ0zqWyo{q_?Rww>kLp+890?=IW6!!cABXS_~fxV2dB4TQ?4 z^sQ9eo*p=M3Xzs$NMlm*8Q#16{r@!0B7P*+Pk^}|!MfAoue}9g+ z%82l9XEP)R6($QF>xj>{F!!X=oGS3o-9IKlnpEf#aeHR|MgVR;xT@PO7CMe?mzBW#n6^jVqVV#`<@uxK1&1AH%B0#fP;f@Jj^(LkpAoVe@A75*oh7@-jBH z73MP~1R_{}!+Zw$ZPz|UvFf{mLTPGc+<@W*CVmY}<*$zI!(f?%(|3Pei3zw;Co~YP zr10Up4thmX_+BF@HB2*EIyqEYGgO+JOkXO{vJojrdOS6cdtb@e#z+Ga_m9ZG?@S21 zvv=T^?RO#&UF>ZAy-vYrhCkbLpirp@A|aIwE6iw!j~_V$7@NM%t6Yk_WIgF6ffcnm zSS5D6m;?celKNDu7XOb1{eM=|qR-C9R~KL*iBaJlh(^8KLySgAUx&lJlY@4_$K1R0(yA9Sx^xu@#u<$=CD7m5GVM2( z%%J{x(L=+SfL*drDPCBO=>elt9t>=u!&wPsL>BdJ50|Pl`TPNCtw^yNO|6jj27L{% z{(>4e^3RTix8qkl!Tj^u3jQbR>-8hhFWHTHg`${}5jr!?fBmxfep=^k*TDF^fHh^d zS49L0J~5u2Z7vz)70C3&0Tgzhn(qY-429O(2P!+_ayYgt3XjYji@NVdALKlA@>o>I zsE;*@f+$D-ChZn(v5e8V*P0_J5UFtOi8&93o%Qfv4=xRB8UBS4VbIn2#AIwXyt`qg z(`t?9$XSonI9}=~VgBoObinQJM`#jKM+3f7X9lb1REgZ?HvMY8R8{P=Ad;cuhT7;e zfvLQFVabKg47r+YB!liD_hYzeZ2ngC@>WkIBN%kTP5u}SiHu;CqF%Dht&u3pH~`c> z!HZ(lrZ&BaQRweg*EyJbrk`xXfoe1iNvTqDZA4CrIb=DAZki=LNt|Pf?ik-WG0y2; zuKRm0Onj#py)65}%%Jc(xN1N$@2?yRh$cjM3R`Gs{k6E7%`e+YrSFT@Gj?@{OcCst z85#CGnxXq82w z!Jvizp4axQPsbZ^$oq_I#HUGN--bOy#&@PzVahw+^tn=-5SvZeCqu%iJy^B+*XA}( zSbuH5E686T{9;?gjfTbOaGPt}UWq@^)8`?u=%>9FZD!=4&U9> z?ykNjF8X0&Yk|aIWSP}b{MifdI8#43iyS1FXdV_7%J5m5?a%v{r2zqmaVCaNSwY+< zXvNMVksQw*Rr9La-74?FiRO+*MVbHsQQiJV4@s#utADue*;Z~Hr>a)5(%-b9#9lhn z?HK>;>inl{8>a5nf=n%X9mrrQnoIZVh?r1n(sO9_Rycu|MXg~(CX}R|zRW%SE>u`%J;=3| z+#1>{^LA~`VtfNJ+xa(XA?=d@Sx7E4{9>LwhYqpJtpf@!cweTJ0Eb^1Pep_;Uo$4j9LZ`v5eDYb3nbCUfy<7mL< z%$O+uy|iBmv!d5liYGAV*LTHj-|+yY?7L*mNnWBeba6T3e*79-)E9SCF7R2Zu>h~X z_-N7`$f%X(z{8wks7Y1B@Yu$RR(@p#eIxX4yDJ$0AeGg_;FHVM7|HLtWOLX$k*2yQg#`L2%mklM>%dV-+y!K}T8%iy@ zwc4L|G_09EQqz5pSy7biKJtPZhmxLiGj5y5nix8dfSB^2(BXxR&TyGtHXW%xylXe` zWyF>rAXmt-mi+wxSarhm6f@$vqr|U8Y7rFdHIk>aRhc;fnhoO=r!~!||`M zhqA=m-`p$Ks2ikpk0-|Pf8Om=1N)}q<_3(keo&bBgUZ9WAS$rgZ(yn z(*qP_eGz{zvkUf$(aSa0N8{PWH2!cRQQ&%$^Ab0V`glBxlKT40qVBbM+7{D`-n&l1 z#K66?y&cDA|E*>WqXE10BH4VC71mBzEEOo6Iy_0=-)E>&DnG}4!9acIVRM*ppS+Cj ztgj0T+I&crYvPN;XSc5VtZExZ^rsvcMo%4;qycf5ulAdAl{)Y+kg!_ER;Gxb3*4# zT?ii&*Fk8lhajsCb^C8^5g_(vMxL6p-av3_$C*{SI(x=>vW0g!nme6ENZj9KYR=Yp z!a`sZgiFuYa7I{%sMdN_EcE>f@4eZCSHv@bIgD$Q#&M zL2US8)*u%{eY8K9+HwGuN9LbAvK&W@3at#)xqryo4Z%1#i0z&fjx=|urh`DN@yQYV zm%m4e1MBWcWE%kq+rOxU<@dFA{xN)S2t}#zCX0ooTJZ~c@;f%h0$3w7Ym^bq-(+9J z;?R-HL1KRtU!LeK3HuqbT64YQtDCtu(N=B=!Au1 zlp%Xs%KWBdL|k4uo!Ep(=9LiQIh){oNz(<#lTH&MYJ{qu;jrO4`k!~%)#h*VdI40w zT)3ij8c|?a@?%D>8T-lai=10=UK43w&c>R*4b&>^C8j{Teezykrw*RE5Ubu8SHAym zSw{ty)2f;lKx@=p2iAtz)MN#OgqkB7DTTf36ZY8y!ve*nR7W-P+X`4;^|gz-+enXg zzStp8Gw6O>5~|8AXXXf%dUdKRd8%memX(NmGBr+RIi904~#Y&JC@>mM?etZ|u>d^1Zl1#~a4d-zh&n^I$0--i3$sIO=E z{>YJ*6?a$5^^u`756~KLyKK7hd644l>QhajFtM>_=R*EtjKxebfCdCMd_@I=al|21 z#U*(lY(0BZdbt!x=>7VK&H@7R%J(HhhD_n{Mw_L(Hg{9LOc05&Bd#Htp`q2`xu)+q zy4?{c{(3rh$Op_DE@`#Q`j1b1G)~=xX6!86;?FcluXFxHYzy~)a+3WFzO5>7m_~?v-@O7Gbdvx-=Ww=AYOD}GcNlbgXdXNZ=|gAOv4&Ou zcqXZ6PMRw%qbC{&VIYu~yG^Z0yk84?)9YGA5L@r7E{_Puqw^|!ecUm)Phx+y!Bfkvu}FEJt6!{dOd-9mpdjeccaE68qGOF(9`OJNaG@-B$1Q%UU7K zVL0Y$)y2%XwaWygSB7tBvO>@1yaNNJ0~zh^r>nVo#~#+V^a+?P*!$*(Il)weE`j$M z7GC$$iUbF%F9En=93$%gZ#5+IE+I2@M@?3 zL2dN@VaeQ!dIQVR4nM@0a;U`Z;qI*ZVJ#pxUd@?^5*s`|=qi3c;w;2;1EF8b%W4@95Y%Rzk3s$d}JvX^b$%8QJg>eYmQ;YkS`; zyQ9^Y?IrQskZw^i@%N=%R+LOsU{Nr>dv{$AixLwmQvF1fdr?b6vYy#WUG1Abau~tG z{MFThPhKgH;mZZF%QxC|)HqP)&C+OQ0^R)gZtC`uqF`~D-kVTlp5{hb&FC%TYL3Ic4nOydVnR(sA;l+!ChRr&PkrT=*4uy5R&i7-vXSJ7;s-bY4qp zhJ((6(&o*v0{lCZqzyLs_!a29An~7}S8NwGSI9Gu_lyjFYGn~J4wJhifxSw^$Q4t zN~4scAhn2n2AOKS;7T)CrcLRse>l8d=CLPI>}WICjQF;XMsC9<7Hmv?o|nUpuP4}K zzMxq-uievJ8$&K{UOn&hNc!1$R+!(4woKL0pn^O6s;fpnv_gM_Zud@H^5ySvtq%;v z)6-)3!BMbm+mj+cgK9G_GtfU>vKL-rS1wVd-^&1o^hFJp<*9V+rZmR8K41AXpDawq z?)#jsFYXbNhtzN4D2K;7Y3LNXZH^ia3Dw$E*S62)c<`iuof6umRLJoTJA-BCN7!dG zR0eej7y_0FgdSKNhsTJlVii2xtXEK93uo+}zPgCZ2iAjhJBovSfJ=t$7&I*IPG_?q zt*No@?EV!o*05qt->+?-V#?}GE~8b#Xnv|ZUJH*Gp2im#BM}7#cAq4RHTi^F1I_mq}Qh*CT!8lJ47lDN(nDay%)T`QMMSG42LO*(Y)EK4*t zw4tFb6{bBMw&U+ozU86mE$NK7gpm|IA9^@4wa|Q()xL=S3FZ1DfD~G2VtLBNA)(#) z-P700w)@Mv=j%?HmNt?}sPEvH>iNrpu`z31u(f65=~~`YVXO;G__J&6+dZR^{7~pl zew;*s5Cl^4x{{`{dLb*$G+V#@Z49y!u2-eknvE_(zdYtsgK2FRp=2>7PF zkn5yGR+#@vhqcIQv(VfaHfy7BWL;GbGhnh78f*^l_fmPA3i-uD(A~YUpQ6(PczT|T zt`6d~7F(ZTD$gvqEEc4-_lzo;ET8)JMc7JvwS9sZ%%&~ovZ~bb!nUT;^`|+Mx)M+2fvq-DQ_*tW1v=nDQ+)iq+H}7 zm30C*iz`{PDzTXxujxn1!}%An9cL3_v*VdAwVq#8xBNV~&kGD5T=G$HV|VK2@76v8 zIyI0(p3<#>MB}^Ot`r3^pw>pOI~9Dksox>}MfQ^EYvmi8nM$h}Q(!Z*%DzRJ5Pm=R zII1pnu3vC_SKrHBy+RUTXMV-Z2RtyV_*w&%Bp6k(Tce zkLg!AZiCs&B`A5raSesBfJN1Z0Y;IS$m!LM6&U`LP9#Hkd&Pt;z>L?nCsTn@4^Qyg**_J zt1eKkqSR`?jOv|-Y@FQ`-OIXujfpfVBwp(1W+92{biHrPJcO`07R*CD)hNT!%ts6} zj59KCsY86}mwB`U=*hVGe>O#xy+S8?Bu1y^soW5YG|3<#De3No0)R_WO6!YP1|;G4 zm;pwV*k)eniW3J-ox*I|?fAo@C7}evRrf*e*#twYzD!&-@ow0|Req(GjtN!C!EPY= zVktXc0hKu1BxVEkKABfCo|VQ4%Hh!DtCI}>%x)80?A+1i-^XJP21H-sG3v-EItIr0 zzQ@h^-qh5q^|MN>a%~n&Gjru&?8BRoV2t3lrFHB8Gp%k@_N3moQ7fc9{M2m7PdBj(AuxAR zOCP1f;%9BhfXsqP_C^CJOlhH1Cj)Cix3%4;aut@f(cq^AZ|OX3PSodAEs8>%3Xu^x z$>@0>3$#DeldsOH|{V9tHv?s}rRgx(qD099P{_9!7bRk379`{6J| z_|pC1d?NHaSY1>2m%-hYfyYu1;b6L;jt~mRLY?bQB+vY1w(xb^u}Dwn#resV4=E|B z|HHvUfJtW*)Vz{BcWi7-!@&1!8G)*gwIWVGe-#oOobI)~RqC_0L66LmMMFc=d=$Ar zi}#X?4h9DJ7C_mk+(EgW7l9`sQ zY{Ws+&3=3PQ|C36fxg-4aj(n6B@@Z$&J{;6<=3I1lO$$6Cs57tE`&rmnSQ>lbdCZi zY?mA~JJHNS5RuSnqBA~xe7w49N)Oc~@3~e{_KI=62R1F5S#sXi$&Fa1Atz3xgvrte zk2VWM9SX2|*a}~Xn|Orf5g9}roR20(XGWWg*2api0$cFFw4q86&6St@G4}Xdk5lG) zuGq}g^Qw3(u2=8Vu!`1$Z)8*GI~LbGv+QP=wG-`TN_M`6Ug!Y^`}D4bRsP^vHNsiC zt)lw*wqS|3H&tZtdk3T+eMlbP1Emrx2Rb9J+^I)Kx{U{hF%L{W&4~fJZPKLEtV?T} z^pxDQW|1`P1tsrA72hQ>(oBy@&ZC`-h}eVoi+?!j79Gs#4aU#LYW)EFR)61 z+g0Lx-EPd$&HY8hp_9nfT&8p}pPQSjE5v|bX(HYZhq>^%ZVZqX*80&}yg4~JIcU7F z=LPY3Y%0ZJPr@6^Sp9d#`wI#R3d;#!UVZxX2tP;ztatf7@xfqtaPf+D$a~x}0 z2~AHYgSozyJiPL8cCOqQXf&H~8+)e13xYzSTRS`a9}J7$N@Xg6NJwsuqWuNlmL%89>KH>;%U21;MtKU3l@cI3I5-gY+Pw^0p@||B+`hP}xfEcn z)Uc`i@q_j4@1wk|EJlu+18SS8^lSPo-8y5C5alW0eqJ1_Fod?Y_R0}FDyn3Ee}75j`!A)g{ix0}Jm#Vu_-7jrNv4eXIE zNWNNZ4QOi%xj0y8MqmpuZk}V&NO(mMlB&zk9vKOe*$Mq9Lh+`i?%~^@QAdJ(}^oBJ1Hcp_yRzwnS zmux&%ovzEz@ZmB+;%lZwx>l}=(Uxt^(5fQTpj&M(rlfu?_4hU~w6=qjke``}iHU}+ zRrfP_#?8|qZsg8SYOEU*3y(}&3d={ep85F}ZHGktgA9))=+U`ems$F0d)}d}FPojT zt?zyj(zrZT&c$Sr_6?RFH~!9M-_m{4()|a=G6(m)bqgjJk^od>7e1{yvg@Y3>h=g>-)qTgfV5B0u4?Wdd=5Vxi^(l zx@s7r5N#@`TuDiZI(g`+H8{54y!UOWGCe`Wvw%#|%(99KEj2Wfgt2HB;uS3N^7DZ`mrX|`e_wmVTu#all_OxX zX`>T=8T4~|dwX`)7NNTq**WVG;jSr0*T(59w2;7{G4FS?2Q+z_zN8(&+7c*f?U9ZmB7Zz zNiKSYH!d!&`NF$d_N)n;rQtAZaATp_|G`(+Z-K`=9SXfmTewO)Iy!RU)ARJcib#10 z=0;n?eEM_g!|&(pkrEU0xo#hQ`g8|_jXC#lC&*Dd%>HmZ`WeFGFrS=~uCF6oTT)cb z>@U`MUo;?&+XJd_y{#OG;jh&sjB)>m!heo)4Sn}Fm81NVY4;9 zOfqC8h^VfHS63tW>-lcHZl-7WKern04ONY=te7w`Fwg|@sQ)_)5G0x@Lgnu6w~$9- z+f|Eqb9ZmaN$e1zai>6l4Xd`BftvtTyG|S8eX=~c)4M5dY@L?bK%zP&C}@I&+2v;D z)_-lt=WHdkk%h5J7N#^bhGt0*J zYzU8-nirT$ZB%+)=K!=0)HC1vAi_H#;iBs#=EBjToO9*_nE&1sdM;Y_eRTfjwq9~= zP0huxOtEg$ifyH+6~_M@=Im3N#Zzj!P&2I>`#BlvxN7%T!Pt=<7?_xySwlUQ-YcFh zm@(oxnzWN}y)&$2X&XmSz9yqkSBPDnm42faSDJzu`xc>r4;?`S)ch_f&~6456%|Ox z`#KJdp8K;p3`Io<(IcS&B9y0I-d@k2pJSqhpKoL`O=ky}*O_H&P$n3w>G zyx%#-Nl-R3rj!n%jY*oANZ@=`e0Uy2p-KeF~Yj%+u^tU`H(@2y^Nzb)1qJT&LKj1lNpMXxL|?FS z-XI}Hh>o^4A3r}Ph=|W+^H*y?$oatnc?3dk#P*(}s2a{_uoebscT6LHxRi8gzB}*hlZ$Ij zYNoyOJ4s6|nk zNF%#-;|>c9mXD|Xv1RP%*00~EN#orXVD}0B&#OZ^l?0(HBqWcg=gX^kIvjW`EIAV5Z(ZSXuf&W%?1#{24J(D!+>WM$oppJ6Gh z6nR#hmjdlG*%c8q92ckOWPsm}*JR;#YE5=n*uC@vgMn zevA!3W{0M$^_u3pj0OLPM&-=*yKj0nX}xQVGt({(z3@B>b9Hs~oE^;}N_xzu&-?36(>eT8C_Ee?DwNS{hjYy-^qKW!%tj+WZ{HF&_|3DTxw*MJ zf-1GUudmPN!~NZa-{mwSf-osDk=tJP!Ga^Hcg?95z#*7Im;dDF-*9Aj?)MtpPj!;} zH)Lmzq|&L>HjaNC+(=5&Ft@NcxLKnI1MoCoA?-TB;3`2SpDem_Ce^`qYW%eCG~<5D zeZk}I?C8j`)6sV3ypDRpS4mrzFRjUSXB>Duu-jZ0TRvH2_?{P3kzKAStD`e>cz8IX=wDY;Q)3^5+9F0J%J6n$+jzgj zi4y8AzWM3l-JZC6r7D;yo}M?GV=A>bsCB%hJpEVL{0GS{wB&H&oEd;YShB2B97>;l zJfrBd1z-hH)XL~Q16X-vu2|Q8?zRhV7abXWw@Tx%zaYH1Mp51Ha^K6pYpPcSvOOL! zn$ZESAWM%YC&oT=agYA;<>}{7w%j`Powv8MtE=sqVr{8H-;B$X6-xUDSxniX)3pNt z3c0z!Od(+~h%aoSXm9}6oqM==c77K5hSNQc`FmiuK51HY>TINT!}#nsXA zs3(Ep;cW2!^f*@*NNrm#<`K~d*E!Kl04v6In}TCCwY08wErc&lM-)TaVvjLX_IQIt zmzn|!B_LE}(SU1VL7}=DGj2x!`Ef||-s#V1@Z6iO?s?^=Bb;YMWHIneHx#hrO?C0M^}Fr(OBr_i?1i-UNerr6fahhX&&3^bjMr?NDj zD(eX7>kq)K(IUb4*u&cO_GeR#W0KqH?;|Xk)P|%jEGD|Tq-cqXz3~Nwn_2yC&NqZM z?1^dK#C3;-bsLu})yVx*Uw^asOQiZpa6t@)j9pNGTtHjs&zmnrg|ji3(d_G;<-hWi zGaZ3I094>hWHb!siO+`VQ(NNNrV#xmQLVvoMFJcSBYH$9%X?zslfo$3jF4*3NQzx|CmzWQza1c6_u!BD#yeLcN9Uz+5El#yGJ18VLm3ZO8I9-DHa0c|us4<@p*Uy2qr<{G`s&1PQy%+4)Ckm-l@+)h^5aL=Uf9WU)bC$+ZrzNA^f*=s#J!_-!ycJ1oD6~(DM4%F7u%iMft z$H&K`qiJ%~xM2|ZFWgKm!LEV$Kmkn@Woesk^U5R^10kT!Ln|$c_VJkz#z!z`2OwA# zJ32ebcV9xoXydwdYn>2qSeqmU^6e)$96oJF_Kio-&c%h3EL!;Pl%v(K?0nblylqUETk7WnyHjZ=(4=`h1UMGM$+OOa-p2tZcriU%0+piLQi# z=1hdt)TgF$?!#M=FoR-ZEHlf;mLV0%?uSm^T|EvN5L$<=laW_2SB>^vJEM$N+J;9T zLr~wM_&mmoKmc`Tu@6ckAq;}uF>LZG%+W{FOT@j5a7rC4tk$Se!W7Mo!f|N!Eh%kw zSZH~-_gwxuXZy^YoTT(N486^^sv#ou_r?n|A}UWzToMb}FyAP2!UD@sE03s*09=m< zjk~_fNG9*AiAhayBm*1^Ryr^%Ui5a}lAa3LZKYA-vS^al!%{&J2DomAS|5)FF%=t*o}T$D%jZ*SF10!R#CyjSW?t zE{7Cx9=P$}PhVVJUV4;k-l2KiB&4HZJP#1ch=v}xnSPk7m&Jf#ss>8&V5)|KIsudi zaFT*i?J==pYaNyQY1cUj*m0%fEH*ZFe7sQh2t7H~Rb#3E1mQ|2%8q{-(pIinEKufD zw#GEB;@$$#V~tY15p9xU`iytI73%7V2L5+v08Zq3A<{s84ty-Fd}wiGtJ-Fw^nO#a z6p>XAyv$y_&(=Xd<(!Q}*4JX;9-EZo>5q}Heka?&Gq3RHbiq7xjaS$yA;fD8a3G| zglej)czJjxhKH5;adV6r<7IN~=Nq&b)mfr{_5p=bPfsr`EsYBun?&6jBqVS!0VT@G(n*nGHkfi`pqA#U! z<|RcP2b@u-Bu9D5K&Y*)r}y?^Tn8w-LB{3plhDlp7Gn4NaBO2`?3KwMk&TE*G^^E~ zu-j2#oCcuTetD;Y;QeJjJq=8$EwK*ACXAE_blj9WkE#{{=qV6zc}1PAj@ww&{8OkY zJKNj0*bxYN=NMaN{G#e#8+ zdB>P4v{4!qTJjs zRL=%Zn*dE^qSRn-f8Y9RfM$>=dn}+(mD|;CGpqX;ZobpdnCK`H$_hTC5M_*&GW~Ga zvNfXUkyNFI*>Ijwtjda2y!~v%NB@fv5fFLE!NJ$p*W3eA%jf6kKFkI@$dq6Qy6{4p zi6Z{PIw@7(=6L13y*)+YyRFjunuj@Hl?w+O;j$tc^+BRWObIg7xJ6;@+dbRE!^1s2 zGTf4STa11cU#so{GGFl zdr)(^r*5z<<83_6BqgIsZ`MkE<>^0T?bX%l+M9c=&n(<$7ipA^GjA7H>(H)_K&yBQ^nC0ObETkdwF(#4s06er%#{G&!d!hi#4a=pR@E#0Fr@lER?I6}2a0 zWsEj%Zss1B9}vzE06mcV9Nq)!QKr&&U!@+_$B+CQV2#$1=~>jzHEe~dmo z6O+1pDF8GyN_4ekb3H2ESLPKJ=jz?ID_vQptvOk!$)d^m{e0Ta+reLXzY>v<>*(v3 z^aDLS$21?I1som!HScJ~v;hEwyh-gI6_V@|U}ZhLJsEts1^%>(g#hw!=w!Vu;ZUMk zny~--Fo`&9}V<{C>9{ zp0?WU@LeCui`JWi2cS4M-d~ecH-jNLnv4qa^78Yw&bymOEPh9_0MnJrpP(1TqQn0X zi{ktH8N<2J6;rxnBEYgS$OJBfSbQi!7#fMb3B9e_Gt+=ejmszZj*b!%66#7taz|SO z#Ap=L`J7Cth$B6kO)>v1M1bDG~w7tOZ zyQcWdW-rNB$E*l!eLaPEW?yaF9ZBA$Dylt4n#^iU4!Gq!%@6WM6chXA?bVg6*fwG1 zX{ab)FvF@xRW&{I@U7ho_%#qDD**B4KWMnQ8f?Z2gEU0tAZJeJ<*z2Rj1G!4 zn?u|U1CWUNcnF7oRHE;VCTj!9N3JuRNH^LyB;F8w6b~;Bo=Hmx=yTbgTmg$ zibg&+Lp%tiw0@EarXnxquU5nX0Rf%S@gPEsai0ErITm)oQ1S1_ka`JcnC0Z;Lft%e* z|GUzM$dVHKjKR+NR};~Nk3TI!ITTa!po1I!r`hC8EG!!6!J#-|V^g)zP6eSnDK$B& zf}4+Fn&0*J0icdQ_c4d>eGYCbhqh$&HrilYB@ufg^4 zRHeo1*w72*rQu?pUizGoEeJbQib@^O~V#1NpnWCkQ?!2io&pqEtrr(mKv2hlh2WFLm zj7cisx2wsWbOOyYaiEp{0HR5d=^y9^Ivm_UJipL)J(w=AN1Z*@v$gBcn1*SEsqdLM zf;x9fv~M08t_O&Tgg)x#waP(Aq6zUiQ%A)fRFjyXSC%zXEZ&W9b?J6YB9+CW*lrvQAKQk>e`=hxi4 zZ=48~yJmSfj?}5)KEVGDizlO?$ad+ zpw0CWsvO12yyp1eF#d(pp45|ExnT8pc=@=;Y0nfi!V0vqC8Eek_*hpjkhdH0)&|nL zx3>8E6^C+qccadbt+ca;H%WThBPXDl!?zLj4Kn2t^6~ZFUVy%RcmFQVeUym_))}2) ziN~Rpm@v3;@Eo**SwJnxh+a0Ij9}2U#@Qd;->I|TQzdmk0#c2bnAnj=Lw8^kkn1ec zJ*hz@sg552;nb{%@LQdR4%$T3xa-D0o+CurLzZT0dTWik+unO8SC2ov`;UqrE7g8* zu`nVh@zGnk$`!t;T|)7E%1t2EZG9NNW-L#OuexcB z9^K+|te>GbH#dsHM-Wyb#^_FOcYQ_zNy)*5AC63^y{h^YTw8J4?)qPpCCutO3-yTC zC?KPAbAs&bI4GAk7xVQ1zfHsAm(kXJeolTv)J!)u?Z z)MZ`?R2M+jJ*o8(${5@LI=-1ow27LDW?G2=K{+A*o;8{~q(zL+6qR!0vy;)Z z0)7=0z*DpVC%ba~G4k6Y#Jh;mQyd+#u8SRA-NImYkNnfriA7iI>PCZ3 zhqMjG@{Wkv@~rI5rkp<7skpqcvC%mAbYOL^{z$MP|Qw8Y8skSgJy0)LEp{AG9Il) zEq^SBtE3cACujfjow6AFU*zp0V`E(GPE< zB&?Z&ySa`msc<}Z%j1Tms`h8IpRbq>#ml@Y)xY}zgGI`!AdRD*)}EGzo7n-qOLup7 z|A(eR(bRRq@SO$zI{t36yX$aMAD`XqXy#FUf3F%q*K%`lQ5OWau>vhUUeLhCiJI$E zFgq95*}eAxfW}G5gh0`qPg?8A)fa4_CGq2@z?cAljbU>w2NyMPxa-Af6&zjy%LRr( z8mg+|yHyoUlYt6f$FbHwXze3Cl@n|nvX1Z&R+leS-Cj_D?{RvqG2{Ya-d|L1)l?SL z*`y`)o@8d$SxKGeo*`py<7BLF%$n2o=t{1QH3cm>G+x=Sd4bbcSG%?57^OPw!)r|T zJBZ9{t7HBtxZQ*+c2J8VX7A85NiutB3fu6oz;-vf1o!n3H+M7*W~9Rpi#0EN*gcrI ziRbFKkdqsxyx8=$B*vJ5pI`BPawGImJ9sxCd^Z9y9xJh${oRSK8BE(bn9&#zNjXI> z(3#DQx7M}D+)0e_0EQC)V*+yp5U>{4g?{KdApxM&xr6eZ?6e)yLIDt-Yh72A80~p` zc_hJvmQvNHsjKUCG3UNN3(X0i4B*M5SknPWT87VYH=v9evTAz9tiP2i*8~PCq9u$g zIV$x#MCGz_mAVWXJeKAz<_q*RI~i&hY8?Kl$xpHpGkIl>5hQx#G3)qknv{@$VBT|s zbOxT`xjyv-Ihc=cIv`Vtl?d&b*r#`kLd3YCU8kp~eSO7JXC*_HE)Vy2<(d(Lry*iX z05}I4m9F;o_AC3G0N&+t?Q{f{nrFHp$y>)-O5OyF>a_(=$O;wm2jGYBV zqm&un_+i`Gxtl?SbI((ST@GKh2vhHdh48R;YwlD)AedV(f5d5QQ~oU_VQq2fBrC>c zNKa};J49+uauE$l2^~NV?3~TSQ!;{~6YQ1ydiv5L^1voju|hL*aXtH8Ntt@z(D!c(UH|__Ja*Q zPXMYFP6Q&|V_D8yQnEh{-NJ44q}CZwHSVUXorJ|pw_1SK%k8Z$7+S2I-6qQy1$yhW z+7;W>)HMAh80a`OHC0zvPYcECOaGon!1Ox|04O^^c!8Y`0{VZ4v9CigFo1^Af(qWU zFS&)e`ObI%(D3{6<%>tG5-``}bqe(7b4$u?=Xq|P!oAuy=*2E|Om^)W+ zo71gn=T9?ryXy7AZD%U%D)9zcIrvMQkFrr~9HJ)#{V1?N#C)1FrB(Ma@bix;!uxyP zTqvH^8frY=nEmj*1K$I0gz-{X{l~rRe`f(`27vbCjnBQ4llI$%4>QkE-$9}n;Po6+ zM`Rm!Wfn}0->OL)w~UXFkaRu+()ueIY0h7NHj|I(L>sRM%E~AC*2wai8F}WoSWF?P0U$3I5LG+iGoPL>vVH+ zQqvU!TveBn{Oubsjx%I=x?kC9%71=&smZQIgZ$#@V;BtfTzPSRz7NcRSXyrWI?VLY5x_!;-*_|z zi1fq5%l}bZV7@NEn|5`*X8~6A8Bjp29UOSjvfbbc?9d->d)AT`k}IGbBSDloG0-7v zfii{?KT&T*iC+EnO!FQ2!9cPx&}(;ebTl>wrzvPK539~EPL`Vt3f;)5T(xP-UC%1)f3zG_u(dT^4oroBg#B!Rl)<$y z74qT5;YaZ|nBr78R;v3;b^Ac1n^$fD9iz68==PN(OGbhhz?6&>E75V{W$ZLN{YS~} zapU^W5r=7C-CYV7`LwH)0`7N#fqA6gdzseEBgxs7MUR;2#rpzj4DgPM{C*}G#D)~* zX*!S=Q3-_v-1l|)(wH&jAfQfZD)j}Q6B?&YK zCKVe7|>eZjo`oK(pNNQh%)hP;j!Skc19Q7sq!otmPxH|Cj zP+UR)kUGx)GG65Uc+hYCip6hB7Wn-ZY-rhq?`2QWEPG$uIR(}$8V1;Q)<=8|YbSAN zSh~1rTo9dCR1wNh1lrT>g=Sg_6Y71l^JK!nh$g@ru%bJCxq5}~s-Edwe1ZaF8~l8H zJNN2@u>c60(D&Xun=rt9{u#h{faV?b1tjQqJ9&7xw7;J&(QosJjI{I3Om3ZTg(1mg z$*S#yQ`NbNF&dJcyJ1svB93Bc5!zO4;3YwPU`@wO0OE6Rz>fu~Ms- zVYq;fEa<)u6V23|j}3LI-37uZ9T;;OUCEbgn=K~G8OV*W)@&T+M8-b8@d0MlD;c~f@YI#x z5!rvl(P>;BAch=G%0Ey{EYBET)0yGDUkm6lJmwY~1cZdT?y`cftH+CqiU8FiJ9`6q zwb~u`dmvDw`Fd=Bf4$~?MzSrA-uA>+RVdalHsYLIUs*J82J19KSYx7 z6sCv&$DwO-)N_`$^5YRx<@Xe`AK+mcIL2Dz>QT53fLP^r3Jf54E{Aad(#Dy>sI7W0 z!H!4@nNh?V?zjH+5XU4zh6z<3i zz>WogM`k8v^MXOu%PbofW+>3C1^_oOx+vS*OUU9kI*b$1xdOm=fOkkrM4@3~9_%bw z5J^}m<1j}q0>2yJ`oZF$KYgWc!1m|)^bJQv zo3w~$oFsGgBb=}9sfN(r5=I;90s^=x~w58u? zW;sF6eMPGNJ|>V9K7CO-5`?c=NV?NK&@M5p-}6E$^xxd2l~Ki;sAtDpA5Jx@6)Q*y z#ssqUT*41Yci-uv5cr@J_xSX8Df8;_ar^Mz@Zh|O@A)S?Zw)Mj&4N#r%5fV4p_6D0 zWwZTZYTqxYKyJjm?pd0cNRDSxJ=i~tRlO4QLXfh1sUnPStmWyp`;X(3lT_YJqlxB^ zj!ZVAC%iTs4P%Tm$V>;pf8mDz=6_UM18Z;o(MLyMww6_#cU!Twk`uIV`7HAlwH?5J zAxa(1qVIj|D%x8@Iy*SHQ|hx{1QgjZgOj0!j%bl5AC7~$%?d>C-Aho+Sv|m>vP&9U z<4NsH5FwNLeGON*QTW-jXI9!kY7P&-8Y&}|Xr}&sWA&YTqfiT zVnuC*%!*jD%{1lq)XGZx`j>U z51JTfS66sSIM&Vmj`gB0CkJ1@$~<~>_&}^cc=uU-aHZ`a2cC_te@$(zo3nFoe}B;` ze{B9^_Wp0*+HZt*XG8lVJvHMINzP9nV#KVS^%@P@Vyc;VbMe|BYviiQr`(}sF@nrO zE8(=1barcbEk3QGs=2wj)fpS=D(v3bZ`ODF0aZRk}I&{`|Jz|qtXk?uod??&Y1+1NT==n9S7cE!OKZM)!u#aon0{89SJ*gLw+cOIbCC*ULLgSo$+Rm-2e)2K9TYLjLapX}rXS;dj#GFIS%b>mo zIg_VUtk3+E#}~G*h#DGtPc!@pK>gU@5BMyv8PLuAz9~zGO*>UFMz&338+b%`0~XvV z$Hyn`QKjO-l@l-KzjhgMx&tT;D3Q<6QXf#hsb$TvKB(~hn|q3QebyDLnj&=^3AdIUJ#2075=R!7 zmM-sJ${zUb+NdA>Ct5L3;@j(v1@EIJ=z4JD_I~|(6HV_(u3yhY8yLsH!BP5eFHii5 zp5BXtiRE;!O^OkbJhg+M?o!gw#enaoF*uiuB{;Bxq$Y0W!^t9#X?PL5MHsJ+w5@c++Qo!5oz8Rgvubi}r|PvKPW=Ab?< zEpM_i>5UmHVI0gjEIvJU+gb zjErnyyDp2jiunT`ttNYtbY>(#p%jtrMh<`p#IP%obboxwg(wWx3M^1x#rh)Ax$^O0 zmKyWxX=xW!_rN=aCj^0NL&H=w%JP;Gn{?A*5x<1xU2canhh=9!1?1>a=>r+M*uqmI z-Ne?|&JY^!_m+irq=;MEwd}dEs)cq}6z)++GocB{34)b#Yj&iDsvMY`8fsP@>$%#K zm0f*&(ic^1qBD%`?Muh<;!V_4vR~38GkcbVy?^!kp8q_o393X4Gh-H|@ubvIE;C*N zm;a%Ih1@pRAzZ9)uD0tp5Vs@f8M+)9h<#2p`<~tn z0oaI3k|^BI7QA{T+95++yu7a;O2ge!$Zel@4|hVp)&sFs!rV?5+k zwRzVx*D#@9r~bXo8vey4iPTLz^lbK*cxN7K!C5ys1-U-Jv-`RXz)gmTzAw2yYWt#Y z)r5ana_{(;Bjxh$5w+KPc}l9R`fI@J`1nY}WqX!1_KRr)D~gLhd^r8LEbi7gS;N%E zyDMk;Jgbjv?C3qe#*eZ_`Ju@>CA`)PACB??L%Qt@~VfVnS|uZ(q^VG za>?S8&F#S7>{@(;2tO>lJ*8Mt+bx}&4^LlIK72wzC&>}}Xx;Us{AtI7G~pwl(S01W zNgzn+F`qd<^#Z;}8JO3nc z`t#WH1SJKe1D9%T{Lg4u^rNHt*tzRZsNRz&ni1j!v`lXuo^&zAF_;amKmoCmyh1Tn z>U(yy4DWrP>IGNukreIq=tpceouMiW#7>n?VOhg(b%TwIwNpXw)i}M+^x3L9GBPq} zXoZ{#SE>%0BIV_9&o@7^$TpCDSHRSBFDI5Ahn7V4ITX$K;(rbGS^KE?WYmXs*p9!6 zY+dkElYunqiz~0)xxY3>AImIsdG>*pQmbW^kvLRBCKs5R3X42Y;TX!+8j*Vk=%@L>=45XSo}$S zs~ouSg@q~d48TcdVzO6JnFa}muFe~d1Vtn*f-8_AL#cyMAodmT(L0{?r`hiQb|%VF z+azz=&vob6=*Ah=e8UBR$?^^&8T)(0Q%2;U6-oN-TU8{vR!{u^a^707*t42w&_TG-B5l&>+Fd)}ej{}I zoI^xpEpfeWVsVpYvnvX-WF^F3jpcaMq{%=;SLLfszw?-F+oZ?*gYn-NC zl~bTR(+}G%57%D&f&ocU+w`YTJAy;*=jP^eCo7M9Q->>4E}N}qRfa|XGVQ)J@3w;N zZ5mt&BVO{5kYHHnRc91Bx&sQ}o~51ki;vvtC}l^AGGj|i8UrJ*$2W_?C+;mK>xDX1 z2bZ0lUbTlZFlLua3h2JGOkwLOd9%*nvEh2bdk|ej8hNUuez_0?c zd-D)$|1J&=4tt)`VIWjf<>g$decCPZLsjmgVj?1tDP1zw$GX&&GnnRad(0$Hdg>WJ zN1g%XE*|Po!H!Q)^YQb$u8o#>-lqsuyTF8YwS+qjv;wI51g#)qP1<21V$vnqOmDdw zIn1t_1tMDSH8!ahQ`M!7#0(O(-rliR-Jej#?kV>p z>x7%P(GTKsHdg;`7BlzpAOh~G0gEd7@1Hq^Z||X`WYwRRzhM*b+>Ks)D9g&n(LfRN zB4$;U08bk8{rTLN8_CMSxOd$YPifhb_O;L&3t4Ns-MoJkWbcl08)2@@fB*Am#CiPRLFS511Uq5QW>+0%49w|4SLq13%TTu7M1i>#wG3W3maGP&AaRFkb zPf}0LN%w#$Hz5ImAmxKZvo*fgK$GL+bAcS1JQMdzFsU*AL(63O5ayZ zAVH6Nvlsw~|NhbgR7{$Flb@d-(Eq-auq=`*mjbU7zG6PaCh*HLCS0jb%A2~+i7+Fz zH8u0|5Bt;Q*Ji&I*>on2gkBb}u_~V9{iN3K6>lo;$f#H8mAo}5K(=#IMk%YRBq*9q zhuBAyGbjMpcRwl<7nwO=Q5>3B+k0s*!(CIWsEghYB}^Gr>U(Mp{CSmz-qDDrB`$|+ zJCX<#E-jkCv$4<)5CRFT}f4pq*2v7H!F;a-_ui3r{k!s9lHGF@IZeFx{8yanMC zVT-Ako)EP1BD)XnK(hYxZTr)Ua_q1B)83vIS)VRc(97T zhlHZjxLoHSR*Ph5G7@3r>3Q5IF!LBLDv~P+hJk1!Tokrovf|H=_l_E8PF-znwcMNr zv%Xl2ABeShh#{r)yop0FNa!DdbnZeIxbuySpNtRV7kMhlACN|M*#EqEhUU-7DPw$r zk8u6tv&w$)jMP+>9F6@OJjwhnF;w?0hdJ;NuLN$et7$b&|7(%^#7J}#nfa>?L0Czv z=k#{^dIV}v4X5@howrSR;v?-x&ecrm%eMUbUX3jSmQ07HKrfluDvf^1liUkc4`ckm zux$a|SN**0^=mTt0|nO#zMIr{M@@1Qv_4O5bKXDch3mqGDBHZhw}Op{n9!?E3aJ}h z^0UeENiPxprOXdV>`%W+DyxNX)eJAcM0^6SMVF^FZ&om`ZX&5xfhr5OhzIdl@r3)_ zz549Vn-w6BO6^0868Up!Yi)FnT~a5aMPm@W1SEk4-(1mt2r0yEQd!4tFP;_E#LC#W zfn3;VD(qSZJr&ChWyUls_z07st%pad(L3NZ?_46wY?$ct+>LZNlBkiJ%zvT;X zDxg!@Fv4Elh)uX=a`5JwlqqFu-_M_$hwh?9)^~KINBp(LGQ7?Yw{8<()=jjQCMQsq z8|wU>-)BCvjUo@8K$`?!hs;Oo!2*$_;?m-nE(32jK9o$!eyo`gaVT?` z2`_n*0SCiojVZZHs|1p({XbQ(N}LtpRo3jQsduFiaylc!`_bthfkLYTd9%QNclY_|{CiS$GwE8&_7h%njtNLSjV* z-7P!Cd#bBVLMY0?N$~J|w*pv#O-*b)70j<9+o4^T;d>^_UzBm55&5#qxg*|UjU)1b z3l9sfWl9z^8Z-SR+4g=ARu3oa0;t=@DR2-FocQ^r;uuEUm$c*i%mF!5%+Wa2K}q;8 zr_T7?btsjI={Bsf!dvSnCG=-L#EtMTG}fZGUCLKqokK_wI7mv4Nw>XxNwZe7S1(i4 zIoNO;u5&s~{7g#1Vr`HrzUv?RSka`xI^t>DSwVRv=%@RFA<#hG+-f@(Xw3<~;yb&z z@KF-cMi@QW7i%B4;1y2$aNwE&X{y2S6qA;g%Z?-x2x!r5Sz8}>YjQWHUf~K9gbyfH zF_PPcV=)H<@7G08Mt)j>nkm;D-(U>K$+5Rz z7G@F4y(@m_Q~TNW;!ss>v->LZBp6KXo+c7&R3vnYVT0J?6MW8fS9NwGAz0#g>-FvYGm|hZ-uAUUNu)k z#M#5*%@h{J@%x(1Yf@mw@OgF?gp7LG0hmD0s@tv4ISWso`c$@k*%tAY)jKys99pzP$YFLAu~AN&;;fpKPR)o!vo(?|~|4duW6b z>0Jvw^+>0#v|$DQSxPb#a@Qo zg3{CQY)3^Q?)U_sk|@N2-8kxdE@@** z#RXJ`AmR%*PwXbV)k2g7$7C_b*D{qpuGe5qa1mG*Oke(6;_q*Sg7*OgETG6G$FcQ5 zng0j-yyblCd~;<3`s@hpc5IZN8uLZo>3cHf+hbnY@KlJBC^~Oc{kMSxNz8>f!K0|O zbY@{29m%M+awX>~E;8Gljyg1O?XIPQxna*wWfH}n*}fMjLi>Y&Jne!IT*q4|yn?Lb z2|WXCKGHd^QPZ2rqd8hvf_A=3L3=1x5)}xpDd3p^%+aF4LJH!d!XNVK`S?=MEro)R z+V|hf&+oDWIF&13#K= zub<>oNzKT(7ScL$M53~40`(AoYFc`_?WxCeXJ;E{XXUZ{Y8MPHL2=~M%OXD~`*tO* zYWR|sqeUG}Jk1ryVs0lZ`y8+20pE3NW#twc{l~Lew7;k@rOOlmzoew3g;2pj^z4rU zDWpd_G@PKsd5>FK@qVDHvVJ}9k=T>Rk4f74O35S2*?J~ypoQiGu?;vPa%1_Fu_IO` zn^>k?sj6=Uxda4mM#`;?sWRN4@%?AaK)DHSCBN65h0{bkEK?FWNU~x(=jS2NytHG# zjPNr?x6I584OJ$YW{eK-+IoAR8lEj>G#iwTtyx>|3O;!dGHqF{*JmEjOfG*+8i=B0 zxZ{`^W2mp+=(20hMpimQ(ZB23m}dK@S|M}&QlS4!#FzJSk#b`pSCI%josmB!7DA=( zoOQjk`pvJSKa_K-0R8Tw(xJ!gseoQ$wD?CbO95kn4G?hL^u15qML>kBnnvln`1P`6 zzV~HSgDifiG3n|A(>^>)KLVGNuf4s{?dUT!6d05wKj@RScyxqePr4(B=1slJmTJ>h zfs24V_!u8gZ%mT>mcu%AM2)gmk*Z#fT!G!0+iGCSw=(q-?3H!>>;QyDv2+FTMZj|Y zLC07*vEd2=NB@~&NxPZ!Zc`rgY|4u#={MJ1@2jeoGH<>MKoj8A_DoMqRM*wjoiYZd z1cMkIWN=x`34bZS1dA2u=aLHhBuC~?xqDqrn9B_+J}Y*$FrPXO7YlE5ocpqn;p2I9 zuxRVj=xrk#5yN0VW%>8{@Iq_=wNj)VPq6Vl>eBw@N%C7dy@}8|22UFgW8=&-efdP-?I$Yc0ug%3 zuC~vd{z)R3FmT7dVj@nk|CZv^Sz+VVSXxvxxwii^<1in+0GZvvq&9Na`4zhsHu*iSOG{&K2jD>}#GtrBm z`F!6P7yA`fqGnZk?Dcjt(rC9g|Fl1M@)+$Zy)_WL5~Oj}+vFW3VW(65^rriIc?YfE z`ONwGIdB+Q!aQp~qkjp0Gq3bMX*sP0FQ+)k;pe9LtXIBEYVif`W#30;GKW!7rFGDF zm;x`%)irlQlza`N;;rEZgznv@)|K^*4W&Gu{SsqmOKWS2-!!v=A4tXP7|$?nSaPW& ztbD@qyV?aJ`{9-t^A({IO*SQ0aW|?LA6-p!a1fu+H^XyQRth50<6pIzSXw)IiQ1Nk zKAWV90`(yfJa33TjR1uL6tX!QcD1Sb?q%hDeNW2bDU_5r%Ov@ch<8h`W8@~a&*N|Y zjf(m8yQ8U_O5-RnT)!q@7cfK;}%aUZPWHIx0$RQY)nSx zP9vihptT7fmy)mn3vvn(G6KA3=DE_DYSXV!M(+x(1mRw>-f*w|rE47zNCKK5??L3@ z{ys${<8(>N)*}0O0}m~tOpTenw7A&bri`uQ`TNVHO5By5(ewq`ED4HBj=FBn&_5X( zqUZn3BKM!8nib1$JB(S3k@|S!3b)>au4HZ#gxaKJ9u>KV9tQsO-bD-e)tqZ>n(sOn z;Wi;&4o|Hh#F z+K(_YOcqb@{Ry6OC&Q)zD$yO`S3vh`oW%Bzl9N&<6sayIMkh&{BF|wW4DL?5*XC)PlPwF)EL)J-j{0^ zJ6U%^)Fj8Dt|sWPHI#AM*G_g$D;3{62tTz{xhR3W4ehQFVptsYcrkr2}hu& zg4Y5)Nw;}rWXfy}-0C(pkROX}FUHf;XM5h5?Af%2Gz@ql8!H=JDVu_1JQq)KVKyd1 zw@q`tz3YAJ)v`x)$8Mj!kCVH*yP@kiUBa6Dpo3niRdL6PbGoR9V>GEgNf9!@l{MGMzzwj=oBKTj-B1*U1CB*Lx=KIY4+Hd-2yO3F~gIftEzAM z5@AEFtgP(sSHr39GfinQlR{>8nK}wmf=~iT+`zi|xHs~Q(iPv5xFGe~;8&(<1u^*` zfS@a%efxMis^4a!Ftqn*bVRb#e*JU@#(tn>o?E#8?cr#7n~`Dvkuk6gdi5nGeHOem zf3KMN?n=h|9Eh!W6P&pH zhkZtQUX4dR&BB)m{h*$w4_w&(i%;`HZF{(`Xf2!oZ|L{$-{=1_#L>5?N7gtd8T!m> zjj{)ZhlWlDl}h&x2{pyr;*){9!j{^{NZb`#WVq-kR3~&i{psqz@87?JKzsi_wGgDC zTa%4LrxeK4zC`$`K(|OyhH7bD9F3!KQ@TiDrmW{XE8rAH;5 zNlC`Y$VlXQ1tD4mhu}9ht*P$lvbFE8Tm2K2%kZyYw{`cW8nUyqF^3iB7v@^J4Vdi9N5+l@uBg_ZqOts=F_?8+tG#F~@1VFK4@ z83Z^&Q39!b5At}>l*gmB1|Z9@x3u zQZWK+b#0A`M*Np8`}7J`Z+bP zKoa8i4qj~j7tV-2a}kKi+Y24LM~@j(2}AfzwsnBsm!MdfWfE~K5lTVr@U~5dzc0k{ zTFt6;ZTTBVO#Jm#bST=`30iRhZ~&$G(Q-xyi~`_9WMQ0LHc-{v1VdwEhc|tS z>8&qdzgAsMNI*ok6O^*g^~tr-+p9lHPuV=aXQ^1s)P%)^JLMIh`F?j6bNW56Zx*~R zuC6n6J}&0wjFh3T72SI2IolJQq~`_c9!VlS3><{t!n^U=nSZ$4FaGQBH~ zl9TjfviZVG2x3Z1mnpy2Y+`BkXQSV1YbQSsTh716tJa+S&}R#>ez0~pp`AOJ{)HH@ zfti`Zou1Oi4bBAvp;>ANxOhmcOU8kiPY8|Mi?7}p$FN%(7B8ErJmht5q8cX@?OBh} z0Lvq4>IHKSZvYR$f@8gbCp?&e zXF(33D^K8r&6)W5@_E6(hmRI5a$ne-AYnDa=sIjqtiX8g4378dkFk%rmigx1h_Vr@ z(oI%9oQ~}o_sye)4(iYP4Fo@a;J0!Tg=GKmhp}U{yyTGp?ECnhJo>l;i~-fWp)O7C z1ZDGz$F}qbeY0I60 z@mmZ!-|ZI{7Z%p=`mp7rNzT8H>;6z^}WMBamP385~q@1@T`A4sK>)kuozy1wg_Q)QPXH&<=!;7L3 z7vtt0otRL+E=lfzzWmZ*XOShk1B`kMk3hQn@!w7lP=QRj)oBW}qFy0g@7=oxYuOPk z?zlc)es*@o??%y6))-2}c|ChCs%nHez-$5-RvY#$&`%@}m5B?LVb8cPU!+{k6=VEv zXa$(n7cP4=;-|w8RYBlVBkFO*%njow;H_b4+&h2;e%5lxsi?$Cv%Bh=90!x@bWCL@ z8;dfTYEg`Th6^6z-wVN+1-2|WV2oY!BqQne&KViEN#d(=zaws9*lp5D!`Ev6jgsHp zspV+-NwSJWn(dub2_z?81>5p&J?zr{ego%|&H1vJM*Rb~U1kM_1jl;jo{ENq7Qb3tS|pLv(#ZgQhW*Ou?flfJ1@fze0WiIAzvKAK=>8nIUOqvUCo zh+2Xcz=)Mg{bL{B#>r{za<_?<7bYr0+{wLPzWf98fa7C5HnKj`iZ&DVxbCp57_aF3 zyU>;dp|Z^ZBwL_!`25)jXa z_5r0X)gGIL7!ukr4$;)ptc}fXs=;pNA5UmE=ksfy-9V_5$f`qP?Ru}~n;3=aFLt7m zWTPDMDY1rs)B77TY#Nbr@t=)ssvg{sz5#fVWZC3KgS|Oz;NpAU0yiEs!GEyOf)qX0 z1n6z}FUEFpe?d!q;x1+mgY#}xDNOYsaS4O-`N3@^)E6+XgpbNXigrQw-N_$TwO{CZ zDlT+(u4(t&9wg>G=BKz46xRiT1Zn-L?0G$F`^PVQqL$y>t6%1xIsN9= za+0<+$}!HyY&91gj7sVI1sJ>$XFh9TF>{axQWArl!Y{6Lnk!QJAy$12KZ#hczQ}Lv=;L$P z*K$R)z)acFp zY?i6+un4sI<|JyrWIGxxtJV0^R@SGXal&?{uuZyHh!mScIL)qTBq~O`fSz9D8K$*@ z;No(!U6s{&cC93$E}=2o3E3!o>3!#`1wkXg=K!{L5Cr$Ao}~)F(i6A%SOSf8AE5Zx zDEqW7sfmyYX)t@qv`P&8p>66D#N#F~-K)G!@%`n4@Y+)>6yE)22BcIzT@0HQ4ZHc! zCD{$hryGnowWUv%fVHe1u!;eUUn)}+gK8Pkrjp*`#~tseogZnO_eftpVssThG!`RK zyoUrz?e9M|4VuAgNYR24PgcS@84GgjVQa0w2rW{ zaA)qywZOc8zaC=6&oClPnyc!oc6>?iEj}RcOniR*sJP;c>eeNjgM=3P*Y6cq_ao=? ziY{r1{Lp|7+|!t(s)VZd7)*hC@3VDRBwdHpE3CUQ@T$0}HK3V~>q2%g~8{8;OgfjVaUr_ka-Pp>Mc*cEprsv-?9FlHE=mSCrXKZE(s&~MF8 zqU&5W`j_zhvVT&BNM%+bftB-r-$})Z$BJDMd@X@k3PY8&*(yPa^MvuBz$Z2M^M*W^ zmUeVaLc4hp%R9Qa>_taqg;o+8W%I2*SNokJMQR^1zs5)Y*TV{lL?KY;=`ot?(7p%Kvj3|MRTB{kXoPv{6=58cRk-7$Z#Jp@8O1 z55aXl2R3&%vf`ZgSrOFeOo>s4to%Z~%ZQlxD&yz@%f(x-EKML_zJtE?#i6+PS+e*9 zuf&lO`1j(;F$hYWTgWYM-Cim*(iYF|lkE$|OBqh}L4mLDS|jF5Zc*9t2FBms_smz* zsauArmE zXM_dXI;5Kh7YBibL+drOW`ZO@Fs6G{^;lik!TsZ`95>RM$nJD#gdoA4m)+0KdHi6I zdOH<=3eP`?z#XAs!2DYJGi~Ts8jb(|wOA72>B#B`DRUzcFwl+G2u=KErsK=SY&Vot zgn#E}pIU#jOx@1@uS#86VcP+;BoYJ?x@~K>E=psDGzI|03XgbD_b{Y}zb89>pB$iDu zGfI*!3uEgTE|!Jtg%xV^|Jgav5|KdWBP~KWnnF-^zXGPVoMS{dQ98H>?`Ie)2=FBp zSV&A&ywns;F@flXrsBS~9uEbttbWJh=|#R>UfMt@4^AlX{`Zv!W#J4+5~UJgV;Lcg zuuKu6-}5P@Ug>@!sFRHiVvKEWdaIPAxglwpcNI$lO+spWFF@>xztCkWdjXdT+4M^> zi}0YY=`YxD|L;jP12qFt+lzwA5=b-|aX=RPr zQb?y_FV{!ppRb*%r|i!Mg* zsB3cT{W>u*{xN1mHO#+=zUBu$^PgcAop@GBK7MGo2<|cL|K{kW%LzuksNPM2^9&3j1GxtvmPkI{E_Ylb?ND#&7 zh4<|CzAH(NVqw^){ITEFf9N_85!c4{->EUHz~A_PCqCzL2ya;sLh2KzsbdK9R=*lAf#PWV~?}%Q-`g;Eq z!SWiP`oDHWwFDx9^69)TP6zW3S`8_8ycEGs9+cFp?aVtr3*-?fY@U8+5gGpwHXL2# zBMl8*5u4yUZkMlTa<+H9)Qbs=eY-Ovd9v;Ln|qr8anU{@68i6jKwQ>pw=6>P|HT>6f2nFBZ0utm}pEY?_mlu3jcVaV<({%*3V zy3nK<;kbLcG0{mi#C^N}J{DM5Jra4b`+7&!5xD&NqttuFoMlLx)S#P!!9ss0)(I5C z%R;BPGP-(s&a2<(E5EKZBc;Ssw-on78G+BFttlxYjQb1IY3_r@&#Vyj!6syef%{6odRNshzo%#5vvhn*KnI37q(`x1rm6TM0$$N8HpAFYpT&TkM#HjID! zj_JcSHQuI_M4mWC7M&H`dqe|rbIM<31@$VN z^;5-$3T$xhMG$8)pns;xOSb!Onj z7%-FsGV{~CdTAG9g}MK!vrrP7)o)HsiVYg{Q(c^J1zqVQ4B%pF=_cOJ7(O>B_z5(i!a}y5uq;jf0)MtP z^dnc<$EBTytf@Q%ICE)+PfagHlxH!+|B|S^m1nLP>2qn-PNRiLD*wo5lP4t?i17+> zob8YTQ}X3|+m9YMU6(2>qzgnK2wK-$ok64wI+S}T>_mUYC|!jFryc)&VcLE)W$W8D z-stMoAHDz7<0bk1QQUAq7C4{Fr6=&cjjzVP!vaGX8Az8I?s60$Bw_>TI%3Ym@b7V4 zS@KJM^G1*%hl`g6C=p-{0>}&{k+pv08YU2Gm$iLQQR?ZLJLm;X)@tzFl4mg0HAlA_ zaYC!XLzEf_^?Tt^?p0L8^(?(A1D|eDYE^xGitAKiZ6*xFK+alny!F(kTn7wa;Ul9S zi0ZC*3&?4gX}ON3)(DVoD2bru!=L)uwLnTsiyMG(*T!bgxD{u;M6=Ys_T3ls$-x)} zjrzxP~-tHQpgW_$@{k=Dnq&xdg7_|Nb?B zvwLZ6W20AXG!f}t8;*WT(h@@kAtP{h{O|b~*a}nKMw8npP zDR=B{#IbT59)ATl0&RDYEG)2Lvx z{`*-&+Cf25iRCr3#qBmvR=-9nJpX&VTNTW&LoT8ekqCnXI5eKlhjRd1;>&Z&%Q5rY zf1!_`9W8eJ^@eJUU}eSSBU1XFosG#_--F7GCylNpkJ)!cOPRZ^VJrq{)qo={iQGMc z;Rym~z|;|=B#M68zdvbU4L^k#qL5g7U6 zN`l{T&i9mw|KkE|wVa=UQP>Tl5LtDGRB9WB05OfO{5+iQJC#!1D3ozfB zmpnC`MMnE6x_xcmk@C@zXsrDEA)wT zv9tT^4cw>fIGx28mq5n8Mr9AwmHp>aRka6-O&4cpzm2WlQrKo-k>HEpZ1HNH-XiBX{r7Hcq{<4 zeqmS+OrBf8N9&dSQkmZ`B)J!k6a=kPF!m@31_gxPU;;s&P~`*&G=UoS({ruFi1W8= zV^Iz&;yHT~j4vV!&-sN0pVcp4u)D|#`o;32eAivQpm`3yDye-kB>6<?10cJL^<0H?vy=Yko0csR4xWfU#^|A)@T;R6xsd!lrMj z)3F}n`R-8@tmafC{wuZ~kPU{)0EzCckW+3szo&q@CL7s>4+{fv^u2>Ot#ji_*gvLM zwC`?89$Kpn@oHo+Bc+z?hI#KMD;qSrZp7ZF-u7(ft+d?wgCeRUoTx~=Tl7$!!5Tex z!Xzt!D8?SzBIelBO=BdI`XixZC4umt{uFuC%jkc4`ofikg_L3A-LvWpBLqsWfH*xY z!IY3xi_(UtPMNZY^0erFCgpQT6@-Rkek5KP7ZZiFE;)jlNsakEa~KAh#r$K#HKYHq ziz%bHq-4T|zi31;J)+CWl#T38QV+zjU3RtSt>XV$VJ=4fV{=_spa=o$ z5u)yocvUe4?Kf#@)8pfHKz8U@2<=z^X&h{Vo9vGTpU>kK*tvtb(1jmfrXE$d=uI1t`IO8kk*zl(^ zC>*^=Z%PLCIYThqy5K^op*6DP82k6DRdrYv7%8@cpI4kG#8ttlA>O+nkgF)RBnLyQ z_|Rg7VJs~zp{R!>mw=s?+(~JwtF1+f_*7AhK~i?a3Vd1&;w)dq;7eICv-;sh{{n6= z+sQNEgJ*{4$766YXlgaPZv2>pIUjDmhi(u^SDZJ|x_lEJeJUE2j9nbyGJFo#4SU!; zD3VgGB~+XN= z^3WK;paAUQ_v3|UZ+Y*#VULUo?Jtamc#w9s9nS__gW-7nZ-s8aO*8K#s~*<{9*GQ} z4f=Rp^-DE*a(?gxa3L_U^5A?OV^WoJ`3BV@c*28~8jM}R3z+-hg3{6g(qaAM8XdL^ zzW*JI6n=4W`^pKhnscM*04)6?f?kYEgC}VPjs|q>)6>r;TTUkdpjs)&ODCtIvaJXK zAE66R^9#d*mVY~y{bG~H-w&~O?g|J9)HXFu4GcX0)tj7BxeYPs6hWcX z$NY*k5iUxCxeU6D^XND1MRRX8;f z8IE1Rd*d7Zyw8cB#J4dQ>Wjes=M ze8GKL8O-_oS&}#rx|0bBqzZ9> zmu+slgQm^*bj(-f!2?E^&e5?8iCjcf)Q^n=sZ596UwsgmAz~*d--=o=@K_>+tfQvp zpzWq1yvKsV)qT$kzJRDG5Eny{+~7&K&>q>=CL3%Fgnn>F=i=lv;!jOo!^pVO%H=VX z`nbCbl1E;+YXM)2JQ6bPi0$?D_2J>+)zw1gFff(??_{5r48gLPzfLYL;OssFPGv7K zK*xnmmfB|?wa_^Q98!RN=wp%nyFM3INckltDsk^&3$Klps;a71vYmh~#SUh%ENsVE zf%#pKJOiK}9SbmdZVfI_O6LW*b1FgKsT7ffX;4h z?IcL~5)(sesvFg@AftFgb^v|`kG44F<&}kP!ROfg6_+XZt?;%B zpc#^5u(KJKmj#W{%=y`2iS`|?8Cr40cZy#u&VD_9bZ6j+o)go;U5>?+U6>tr!OH*$ zZF*V-d;Lj)JSjZv#f>Y^a4{vLpsD`Q=dH%Ar|$mkDaRXL*S#h!Hacl314-{Xjx)BVj^!SpY8 zo5(3I;O2N=RvbRPCnNrs@=ta~s>dn}3MRsO?43Vwo~CvC_1VY0ES@H~`Ou8-VU6g3 zwMz;Hhx+wZg-lAxi)*||0tuBQYXX>VR7}`}%FJKXMj$>|gF7U5Xa#hxc@=CF1i`?= zPb6s~ASBeXKZA)Bcf!8xie7$9Dy#eWF;F(DtCN*;mHF>0tnycy1MbPF#%p)&HoHVxDgsSwnm7Hz2clAy58`ZJ$pcqk8cE0GEOueK5)=L zg8<^0quJSaS%7ngKV+s&zGx^5`bAUSgtk00I&A;;1R3a_IaSLF@T_IRT;7Rt{FSl zz0hlF+y+#S{OQZL73eOr)!NT|gv)(!ka!>z%1xLnlB1La_gmLD7%h^iHY>;;D-RPC z{$uhXC?>XfcoHh%1i8<|gzkI*Z0QD&InI5#6tw``9>`PdNjM1ba!6tbWGA@-NbmKo zX^e@sC^bF;`UfLT?2Jwjaln!E*mvUO!))E=?y-K&;m>l?t424QV-PyG!(Pjf7B+N8 zE$k3?@c5L0v}N)3wd5m__^(|uH$3JeZq$dCv*~BuR?3nOBe_hBP}pnGF)AN_d3XG$ zoBfgai}`&|NvW#4`ozu4lF}PLcN!1RHrsrb)3+$g-N7#+sYgXsRebONqv^WisqWi< zbmEZAlY}@%k|arzWD`ONS!E<4At@u-BP63FBrAklLXu=9At6bU9hun)8U5a;=k>e) zc%Ikm9yz|}^SwUT^)>F*tGu*d0Y%~VCm=b-{0lc7I$N3K>9Mv9WH_1Tvp-c8iSxoOF*1sfW^~XLS?{;* zZud?D;qZXq_t<-bXgL%jz)6F(p=kk1de4nTq2E3C(uI#ie?|HsBBR>c^oqN*nBQV) z1q47OdY>v@RlWG8Yq;n&GqFzO>d?DwRs97iJueG?|`yNv`!QFJ&sZZ($C&9>c+ zQsApyq$g%XM+jnKV(=p93I`3n>~Oez=~AGX5Vo>WQw7#+deX zdN{5lPQbElicP{)K6Q6vxK4ZD{KM5n+iIkG81)^#KXb9tii%!Kalav^C*kNcaI2{5 zVXwoWi=AZRKhc0RHc_byLd5^e>*k3Qv{yf4B?eDaEdx|T5X@v`Y@UXm2(kFs6_;NvUL)}{I|Tg2sd zKr}x)=1u~+p_8>yF=hG)8z0U|zhk}%$7l;_|t+Ow;DfZI* zIwIh$>{RD^aL%fH=cnFd7mPfIB9ElEA%xB{(893x*%Da=lE(M%>EoM%g^rbW_db&u zGeYVthG}Oo|CZv*5Y_TtFJC`t@kjsEDJJc9G&}H1P*NKxUG}4<9~jr-o3K7A@y;Gz zeiw$gIpbv0hgmFCTuamUtXDV{*WV2+Fdc9hH{1A544ChFVA|mN#Dmt6wc^440n4!p zVO|A$f~qbb7neAZ*gO;Zzp?CsgYCm#t5*-D86C2GJ7MfHYZF- z&fjjHtnK}u9wzY2Se@*^(vQ-2AdkTda> zPW$-fi;>XXt}5Ru(|o6ft2v`vIfXZ?Nh-Fxl^J~d`qhs!2ODaP@^E`27ZM45IR>UV z29TX0u7E`U@oN<#D)e)Z1)A59+dpG*?i>#X2bpM%Vu~va3VDcPgznm3y}E!kONgn& zMuR%!98i2b$|fCcZ8bx4SVucDGJ;dd<1s*mTV~OVvT3fY%pTrQ**?g(#W|2{SiMhM zOAASGl(6<{J8_x#-cCjpNwgNmq9Y5Q1jX<=erD!>fy<+=WftobXZ#fu@{N$#5D4uC zF4SM+?Xo;G4KV_`Cmkxw27t2`PT8v&*H3~}|tk&aV~WzT2L%uWlFn2!I_ zEi}fK!VzdjV2?&9caRd_a;z>X6VHQMF;lFu8C$WA)L@3{$WY;1Nto6buM5BFau6&(UNpq4QEn z_+WypD_yNVQZh1L*dQ5_&RF*h*;I4iRUv#U?Oya+2fjiobSgcT(%O&T?nA;MY{YRu z0j6v<(abFJ{p*9)80YBFq0Kki97_0Oo*0N=mj)L+8m9TC`ClBRjv-@)fhNV{J6)#! zPR3B*^+^jvn2=Nz3n;EI{Qi3$c~CzV*8OFaXQ*!N^gs{WjF4ZSsZY23AKFty$0%(! zEi``k=n?ianTwstXq)wr9f1JTTA0L%lpGa)mrKecBs&{w|7tW_NGZpYC#YXWA-{Zi zZpAyVBb=!L{@0v z#NxRk>W~_N8gM9qK~;}GMwo+vN7`kRV+d4TGRZ<3^Z1-Jf&PPv3dWLha*tX^(*l7x z(gnY9En|2mR%6M`=>XWNv%MX|F{hI6w1KR6lmJ1onnXtoK!dI;j5r)P2w_RP;;#T| z8P`AlLdaL4vG-I-CnLA?fSb&qEr1J@8cGi2+z>9E1TA0`@K@o2*ctgQl-K9$xSOV6 zEU?t+o}=OEK}v&2?r=w9E{^Tqxc9gXsu^mocq5M#xCvef@fE~zVFEx5lV)bDehxP$ z=fu=hMN-QhubbF?DHe}l$EMMR{DJ~Z9&jq=7*xMUaux2wjSW1n%Mu9>_D2h1ku;qz zHaRwqjXmjgqP>D^5qUQb4)14{*a%dS;mjAd{{sr~%AyNKBSaOiEXodl24+Zn=?*2i zZFXqB^Nl7i9}gi0sAuXcNXz~HdLB>B_Droc`4rk5@s86upXcW#+?=S(u|*lF9TO7{ zX}YPxnmGnYzkF{e*>@;zxSmQl;5&y%bu?9mE?;$~>`yiE6p@$<-(UFB`SOaN@?}u| z#riv1<9WYm?1G7ONMG?cDpK$UFZ-RHfL{0(dFE|`2>jsM*z{ZT0K>sH>oAI*nb6KGeK%>#v|2_CI9SBi-NmK-z( zN(PQUYP5kYc)-S=tX^hb*?wI;_O=Q?dPIDEhz?v`nyD9OQ0-qD*>sv=(=*mO>ljaa zrsf^vZeBhf?2& zv79yQ|MO*Ief0`AymtWf(Q+VN%psDqRvh^UE3Lkj85x1KgQ>#U>#{f8RR-f}GMv~Y zC5Cw&O0zoP8Ql)dyOu)!s0A*CA0 zhTM#pQ30380+_`slV$&G&%=ZSjH9r32!{jg3$4AfwhSQoQfc=!nO;l|RY=!;rn~4N z%O3ILbjqK5=L)igHO1n0MAT(w!mTJJE34K13+wDN^^bb}Le&Y5J`X3R(d5UE(F$bv zzo7ipm6&>TgP^$VU5R7g>OF#=jJa~m?G^q6+;OGdJ1Z3aH5uTUtP9D+H@3w!J8dps zp2B?uh!-Dz;C1(>PpD8Xf{@PZSkh{;n?p z41p>f9S?T5`yvAe_1QH4#YU!#mL_9pJ3L3%%k2|G*bhb3w}1OKv9N-+6y+WZwstYn z4vzr#pZAcBsEgGS3alY3GUH1}=A}rS2xsKE*B&vgqgZrY*6UQ&FMsst$`>=|ZQHh4 zal9xjq(D?if5KXN*eMuj{QX_adqJvX>iY|x$T4{F{JG>;1_2^{V)D_eLJ3+Js7SRiAL6D?wLpMP#mYz$W%vOe zM?*uSptn7$9*|<29l#I7DSOGdI9HWkCPW>DP0=4|#mDVFtQkBbf2XYN^yDNY9XRKuEic)vLwZ6K# zik29l32stawZ~*)Vq&6xUWd?KI^#_sD|ChJ60rl?%)~@bm_$;=01_1$=~;0uv=&>j z!DCQ%9?4=#MUZ)x9c97Zv17*oQ#+J6NCIxcu3|UT+d|`>-rlo$9oXOqoI|@Eo(5dI zm;v!tu}1_WML{BgB8oT7pYASY+F<_Ko2hRx8%Pc=OByJs1|O(P0_jFlJzMF0lrxgj za6Kxm_Fh@{K{}5fN!pl+iHTRn4c&QEJph5?XV0of7Y;IX_w@W)@n({p-Q-q_#yoWv zkr8Oi0XpiB13c>M>Y}=HfSWNe$iccwzl?s{Ut6X)0y&MSUj{(cVW zyabMG4e`=#87FEg@0ehZYqyO=G8}K{3c!kiq6urX39$C-q86uCPv!|S+2z5!%*FKg z-Ia%XjTBv|7_&Z5>63P|N1&Ym>HB?YRq^bpb~hOPQ(95kqAR?R6pIs2bpx9oRAX)U zW1`u*z zh9R#`abF}J&>beUN3EkP-aazPnBqZ4kcrQff~bptX<-XoWTa|_UZF~Qn?n#kpLY9f zWjvV(sJ?R&2Ud4KwSQ`U{x(^6E}B!!Z-M#A^6b$-7=n`Ogo`w|)n?n`UZ>D~4;s;4 zZNlE)rXO1Gf_j~HgsEU5dC;R|7wOl4ATdmKc3vzoU7EJATvNQhR40Cy_BTH>@t@Z6 z=kzo?c;z&B32>A?jZ41Hd3VJ;yS)O{CCA|X=tAR<`F>YAMMOq>{2FV+h96i`V+HZ{ zBIX4XI$eOVu`$;6$au^mdN;bwPLxD1eFuPj6Rs^_D@x3dGc&i?R_Y4lvc+OHm}DvR zUAFwXJxLXPo^bdpuf>Ux5nG|VCMG6W-nIl16bIuV18~u&MtQhukKOqFGh1$PFOI%g zJZ0-t*VJ!#6nkqj7v0_SjnHEPmjE zK~@b>c9@xN8xr(8^L6{RS$Cj-1b*6n=%utukMLa$3Ato#}4i? z&f6@xk9kyG0^pD1y0iSQa zQEe7%Q!5LjAcg_leXw2NSz_ci02@|6l*+4>-9G5TQ7b-XvasR}Cbt05H2BV&ejv|* z!qK2$LU6C2qe7Wul~la&LWb62>sf{OiiAcidI=0}pmUHj3K$=o?S)AogDQW0I*Gsk zF%6&)l7f`n;{dTV+Hi!dcvn(LZY(qXikVi0zszm?)AF*kdieFI*U&@g=s>>$rVFYA zkBxr`Z*Qc3ZaTd)s-9_=j9`p90#?y<+1o?6v#HYsIRw^){~7IjVi4VZMOoYXmV#bT z{hP1U_gdcsalcl5Pxm-)&~g8{CqLfXL_W3;y27W#5~Sv|MW#P?Ki@Cst-D-Eg9A@) zMdSrJCI?-Pb=^h(NbN1V%f{>XXlss2e|kD{#U&`1FOxGNFZ%F2&m6s#f`EEt`sj;@ zE{VAPdbPG`w<3x*{(I`irtSUtf1m)=sth!>cw__hyGh#zzIlv%*!l4cHnv@n=GN6d zvNo_erw*ZDlVxQ`3`VR0k;ac)ps0{YuC4qGfmdNR` zF+WY#AVJFmZ$=ktUR7b-TWC2(=E^zXp75Rh&!>dewDwTXvvhx-%G2A~_$lnndY56J zSUWi8CIg3ux*%?OFyAbM@rel>kLsTa?we}MkhA-*5Po%Jykj+cw0%4L(ZGBphr!us z2@Nf+q6`mYKEVb^4_OQduR=NUPW~~HWLn^=7#vnU$6)OI{)g+WVyogVyaNs;oYd}H zsHtqas$aPXAzeT$K5&0vjff+2fV1W4R9_bQU55G|Zvo)w5?fg-Gg<+@etaw$*pz>XTV3157+lPERv3YV9N? zM)BgK-SWoE>M@a%4H3ov*7+Sed>EO2zbUMmb>UCF`{LJ59%l+jCx%q;N~yFzKUaW4 zFYk*{cy8`WXl)zLTW{}_YZ->v;m1H~U|Cze9W&L_^RUAKX<_2$6DkgQF^@3RdI#>h zAhENclMCPR;4=j>nFvE|OKWSOG_}~at9_~d{OI+7WO7En5%ZR_C^RN?hPla1xk!UU z`7dBdn&T?sUfCm5zml{#7(Q@x=;4Vv}PKFdJhh`QExPBs3J6TaxWHS2Z%)o^&{1+!Toe&x0UJUWR2! z{JSp$ZwuW;KKj|Sk@Z6o3IA19^*fZju}?r86SnpxCkOvo)5&&hostKFTm75 zMcsp+<=-j2#lIPD6AMHX1ev+FpJ0n9NzNyZ-u)>qs&Jqh$cN3L_ z?shm(Sh#xYgLfMx#l^wERUgCl+&Nx+B0O#NCt_z`p;;`e4P_D_@{{P3bw&lEWWT$~ zun?$B#s4MMT#`&g;AnVyCFqL4AGx@0Pa~?by}$neYgkK)eCwbK7Fa$p${X~-c27)6 z9v%;nb`_}>eR_)LsPPu8Cd1{_Id#3b>nAFnb)htVbFp3*w>oPUtx9lQR=HR{}2`QbMe10d1msdYCV+?bt>kM^xhQibEq_^OUZrfTB4O8 z%3>3jdPz`Qm#8W*`!X$IgqBppOsZw(RyN^y|4vVi>+ZZu@`Lu=?Iu59#_# z4%{CLe5dV4~@61Qc2tTd{Vi^FfzLCd_JbT02-mWwe@0g7uy~k5FLuDL1cBQq~5+h z9YI#Oy0P)T%-mmL)AS?V^iJL_(u|)Zw+SU$ww-8~d|exAdM~&t>W>TUyO#tltpQ~r zr_JVi*g;0g@pO~HGfktW%G~sN!R8mILh`-$yBTUVVr_m0q(4z0Z_3mXCe3?Q;8mf> ziqO!}50`YFL;MkjLaZ1C{Ec6rf2GA8GEMF+3ma=XvbVaYe1>CAASygfce!t=(tUBF z1ME&;-#LcbRKce+C#n69h-)w2RQNzWw*TY~_J}RNXp3cT`;&>%HY8ORQr)xuXX+dw zKzt6M20_;-yIYWiN+qpB24Tis53CF4n?Q}-U^7dblVNP6 zbRkf9y|X4KXa!W=?s9}U0o=GKd$;3@e>oSveM57A;5}Bn%~DGx%zcs$DC?5Wvm>hr zKP|P{7H!gsw;W|N9A93?ABvDnH$o|GQ-p=|e#CJWbk6(^P<2){6*sfB-TF|2q>8r& zV|y256^e?1U#Pxp;W7Y3caPnCYl-P`85wk_d{<~VcH6!|h8Is1=#W&}{Jy;T7nagn z({y2nPEi*`hl=S>Kj$7em89nK)?9$r+}xN8aX5gx47wO+w=24LOtW5Dva#iyi#GFN zLme{^@o%QBHN?g$h76xMkM+mL#)Q|7;g!CfHrPMI zMCbWe{@LN#2bMG-84xbV!$89&>fwCjOdmU1`~)tSY(G7_^(^$f-BUF6-*NJ6BcuZDiod+eYGQ|HD~8i)BKO6 zyW=!LA4Aj0#TW|6Q|K-vMrcHtevS*Jt zEG_*K5H~@ws7utX@>!Q-i6-!TZ0%d~krxz#B^%#x!Hh$RsYC*WT%`;63fk6xGcCBe z$3fN{FR&A0?t9(7Gf(|I2?9&dbkAOT=_4q82V!o5A}(cgCY^7H0cdGK;0?M|+q2d` z^YSF>pW#;O-NGv&pMj19{4E^dnAL_a_|*pJ=V%GCGIQa;*(W0J2UjkC46`8JQ{lx6 zzk|2#h;1CMuJ!{D^rREJobrwEQ5CKs)EaG#g3#syu{1}!u_b%)D$5DURN1%ISD@Yz zWxoL;4A+!_9H=;~KC(Ut?EMNW5G)kOG~McV5q11Fm1H8mXRmYflv3v>G zGT~_g(Cp*K|1BE7uO)O^iV}xR(A*|{B1(&hrl5mye=50 zsVYozDEX$wGhE8$!fB_XPKRa}u$FFZEdy>BulJkEc6WebbShm1WXj;L+Wx%F4r{5A zRuZh_&qrlt5T_Y@usvr7J72l3JSFZ%EyHuVY&6x&+}!*%Xk9?ubC4R`1SauOY0H2M z6h9-EELKhVV^F^EFe!30d_xqZ>P`EmvOvLMohPj~a(VZMr&|{;zYSwU-MMpz5=XZw zM_-&SVK>){#)pl^reK>UE7}Fo)aY#1p!&}wP(!5nM@8)w_pLP3l04k?p0ejKgUO|& zBqo0A>cTGoa6OtBXa$qr*w3Ff!>&?E&6eU{e_ppO{-8>Vs1u8yg#Ha64@xx}#8+-~ zv5&Nb*lg6Ne*VOEDBKBFGUeONO1F&N23HP3OdR4Qq#; zq}<}?(*r4Z-bs`^&K&^wFpp|xe(UM+MoI#*(okwzM_0#B`O?SHAaS`AJpz_1SX6i| z{_H9SeVN@3+G=s}8hFMpU$WZlCYb!|tnt&!%%9>O+HuY!4e))A0V{z@by1n=I6>*s z&lWG{kP8aV*UHI6#12@CbKounPBrdk8H=KytaB0N8?&QC0xpNZo}CP}6q+iQ{~&i> zCjy|bGy~AC7cwx`als+lKSmuGe2xLu^O)uXPDlDX;b0R~6F3_}iGR+FmG4(d%?uv@ zg;EQxI-pcocg~rZ97HY2XrrX;hZSFJ4RE^vJ(ri)H``+W5nk0cb1_uI_VG&8}& z0me7Ym*QX$)WCZTP6BaXP)Zu_vL*i4Vs-T;w^O0DO*i%?if<8ilE;!xJ^3o+JK2T;P z5dw-2ys-o(pvhuGB8UyDPDqLYuVYTb%*Btc0OB1KJYmu&NkA)#O&@g^tgFt>NfG(c z9BK(gsAYgWC@G1{vX2$4v3qe&iz*NIe|fJDKXP~gv1@Yh-Z9X}aM2moH zM>nb6ju)0vgqcHBDw|;a#Az1 z&B@qdh}FTj8T{l30k#!l1gz`BY_yphhxf@?_=E^YLyWTXcD%Ty!XNzsENor}{X;#u zl#7MN3ITWz&^^%ylQl%{Hu@=P=XFRJ&LuzR5pYA~)gpbM$RhRVgv1 zP>G;TiPLa*evKa(Q3r#^$0nSOGZr_m;qi;a;dJ0dYx(d20O|4h1_3bEGfUWDQ?V7NAWSN=P- z5X%5ZGVz_#^+GO`^{XkXJ>V=ji3C6y2SCqY&jR2==bMvei(4~qLt#|c%If)XvYW#w#Y?9jg#BhF&@FMYhk!jK)mZh&qFuJmBEehMAcbis)V4*miqK><&PuZzw;Z1f;_~2YY4QxPSb!Q z=>~iN*UM|}Uqhrl6wKb36Znwr&9S|o ziXRl+OM-!;c2GRDwy?{wx&U7_ zLT=jZUYa|huYB}~Jq)}zqarg&QTNx87C8{XxTIm%LWVkKRLBNxB-U{#pjyC0?~{)E zO*~}->0Xf2KDaoJ<^oJGlsT8BxCG5=4A0-Yl&NnIl{>^l7OUSnA(iqQgFg^3Aw%7y z8DrA&6Th@-=^;n%oTl0>J+BT-=NLuFv%fWetz0`=^lVA0sM2Qlnceap$){L#35vvU zow!?^8Z0FJC$X0~E6;tXDZCN3fCepU2c& zwT^@ z;oxh*8`>PwKfS56JHLG#108gmTZ01{ZLkLRUWY^QWw}3N8ECEG`YJPTnYs={5oZXp zhJdt!f>x)}z}K$_qam%J807BUVH7H1slSrZwtNPDo`!rH=7F0yzW5FT$oOR}R^Fch zpo;E4-w2WVki`P=t$n60m~NDZcASrHiISu9|3*j^}NSHpsv)#4v)B(Pvy zH?IQ>S#z^?L+qxmEuvVX0DpqqYFDdQMIYX5kvO}=FAgQ>GHr_$zaILmQ(bcS13Kcb zU0oFWBDUQ96Ojg{;|zaxD8Va1A586ij>l(tFh76)lXgfxnto6RB2ucqt!=JBAPPV| z`a4}=LckXFF2@J=0rwXdv#HR3*fT(k7y?k*go2OtM`H2F05=yq5~sP7fhKwdcs1PP zBHJDB)(=66r5wuWpQBl5{8*U&r*rB`-Jpx?Z1v`91-wr9U2%22D2YD3^|E>OnQ0?6 z@OhxKW7H9y8&yvU1%yr+enhaNip&&1^1!>m&1D^n1J}zb)*JlgBCVx|cl|=4@yFpz zyz@>=lLb{U1X|Gp;6zoiWbN!8c3h2!VnTAm|!Q zrN*YF4wo+j&IV0}aTo5UxTYVpjNG{KDYQAX(4dlG6*M*;o0tet-~|H+chjp^C`ec` zt?_RCUV^Jv1x(Bob0jXRDM%J4CK9n871|8D;x4o^WQsl+f26eAm~LRDvd~?aRw>Kb z=YKRoajPvaj%Tyd}zM z(ON>AGk%os6m-qocG1$(65y-1w>K7(Ll@vw8g=_NQWddL%TyF!y%*Gv>=D-hAJpV* ze!q;`f6l_9{t9-EI882Y;#s9x;YQ$l%C*@PDBInOoSgObq3(c)zQ zk8+%$7I;%qbI6GvC##d<9H6MZ<^BQ+z@fiw?}noVOn_ph#dkv{LeN^nl~nfL(s~Om zk?t5r2s$B;ks}`0j?BfRrg>Lf_5HTmf4Gi(!!J04o+={ZykWpdk$9`l-ZMhXf9{)p zKS!m?*Clbd>Z~Y>L9mKA!EmdIBloL<#N241X%;PQ?VF#KJ$NaN-YEu{4b(EMOm%)w zPn^&rDbZd(nH=+qY(`LoU|VtrnMhr>eb!7xlpUD>wu^rv6<&ax01EJJfG)r?U2J0C zXb2x#qwIEjBnGswdGAhe-p$(h@gvq`2lBoo1|W+jMm@-ifbGn(8!_-P|Q_Y zuS~U$Z?sAM3n3RaVGO!3&}_bU@WUHX_LE}q=$is-@b=@w0h6E)*3AT_to{dM$UpIS zO%s~Oh@qE|Zk+FL4pbM6gi;U*DjeVt7cfYe0a$S_X@n1h!t3nATX+ znA6p~%H+WnH+5aPN?BQt{=08R8?hKxDy*ygbN+;$0cb0OT!i34z8O(R-bwi52hc$H zJ=7*}Jvlt;y$f-IYC)&7qa#2;apgkOeEa~ci3`AgMlmr_BIhbSWB~&J#(|6Jp}w6G zfM-7f+edv$(tkQpl{vK6XX5i-=|i)8l2LwUf+`+Z2Mjq~;Hlx+S*9kM;Q!YGxWI|G zEdBe}F9m5yZt9+`sc%iroeL2)F7K5Cg}(r${@*%_wK`0Ag1H!u(8wc4^Iot+$)B>( zM^KxU-xR~Lt8q7oDlk!EE2S`rN6!1JjRdrytLr}O5tKso?HheTGnefEbf2dAeZXY; z`qcD3|8PYY1^EaTYcdmc9?3#-#8=hz!*v(LOAKLP$`NGiIX~RcKn$&=Iv;;JTc_p@ zbE2(}$7a6t4hM?Ero`RZHoJ0oktzP&Pf*YO~)WAdaS?qLj~^49s$c%Y}2J6yHabYU4;+(q&A@7~R?$le(uZ^jFNAFZHwui1KY;ME`R zw=>kjj`-Q(uy#9^jzX3RF+@QDT1(&}GzDzfgr08%Rp@bnFfwtt0P~8CL_*UK*bK4N zWMbt~oF<;rH3)K$Q*la53mYK8s?B+TYw2~G0YNb9bW(HQJUwbd@j02WQ#Y+{}Ks?{1^g)XUQ%JDy4ZCtp5H0p{5@O(F93 zN&Re$mACg=29FY3l{{zP#?1kVa=n77i@!c>qhG72cQM=j_cCq!v#-5O9#Ln17B(|+ zukbV-c^KY3{loqEME^BM_rPP3!_%~$*?XVYe@=JqD)DQj4zap@-)1Rx+x|TtsBiCl zdpT2UcE3kgz)b<5DD!~{$^u06GE`|W-6n`|idkgpTUBmx4-DbosThreFBY$;!_*I^ zhWV8L0XpV$P>Sg1=#sYdP>~XtQy9#7qK(8wo>4q4(J_R&qgUMqL^m7lWep=pDhh{F zcf@ICD!eFOwE>y!CbKPMhr)FQm6KppmNe0tjV`$J3j8G9Vjw8uiDTL-W7cjjG2PD- z71))p!cV17qpBCIq$d*hKpNxNHoj&uL0Rt}xpBsO^lzjE*I&dv?67-8tsIK_r<2V> zK*l8co1nAA0PJ_Xb%2kkgu6T6=w1HZtZ_`{uO8vj3YoGNQWlE`oq*ew?2FP$P(=5N z)U-K1w;^r0QE@Js30Mz75rQy@1Q_!hUutK!!&$|t zVd<~JkKzqElFgyo(E)$lT<}<_3kJwMtRIRIJbL5^XaL+7=L=PsRiwFT+Aj@ci?VNR z@I+Zw%Rr9`FHlAs0B3liMcIK2f8|32$JoZD2YWuU!|kXz9oj=bO&3~=QU3LLKsxA7 z=jV|tKjK;j90kG+7j3BOF~8Xsqh;4Qz}yZAkzNF(M^L#Ibe?1mg5+{~n#P(j1O|~Z z6a}@DI@!ScfWu+qs;;m>j=??63-C4#k!vlToX}(wgWo{*uf`BSCTd`1;#g1FRmdPg zBO)zjBdKbIOP46o1p9!oD0UMv))ONmWs+M!F^b+Vmo&u0af)3yQS6JbZ?3of@nX`x zi%rAFk2LlF9jv}!MNd_3Sl4@zy=&N}APqr8YS8I6IGZ7OU_qH@uq z-P%6A&7;Hs95vPX>Aw5D<)9{XY@)7l89!q(FY+mN|2A~_gh%$S-Z0x&C$Il}ktaDD zReqxA#$xZ*p51Kd?fVG*XK}KDNlw`f`})kvb4^ZCl&t@CIQS=)-FWZ1oua-ou=G7C)? z*1g7Xkg#W`QmP_9l|NcnTH&MQ0Zzu9zjom}xZdnY{~PLtn#t$pVsO^Dmfg0(7d$lQ z@vL7nlUkN6cq*>x!ma+?C}I40xO|dz5PUEdUM>Eq)cg9sU<-Z95(R=ZdBBJm0C5?# z8ZWE<rj1M zAGqN>C>9)wpQ=Ht+D=d{c&mA6@Qw9zj^++I!OZb`7H;mTkF!e&s=YG)(Se1}Y#%$Z zr8s(fdqii+tFviS4vcosc5uzLgC1*h^?D>M^I42!a1T4SziR2aoXde5qAp8jeHFvK z-k)X-YpLB2Jwqjp|9bw3yZqz+Ydd(CJ7{^n(LN>8obqiD!*T4}9M12^J@uJ>+3|KH z-}w&n98H$bCyxIo&zMUpx-UGMXOpGE$QjJZ!d08(?gfznt_c|-2*!S@c zHrYm&r)QTPNs4W@fm&?ZYkdEcuTl9#Z}YjUo=oJfebznlxsPj8lGZPFxrsr^wznyV zbxFZ?k9!s6|MwBr_EL%Mlx5FiDZb%yJAJ%t>bq@``Rj{X@%VMtU{iHJevs`h!8LnWzT36j&E|F z1V~95HbGkl27tQe^4$~i_vQcyxJV;PlSo_vLSTKNmBWSnpnBV$+%}k{F;dbWtV zZ6{9jYkJX4Y7Wr5({lN~R8F`5!(%I$WS1U>OH-O!)kCz0Tw}aniCa}Tk@4|9!}+B{ zZ#Fyv)tCukBbQe4dvszv9xH$2AEGV&tZ}F_ zeh3Rv12uzQ8FnFi$;2B)n|MF29VLlV$AAA!Ok)G)=zQK`pWYVg49W>n0wUU|HtHp=MN)*A|jHOZ!CybO?ogB zurCJV8~pP4Jb;zqiSnwbwAx8f#N>!8pw60kA6g9Y&u)Cc zHLfcRvQaAOX18586M-8OH5AUcMVv|x9ip$~*C;X<+q{2^)ov{gao5&s>^+Sp3r_b# z)kpMm-i|ILy*9+Fhc{L-WPq5m?DsAqr~j74E_jTMBd=uxvR3>Y<*aIT;Q zBr}V5w49|m_%nHzOZOW;``WH!?P*r-rIDs~W0UskY<3(raw!%jCKxAlvWu;Dq_%MI z^2%QwVbF-x4L`xp5?DitBB6jVr11WNk)F-)7+tu4Ib`$P+@Hw;+|3X@l=tfB-Rqw@ zm8p;E8m%Px7M3j`F&>_SzdtNCG8=9F42`pJVx+_8+d%vo1z`f=CzUkC#JAV)=CPZ9 zpfCU3zuw!gxJa}>p#+b{N1UInWik`J&vfw@ZxBcu_|T!H0E!B=XKt}oHEfg6lfpd$ zTpS&NgdALkfE@6@p*qo!4I<$H!g>&wG&}^M2}DvLCIkN*TH)%sxuw9?(XBLrh&i*9 z3?R^fJ-}B96A3s07b9+LLN5F#1X_Ao(=iN<^)A#K8%cHbvc6F z@cr2)MX8``Iey_UJ(3caNJ3Sw6MD6b=HqU(ABlTB<`^uxXD@?l#Nlt5gGn~r+?U^t zgCv=`ePgt9aK<0*16Ty3yhz$TEW+XMZHn-qYyZXyt|00Sp2CQ_`LfoVIynYk_H4yi zVVY0#-5c0=nW1fg=&UTQMjD6py#?S%D)KyU2=7^N9gK8u66Yhxf?a!*4P^&Jw2bflBJ< zocormIuC>plDCx5>J3i7@1vh!BRoC(#l%2OXX-;eh$l^nqk!FCKj#4_Lm4&}pKuwW zWvt{YI|SB`l@8MlwqW-5Vnv{dsF8B|=;gpY&L^+=D}${BDwxMYC~)EcNPhJyn_{$5 zn%~-Qw{Mp(7S}&;A9`W1>p$#gRrJ1s;|CxUZ7nl#q7&Nha|KHPf8ZOU_E*R;fV9j~ zTv}cp%XOEgx)Jj>LrQveW2SW1)!JE9Bb+3dd9jdjN&`3&MG<9h4<|(xFB5e+CNjB{ zQxvu-lu9EOf8gI=r~U#qLMwV_sLWgk%=qHs&FQNtD99foU6_!!s*<4>o({fMKd0xs z#vgXgxK>v)O1<1ScT=f_gJC>wx*oXr1h%+%0e31k_lfhPsw{L)4DQI*~Y# z5&`62Uh6ReC*J><2Z#=wOH~hPR4_$=3T+(?9NxgI1Z~Nj2mBxSyRe`k&5XwCs9nnr z*gJRZfR!MC%o&-LpMTlX5<95?VL=t}Z?cc2tPE3QerqQQPbhfE*aW zn4c#X@rDX&NX=r2abzS6SXN(Qw*h39b_sWyLN+9h@S^g^+)5XQo^4?zy-hg8iZk+^ zLkUjWzqTH&ABbL~Jb=gV5U_$0qm(w_S~j3u2*(;YA(1$cFJHc}M{AQ*sXX5fy8Lsy zV2lOB1^*PG}l1b7mGI{N%a$z+NXMFB$K4hIa!c^$~&2~(kt+=GH)E+#;X z)yzcKnA8l_3;us%4dbe2CNf*#JGf#l$Vx#}LP!B*AUfFoj&74kaOqRn3PJ!!Y|sO?4Fvns}cA~S;~k5T^|t)|gN(ui4%_cPgaT}AJITObIExDl(i7}F%O zh{Vxr#BxwFz<8qE&C=)}cp2nj?foD{@jUCzry-H71BGyz`805Trz5&I7V|=D2Pwf) zsEsh2BaD$dv^GuH0ik>dagp}jkPWd?%eWF%?#NV`<9{;Og6F5+^xN%yP$@vS2i*jj zx#zlo`zM#)>kNJ&tyWu^xP1qP8}Dic!}#L}&%c=11|>`hMwoFBY18?1e-s#rU8<#1 z8xvxl@5)VH`p4$&c>~E9R5hTEpana=!+Q@i;h>b18go#a9bu7MG6IO~gS8uX{mTEA z`UL%Jws_h6I0J$OtQmME=#ENj3jA_?uFt0)o6a)aH%Rl*>^7seK#f+W?ryf=iS>N_ zySJO_>`01ZLfb#7u(^i{QLJ4w93j2;Y4M;iTj8q))Rd_Y2pS?&T~eKG@nOzplzr&L zpu-4L!DOL+7aT2SY2Zt7n%m)t58Si{x&8$lGBdNS!AdybaCF8u^}hDJ3bEPUMoe-z zh2UKy)poOnX=dimXaYk-34$>X{&?v-$|gKS!oThr2MbzJK<;aD|EAoYZ{L)d;hueK zDGsH92MfTt+EncaV!CW!+hsXnDROtIwlv-y>hdM znLs~hZ1In2{{3cKjo2Wk7>usgg-`w&IbfD7#eb_>sV1mYbm=rI?={0V)RU^4<+(Cq6GNJyg%QPKM?h3}Tt*f-QfH$B(!(7_@l2XB7i$qSXaK zxKl#hBI*FwVhs7+brIRD1|q7=!@chP+d^xh=JNLL8Fz!L(apu>S>^a9M7^!$o6xew zb{&2g?cV2k(aTGQL_a9q*WG;#n5(2Dfg5dH;)4e-eb&7sInfQ^zT@KIak6u#9$xS) z=sYGRg{vdg`?$xfrL%K^x*+Z&L=}ERHV&915bN-W1DHHla8VHHkfg&wX8IkSSkffjUP$wI>kyBHj1zkV-WSw8`e1zcq-G#og~tE2**(^`7bXRmK`xm< z@%+==)WEostb>w(pTS*^o3qU>C=cifk`O|y{-#tMi;SFohj+3Lxy+u zHx=#HTU82w{PJo8-^KoEuRf+w?o+}hFW9;TL;v=NDx_a5yE@94v5+z<%k+1P(q7D4 zfF;ir9Enj!id3@P&BS_73@D{)A|(3PCPns%MWP@PD))<}v_fO}P}Wo5&~W1UA}soH~q)X;~_1W zR@yRN7$L=X^YYVZqvoiJA+NU_hqPlw5<5pDZhzdMIpf|ieVU+2cuU@tLU3g^KDGQi z{L>wGCF1#?$nrw)#$krQ0=n$1ET2E^DG&<5N)6vQ_SGFc*!KCe8|pqTosHh*+1Y39 z<3Gp8?HwGDxB7*mB}JN>7;6~!vFksG!7OoT?X?@`@HZDuXw@3y)kj7sz`JaJk>F`F^Z81pXlJxqb9;6O|FZY zS2e!Ry|ho`Tv{jQ%h885Bv+y*mx7X)#A^mcre0NhK4AoOEAytZjBzsau9tHsX7F|623kP722KjO z%BN2quj_XL`63~K1-rqZ>~Ya9{rZKqe4ozG%il_Ga5D3W_dSI_sJ=iMx-_%^W3TXU zr|0JW!`LaxVvo7+kQzB$x&%~SQu~!#1S$jz)#tP1HM(c|<$g`|jVva{qO-QhJbR3TQ;ESj*?DrdASn=56pPP&1tSZ{w=)SMkHYiQaAJ-frD5pFgYY{gKdyh$ei;(CG8<_#kKjOUN-} zT$VCZR<6Y*C*|Dt;m8AAt|?f<2f7xXeu1FRot-n?lnk|-PNg@jt-p_Fr%;Y(%T;F0 zab)XYZ5kuOq98MbH4jr80=eM-$KZQFObj$Uy!!B6y$0+D{{&?FC^^W?D82skD+>e7 z%28R^g|{AfU41DYvM-DE4h#JAInhPv{iKri-)(#-eMN~>hj`{)@;=_Uz<9l9YY+r} z9dT^!l6cB;DZYU0c586*^7=x0-}3P2-Dca({tC$A!D~0+T819g=kIDi5+4$>RxsgvN!S){otA=mOQK}mfBB*?-;8(ytQ7s|pG>|3^wnLVu z%404)T^N%)$a+Xt)@5Z5Zr-$ZR5R(C(XzNgn6rc$>%W*NGIxY9BI@ zbv6$h*%mRLRkGJ^>8Onfd29#uY+-a@wU_ISSh(H5U9ZCfp<5x#@Ozva7V3s|_9c5ub0fEk(Jv+6q z0x=L&b;#XWb}s|Ila&=x`f8wm3}VjDU%osQe&Jr;i#Ue9a`ys=$UV>}ty?MSUGO%G#K8kDQq>g5BsaFSif0Y=A0mMJ(~G_v z%&tqkUZ@K{jch-T^RJ%b1Rz_+0r85Ir*-Mlki4Y!0=`;kIKb)MK6s9=$bF_yfoxgY z-9G*c-z%Q=3eSCv=$E@+>^gQGdBu^w+Bd-$R&oe6T{hu3@2}vu)PS?whxYX9)#Cag zJws@5=jWc*S>gf1E zoZ)OItXj~n@_G)(>^FNc_6lz_4z$s0Z;jZAi3w9vQ}``*?AQT|8u}NKY8e_NG(}nV zIJQ6w^b8lV@1DYmA_NF8PtTVxfFI{qybTSv&pb!e!I`!5VKWgXb7J>K$q3oPM{KkE zMbR=`|M?)xo^lVN4?#0&Z$EgA8*^7dK|yx*o@AZBok�%jLOO+x~bX2f{jzVtpa* zZ=RdKD7Jpw0OcgS)ur1ROjT6?nLB+frRO2GW20#@30n2X}{Jxx_}stzMdf8 z%o!JHgp5>4X|*H&iHDQZ!O>9`F#uWGNuo^7`ZWgOGV*&@=bH{-vOdOr z2W~-WX|!`QuucJ;X)0Qq#EbL46k$xj_w;MUQQ+WqfrgU@&k-bN6`~peDxJOBV`vUWB410(0TAeUxw$gee;S`Z zKLk=d%6IMj*-p$F`0M1w@r((@<*1carM=grxp9y%_n@)9e_}#`Ia1XH z`9!2zzt8Fv+VcrC;|dSch*wVT@!MAZwQrufrHfVRVK~PDvz#e3o_@sQz@2 zS>nhMgT~^L|JMSzL)nUmehe!((2NWWS~@z@-%2K{{Wl|L6d`53SZMhdUn=BQE_gwa zTMjw}Z3oTypZ>HwA0?;o8^I{5cIs3sKE>;2&%|*sDW2B;^=bD@4i11LkaUYC=5v4l zUrKT+oYxTjdygbsM8}L{2<~}#`Wf`HnA-G66qPizvJhrd6a|AW$k9df_HAZq>Gy9V zLql-v2(>!b{v7|lr8qQ125PyBvLlN~$X zf3Z>xvww>Pf|z5)5_j0TMtIgrYMk1?cuYkjb$Ok^#l1n%^7vr>sgp;E1$?M(U>)(! zz>|9SLW1x1)*YX+>~RrxYs@+qd!}sJpq2CP9CQKtr$<5|Y8^%VNvvRL_x>gc3k4c# z|JCX884RBk6A*mIxMzh)xdjEI+LA`x=L`)y&``wfI|Ciiem&A2At5~69;ec$ldshR zPgU337jTj7lY_Mn#W zn#R911d1f6P$;1ZAnS3r9oQJ{qT+iD zUdyZJc#6n7_N5o0`W|Sxc6RjUIqh}?GhkBB%|(0hFy#n(72tamw<3|twh){vZ4A@LD9OxZ%13sRd|)4DP#^p?-a`8Wrv@@6E*tVR|bh&CLfCan_qPI zWVBASl}mA#Nk)J&tqoQo_+o^)U}8l2feR7ZKOBR%NMQrzfpjMHX0Z5)nZI;F>pj1p z2LBx2E9FWlb+&MKKa%;2tAF_&yhf0AAsHUK4v=V@n3RM@70t+V`}QpT$$q8-G)f*_ z2-x>dVwhp9b#8}ezrDQ{C{50I*q%oNyNnrXDOsZ=RXUiNQT%yvBu$Ks8%7t_sBm{w z;Qs52S%M&*Kj`(Ji98tX$KB@3bSS=i#6dyY2MZxZTt4;faAjD|=b*3Rw~a-w&kr|J z90vHXh_I2+Uci6<{pLl{rf)?TBCuW=TRjU3a6ihWMD^QRS)~;g&WZhfy!wP@H+G!1 zKX;V6Wby?AGFr43m%Gu)=$$>=`}s3ad1(3?@m}ia=!BktR}tojF$xzgxQo{sx)KSJ+E)>o4IlzY3cM!kOZ}rM0f3MZ zp8D=9ek0UCPw7?pzYFqE99}O^W|DYwyemA$t?D zN45~MvnnHzl@Ree`h0x8KYx8b4_)^?Ua#{y=Xsvb=V=7tI^2RMnJ#4ia2K;aJK(wT z)_z)emhrVN=UruGAQBjjgIcVxv}x7lhWq-IE4*jm`TPQteAt5E^nt|0fC=L-lp>>| zU^xN-0%-WBCh*|rdwMj%Q3d?#FhBG2E&8(T78UX}A16{tv}6|AtqZI_9fPsK2W8>- zVdE>PPQ0aRFRRKq*7@s#Ek+F3Pj}5_Zy`7zEO?1-ReIf6%Fe(^k-D5ZaFVq)c?2sll##x5-9x=8jwRcO)V&k6wXeZJYZ zE*+0`#B%772@muWWKZ^&%{{qKoj+mafd^Os)Uq*tF9s9yBa|c1(T3vJ`T4g&NVN@P zgKMVO8x)j*Zw!e}jOiBEB`AqFg^B?=2U7i)EhQBdcURZ=jj-B3c%G=d+w9qKHF}HF zT41&Y!V(Y)%$ZeK^pX4WOj;HajEk zZ*KK|Fem`}HLyZ=9N(`%Z2u$m(EqML3o}u(w~lC1XG#-7c4QVM>0U#WN&BZ1Ihs4 z+=|dTfYb&P16o3G<@xy`M8mLkb#%I7O=hvc+{tJ}PwSx#&++jjUVH3&P}REU z{P=Ks4mj08o|?V>eZXb31dGWAG8agIz?UE5oH7zN>&5hEhHRw!nA{kMvR|rFlo@E= zr?|V~vZR>x5ou}NasqXx{KjPJrtIg;WJZe*!o_)0H3+Viir(-i)T3`pJvKdGrVk-o z`;bT+O^Z1eOD2jmx}rDy;ln2QhbQ6+?q?=bJlQ09K0Fl?L@eetAJsF?`*mIRYM! zx4P2ESH+v}cs(kmn?j9aD54iF-{e@}KI_KAbult|bbPQCS5wUOXMCGWQS9?V&DU#! zO(HzX`Kns+LCB+w{fIv4LUlqZb{Ki%b|V!~OK8)(r>DMrDF!(%bV2*@80Ga|w(1OA z`)wUZSS8l+sz#YtZ_E0~ipV z`+Q(GiP2Ah`5oMSPC!)*jc1lv$d(k&elP$0_4Z!O@fLmziC)6NV~CL4i2zKx)!!mQ zf+h(ZMMOlvCq_cdBdwpfml6>1)1#jNbucP&>sJ4G-P+wt#vaWy#=Yj0SQ4^|xvA+3 zi|&<2KN^1Y2=;F)+<@TTK)_)J6c!(FsXsM4fH^_Un+`K|9W*v^CSTp(OClK>jB~~G z`SGO_EQ~SZlvp2&o7mfPNoY3thwo8=PSodF)Zp^9)P>vh4}Y$xNy+oaC#Qs!h~f14 z8O4|nEe7&8Fz3cKZU-%PFaaC_iaSWGscC7y?tx|#fZNo&6u1{EjwbbRZ7w|J_WOVu z)IFZMAW2C@1

PN4N`;lb=6-f~7lP4TF-DW>Dn%ye=I7UNvb~!3liq`Wa*W^-EIP zV#Izn(0iDi^n@+}I8`1i^P4G+2pTsTU(wohm50tmItTxa8z5HPm!oM)KUqvPIX*2y zz+(BKh{r|`6tv(*FC{N_h3@iYFv~yM+|Ot8d)Ty8t^_zYl;f*)O<;-y#jgYLJ6`CW zKy#S*dtA_kPA6T}0_=r3HE*#rXkS1U0IjyfzU=Qe=u*MT$ur`7tv!hJna@3B;Mjy`_J2{nEB9n(74Y+a^Dj9+iYgY++-cOgr=8gd0yviZvo&C0=V z2M-!{4@LeGUjBf3X^}6sgR?W?m@7%1`80`wT3ieuW(e1o;f+vCLV+cALLWz1`txcuM?-U3dB`jJ>-Vap78LaI_f_<2G!Kucp^(|=S<{DW>*p3{;vFE~ zL&AFTideS_HCv4H^K(J}k*|Z_C^{ONY@3AifCMZwr$XA}zkRV|UB}fEDW4!w zaMYaO%f#2Y(z~;{P!&Xki5SB}g-1qC5%1X3nYBesmo;)Wq>hGJQU5h#OD zkt&Ux4l@Ht88Cr9idjhffmyHyZ0$;U?XUE2-n{6jc*(6}Yg-6`+{AE)(gKp1M~}(@ z(Q1H;9a~iV4XU{w^WIouHBultX=sc9$O~2K1}v_JA}{+E;Z0g4TY{jMvv1K6mmQDZ zBmNlnDquw95pt(J7&;uB-W*28#k z=o6qN+(~84p0MrkT=H|hkqQ-4CO!0pTbECn`%=L<4?v0M*nPf+ve(-kbX)lk3>$5oO$}QnDy%hv`|%R$B@`iKLf< zE3z{M-Nu6rL^*i|Bkb#=8DD>SJ+>{b9AM(9((0h4dSXFy1DlGH68uKGZ0Iid;5Jy+ zf4uRONQ!-?&b82#Qbpp=PiSlcu1+QkM*y5)2Gw?^;akf4J|-Vx{zZOzP> z%r-3*GewwSI-4qwSW+Gni@v={$%pqgVfg-1H?FrqTP3lP8m46yFhI_ z25no?%a=ezf+`2#3V`r{gbv*~SS8?GP+NNd_!*3Y*!b~dDVw0K1iBA{-&`ENP4ZKu z-t;?eC@28r{pbhyPm_ei)p)U>p~JrMsrK|>I`!WH!vN5fZEkMD!ERz=qM;Ex@(l)c zz!S=dgO1^;Uj-De(51s*Ks%lXuS|g7p@jnFbG8A0SiCp}oF~3?u&-aFqyT^OG&h^p z^$0WRoB)Il+%^x`Z#gf$hsZG7=mu5S$F=cU=9=J)+CV^uXz$pjTSU%+) zI2}(tJ^|LZwFRg*G!yJcV2jIU4S9$)y?qPtRsW@+>30F!6nELdl@GcRy_S{G--(J! z2M~|60}#Jil{X;AhxZNbqf>P0T@v)mwX{I@2cAn5n5`RoVD1Z&{B0veKn;)lPBusUFw>%{{u6MV`GYJA~;Ev!@j!O+7>gd zRZUt*-bP}S*-0HHBws(+=iqR9r4l(2z~(n{p8H11TR=xk%u7E1Sob(?m0BezzZIp$il;<8VLXo zy^2zAoP1ZXgY?scBmL{-7+v&Ai1ywn6hv437~DEnG@^3 zU`PPqeY#ZQK`_^4Yfp*@4e;3M1Wd3g+1T4jON60|bS9Iy&pv>=4G?pi0@^D$AyEYg z6!L`0$)1#?U%R^jQVcMfflgU14#;vlSuo@h1S2DFU?7_>mW_?guOBlsAu=9;>c`x` zgoGP?$BV)S`*Y~{l@zRkx#5k}rM_dRLLKIspq-$Gf=0;8yH@$v+i~Mg?RpP4n$xcz zf4wCH8WLVgm^}jSM=td8<}5P3KLiW^DGsWRr@MH z+P%$97{g$>+6<5_U11QlpzLU)w&@h#qk@0lTf77cGyvnSI7FF8Q6a9h)o7;_b zb?=1(T?Dr7m8Q6adRTBi7JZapoCXMP14f%*KfDcCOv799&ovDU4y#HZM>w7bBFtd( z1Z1ElWKhGYE9#`NeXBFp{{hPeRu6~)MN$Xu@v`-8!z({X=`cV;YIZ6~y?YmUZ@$8) z>{|_4DDcWS{BxvqgEkUcHcu#sHw)5X)4*UFPPq1V%(>J0p`}z1^#Fik2u#omhpa_;1gZvT&o(}md}6W#$~9FxwoRv1{9&0K!uya%IP;eef3cWc_;JM~O1 ztE`NzdBTA9Xq-JQiXon7sWp|`!p?=gn(a^pU6*msEfl$|THC@VoU!|^r^9feau!Iv zTR-yyD1@`YZ;Ffizqvqz+80cXKwHNhpy5+P0pmY^zn+6*Ml1nFPaJ7Th=_DcOu;Fl zGQAMh38jGfsmudNt49JIenMLZ^!Br@uvgwt1~8MLXa0iD_Sz3?u{BmR=a`Rp*5e+jM(vt5`^k%%IR zxX`#8_U2Yu)9iSREX%ph0jQU`2GqgtILZ4~HzF)Pd;Yl{X5}35jsY)@H;{n8Y(dQ! zx1J9yIp+?+Znb9W&bjo6?F}OxyVuQqTs>E(SB#I7-0d(Q9{Qi)h_AM8?BCky68~~F zf3*3KYCo%=knWaR_EAEO&PMEFL;g=>_P~W~V=nXBWkvSg`HLNUALAVBfx$l)esTWo ztx(23e+jNWjw%zb%PBbz8X~Uo6tPuFsA`Q?aEhPoMkW#%fY^Hf3W4#mdUCCX*Mo*! zb_O6sZ)PS96L9tcesxsqaT0JdA${{I{ErV?Mc*QDHGOtSC9VQAvb$Qt9=wV5 z5<12Qvm-D1Xcc|;f~RcOnPVgTwOz5L0uj6Y7;F5zSjX;DRFSwLa!u0e<3%_ zDh5I>&+e@&DhDr?b1k5(`)D}!_w+C}(Dc2_*{7}r(?-DLYs-``yZo)WXCMe$K>-@4 z-aI$=;e%?ES)riy3r8OCclRlKQ&0d<5A^Yxi_y_CjKKKcFZ|-12yIPHa_1YV4G*rF zai$Oc^P_=+m2=uy!k&a_c5mNO0)G7zA+Zge&9DxS%`WfX+vPG~aRiqAQP}W>J~x$k zDc?-5XR}J8iJG$PeS8`K=pJ0W4D3=Ho6j5k4Ctt}%T!e0fCG+^4aNA`aqba4=KMbH z41T4{OG`jgfc{|A%jiHv3y=V>Q7)OQd;2juo8F+{Ns6D|4JMYtMBQ>LubjGqbCbz5 z@ec9psD12A9^fN57};VzKTLjdb3;?zOF5O`9s)F7BdN)0x-mzce~XD7t$_ z0EBULnnKRhyThOmYoM*9Z%%GJ|Lmx|Byz?Dc>EFXK$Gut*X&}J_yu>LgRj+LUw??N z;&Lu}Wj7~WDf?KK^Ajmn$<)V{-sh;0c>Tv#T+p&t_VTc6>Riko=7MuFSZ+R!{N`kK z*;u;0Qov~3^Bj^vMoTNDzcc0B7L9dsP5}o`_Ciz-U4jI0sXarV*>e}8KR*U{OTFi}T@vc6l1Wfl<7p#8D2(RDySN}1$>6lEsSejDUq zMZXw)kfKNg;*&CTx#j@PJ@jdU@<#p92a2^3Ruek!N(s@8!&re*2?_thi6`HFL~Sa3 z&Q+ld!9ZwYpk&lmkdsECD_ZS|j?7NU7P|4tXdaE`H9K>jQ&dm-&AW-JPp0yEZRFh(UwrMD+JF6R+4Z;)vuz2D#U)UA)$wiMF$n z*cjKanT8Y3ig{IC+^LksVF>J5s_5)7_@+5DF*#qd+g(xiksEW`{MBa$nBEFMPY5DN z+SpvD(A74J`>b<^mnKunKi{8yh1N1eR-pORKNN?cE%jxtD=@Diy~z@lNjY{FF^-78 z(*M1LvLQ7oX35Rz{7ShpPDZ?+az$^WN2&5BIMKwJ$#$F>9e9>QyfxROEt@}A;Iyf0 zA@e_s6FfP)XR#(KnO8C~XnO+gdgW-Dh4(V7r3S2p@7ZMN(L`;OeWVe44i?WZ*y_X< zNy!hZH~7 zA`CjuHFMnEnNR33ImrHfa0r->jpmnPVY&&HS?tY z6?#fWe?88;CnM!O10GzY`4Hpl&%)iDS!mtx_6jfKN~gL9yu*6R7j*<$j^NAYLv!FA)A5Uyf&A!rOyA~ z^)YX@$=1$2lEX0_b2q(@)iC|qd#hbk2@V6ANdH6ex40atgbsO=iOCh6hEQgrz@_}n zp5m&pmuD|XocO7FDWjWqSbK#Gs-%CUHr!Injl3<-vTX8AQ<4e=zG991ovQhSklSoo z;Uwy{LVT*g+5CH}2p`5cRlxHr()5EE@q`sbgd8li-o4Sy?mQRAFNI{15t^9nu`9S| zspYJarI^6^R85Ze4%QgmzqZ@b66(s=NT~*T3FXJ zEL+(;OXj4|@QAbJcg2u%G-xDG`H;WV{(gN+ofP!TY-TDb-T2$M2flV)vQe{&H==1p zDv&9Us#Ye;QcfCv&)b`#-Bu@kR-IpFZ1?l*nT>q5^{r<{H&!TbtD>kFVsVs%i+&EqayAnRTP?S!A>UIa|jMO5MY=Cw#PH0M(I&PZ*M%@yk{!F{{CDXLSK(5d`oWB+|K{-$g*;}BNq zo8}ICif@b7zO2RHEG@2{iz8AOEUFDJp(Z!Avz?eEFT;MxZ$U$O*V>}_p|0QABl8hX z&_0agAbC*gHo>eG6VTwmvK?s2-^Nkx%;C2XPBeNCdaL=*V$}K@`yHYf6Q%;_ai0oF z>8_vGwXiLA7(AbZu`x>dmAl zQg7v<8N2x3PQXLuF%G}dm>rt83|B|Vk>h!$mWP%^&npC(>Q_FvmTNIwz>a*~Q95Cv zMv8n+r0aV2qQvh!yX`~xz@)ItjKVc6g1ex=wD_0gW66qSPnKjA^6>M;X=&7VTG)po z%0-dA#Z|tf|NCT|s$7y0Y27n7+05LoO8=bzkJ&Qe+YitdfKNtV)eIX_8d}SLB)Cte z_X?e9&rwAE-{tb4^4N&djciJD!inmc@jG!VAIuc2UFL@zf>RFemhzf)pw-0v&ev(G*4nGb0&l8j91p8AY$ZNKvxs=-qgU!eOYB zRhO-NtICYF)GW;HoSg>^jw&UF$?J%;v)4Ps=GuLKLYhpCK76YEsMv$A)F7M>rC?E` zQbpPGeQeZPJWF48CNmBz^|=u_CJM(i5BDh#;=hY0WkC~h;7LUo%#MF{o5GxV(-~V} z!`mr;VO;J*_DOb52P;X3W^0o2_dR#dls}=20w|<3DMq@)*)uPEN`eYDAUsvlYD)MWqV@uR`KCn#7JY^(&I(X^q z7PQJqoq{p8rm~yLqNvgqr+r}CVc(%!(WHLqvZv^zd; z``_(rv8rauyBIX~*s&F z9r?XLsPcM1Z@FB7k&$Sh)BY!|d2#>7ziFebrxI>98X}}y&zJHr9wQZ2yaY=UDcueg zwFRq|GTnxIO+qh?yQv`k;SwTLAVQjAI-Ac|mJOX{B0}=7J}yUl+0Zg(Z$wyiUb4}y z)INOGL?2Gn|Au^fY_wKN(&|NKZGPv1dvJyPbvZSBpQf`=SR^YPqkVI+smxmUJu40q zUPrhMNvB7Dw+-FQ^1yv_@vLQ`YkIscVXj#5uN2+nb*c$L3k_&z7C-rFhv@ zccgd9OsEW3XW)HV<(i^ww%5<&jZL(L96ND`!rfF-tgQU&Yf-P`kcFPsWk3FV>h)|4 zgnGf~)GM-a7j95$2oxyb7_5K!{aH8MTx;jOjBuI&<8DcD6=9+>N5sbq`)~fc><4k` zxyp9=6?E&b99Z1V#3j;4i+g!+_1cg_%EIYFf`zKQMK5jK0%#d()}kef@FY((_rLzX zPpihLM@iL7yGaFeMi)9CSj$<_I)?Za^v z6vxh?f|Xwz*j&C#qs9FDSFwv^Wq1U?bRdxwB~x;%rNGqpci-~kn(BMVaO&+yLM7)% zh=Dh#eMqT230f{dx}fd)H`27sY*t{S@-@gGyA4?-e!h@(Pj@MBl3qH|vV-WIxoCg* zazwZd`}2E=mo&&YzAVm|-n?EKZ$VJq*Gny}SimLz3kG8Zc; z$g$w75WADJU5V(FA1dpN)faP=5txd^(s3*vvADz%gUrLzQ~ZY+rwt6Fzqe7ArYgmr zfx*I%+fX|BMXfz?x81Inw>Z0i2&HF%eJ*<-FE09-gHif5&adGi=<52O(fLYI`y{6G z?q})gy<7LuyonKR*y|O#y934VCo+>csL|2Agp%52l5a)7!3MZr3kqglA{}f_VRvQjGzvtNt?&R8NtuHa3 zLd`FED0j=Rip5cvFW1 z$wRTH#ZpIqaRf2r%G@T!u=sB=nL()&qWrqi6~eBjjF%gK%1{x3E*a=C(My8g;gIK` zOqDzw)9=cm&YflrZR?t&5=NeFp6`@UA)(mIL*C3g}uq^c2i6;*!cS=8x=rHFj z<8%4}U%pSkIt-(H8 z*4@dD&#rP^N$$QVlb+z!*i|3xIn6KDzpkAN`dX$If=ja)-jYg>%>X_u&{5W1&-(i| z5&O<+s5O#r_*3hd_Y$p#c*%DXOdZNB87y4h>38erZZAa~wB6sLc|b`?sk<(%i*xq3I&^VwnxBRyuBy9o-L?6jbfx-j$2jPw3Wk*v z*pjG5Ln(gBoF0Z;TGeHPOIk9rq{4#+=sVW;D45 z-IrGqs-guhc{+=gRBKQEUN!3XWm$lbUB$|m4}j*%-v^=klr8(Y{CUEK+hODO zu}Y9Pkqi2l5quPJWkInqe7w)B#>-#e>8xgZk?pbTz-(FN6iW!&iXMN&oP*}lIjsvxFK+-npZi@1_7-1*yq=wkYD2NP`Et zt1jeq1T*4Emw%Sht|=S4+J2w8m|C>ou=`t>s2M|U4VIm0Y4Oy9SXuq4EB@QjxM$nx z)pIpqg*1dtP`If}LBXcaY0Nv(c{#Tpt=?ACW3Ksq%4b1a${vpm5Tn@}>Wie8E9lix z>=qO38hX+GMIG$o|Ez>`J`^+RHzX5`Y|l3bto4PcGNYX?yrVYOT;}gwoNSAfvr;J* zSc{RZdo&Hg_Wv$Eili4w%$~nD^-HLpOikowYUPJq@iNoTN)ZeY)LUH%KpihB;l z&TiO{DWR5!N^%{HMDFXK9SwX~k!7{yDR{9&=z%rrwNTxvV9X8JZ|8`o)`s z(ISsok+F5hU(+vz)eP6A{Rh!yQ`rC9FT#ZOl)Rn6ycWM#;}z-R`RA@0DZ5iNOB_5M zhPdbkOF|w}KR>2NkAxGssl$onD49gGzSFG!3u6e=qJr5}n~kPOoN&=;)PqV_tDZR& z|9Vu+mD5p?EK0(I8<%$@44vv5#D;^RUr=Ow7J-D>WJ#qQCb{vFd+hEzh?Q6hg*oC& z8mLC{J=ZG!z9Tz&FYb9igLe!2wdZ9Y?JtZm{P&!QO}hIS^PPgR^>2mBbA?54+BE1P zb2<`Kr8M7B>$9~xdEMRpVeK;NX@|k}=Z>z`S;(?8jDwIhEmw10WG0jz_uEj%edBjn zFXB1FUWYFAlq+dh{-!a6OiM7I_cWDC}dT`W-~P>o<)|MP%#xfDf%Zoimga42@w50}Si zq`JnvL?DMW%k$bNVluyxogb+6kuzr4t8`6UMxh0#uCl83lia`i5dpce>gVSHMiCB) zoZT3r0xxuw!%R_YsImLTbV=1qmA}g!P9VY#Hcj2ZOvn0n3nJ!a>EehPNv6ol@G#<; zw?4@T7blD1NcO+uM^Um767XmIND;M0V`+9)tVNa<15SRJ-S@1wufX>y641jrVH55A& z`n`oK{s>o>tvN0hO(@w&!Gq+Y(pjx9&&hCRG{Y~ z;`Z!i#jc$kQ%2+gQ#jwu{d~rHk(6=egptW5{jOmwD&5$##n6(fhFY&s-O$41SRt<$ zOG#J$p4`)S`3aE}8$&p8Y;N5!8A znc6p9|7UgBqM1KXC%QP+yE|6a_p;-XGIXbsxj1tgAIS(n=z4Sp)V;v*$}0ZzL=Z_m%%uOZRTytm|1-8?zEQqzMWNm4<6mSa6p303F7 zd8R{5SmQ|+lSW;cGjgMxG6Qp$aFLAxU0!6fO~8MX+Q`6$HdHe?*PuGfdhvmQjbzx) zf#_LvaSDRPk$iR!jwy>(-~OR%$zYp@RUq{PN`uT-Ch1mnJ=@8n2Fnk7pV6y!BFz$d zkYP3N=Jul*Kh!52$pT6NK0IRhgD9UX2-*ttCvPW@0J zP?o{w~SP%ySlkGm!z}~xyT6tc(vxOx4tBoe9-VXBi zgoVY#EH>74y@CNjnk9wrHD8oGjQDaSP!WgbJhup_x)c)7Q>hXXE26RaTPbF^R^nf= z`N=p`lCYgGC}}l3XYwH`;qjrvLYIG-yKn#;cH^eJi2^4j`rk(s%gc%$gIuA z_|&_vCarJo54>Ufa3U?NegQ!=|J%1`>uT7K4u#-kl;iNksDr(uFb!A#$Nl#%g66() z{{KEAq-UE;#)Nun8@vl@b=C!py|)cP_2)? zmPvc|aJz2?oHr-I@;(`R+cpui&?Ylv_RKO$&v?RV_oqkgT5$Qx%EB3&h}D+@a_7yL z?uh>TfY8zIk&m$IFjD#cR1cJ0o&RvJNtIX}Sx0MfWn`mpIV``zomGpw-gk1xy(Y*Y zQ(s&gs+L2!w&9Er3Gcy>Dq6ia=1Uw>O&?S1jww*H}&``cT+ z_>(u{-^=~)du;>H;eG4eAlE|%xB);IeCul`SXOY~Nh2@BA zOWidY(IeO^i5Rnyll}KOeJ4Gi^Jt88ss83Wmhp6s`WF>fF_Gt7WSfd8pCBlc3V5;j zV&^8wB42RiUcdFEH}>rDawe9%ZK{7aHDj8OPkA0CsU663kJ*auZFD2=gXQ(nD_1Hz zRSC~7(7cu{+_f`e=5owB7lWdXwzs=5(KOkY3wyiApXN0?9zA9#qYc6!?gb&vKd+sW z4$IW&n*z1F>zy0->+*+XS5PelDbK&q(Q&0J$7@_j+`bs{`@glNC-+jaP4mZU$7?>&6VWu=k*TepT%ixVu^o|Sa! ze7K$CnNwcDm2%pcUe33RZpB!vYeDceQYJ>eLYXlQ~gXwUfH zO2xg02<-Kues7>(tc)YA!-tpgecR$HqH}v-Qd3lC%aE=-COr{nU#R3hs&i*bYXTl$ZGdSjObnsNO5RBO|a ztj`%N9CKZr!zPK;FML40h^K#IVSm#7klititO%)>#fJUw^CYT}qI{CG`8s=M@^Wp) zQ22@=l1Na@@&(S5%yko`L;;KO*-ecV(0~2=0?Y$=@4e)cUNA_Jx@jOigCm_?I80_* ze{9}L)h8<3WwQQQ&*CS|owI)}%ZC-%>sF;#f3qkr|6!-K$9t!pfU;YU*il-)NYA(c zW>$S^6BE1F{}&VVO!1#|DDQTXf1jPz)%}A1WXZ)y9RCU55)P%jPEK!HP5Cvc|91<+ zl)TCdT*T`M)gL0s1#CDpNh&`1n1oZT`E)op5L_0`FKh(4=s&k0oLAOaf9d!7Ow6+{ z(&s_3UNQ!U!kdxzf`N70;2CQrWj*Jqd!6=3J)X$n45VlphBXUJu>u#}BLfFOkdmUJg3X1>lFJk+D>z4jfbp3%-r(&d^FGxY^ zes%s>tW}zLGddfkCHw#WsfoPVb-|UWA2t)yR1Wwf?!Wq^OrvmPbi(~`YsI+_Z_smSHO$6|7FTNjs+f;s)J?DQ5mm}p$K`XkTEHa6( zMQ}iql{UGasa-|KGcC;|-A3F~qZ7C>tQWUElu8Ks%2^yHX%lb_;ILba;1?)1EKs^R5x2>Q&x;VYv;0rs0jA^+R6 zw#fx$OToWdBHO*M-?`30Ah)x^9doaR5-(pY)46G3?iMwL^x5uEHbW%0J!i0YueZp1 zKYTE4mK}Nxwg@BNxo`nR9mcx0>t3SB|D8Nz!kh>-$~PS@vJ1&=lEHmcHw}LIB;U4t zq&d)b<01{N8BJp&?*IGeIGri)^mUhUVo!eB{ZJ}+S?E#NsPY{{fRtQ_RAUiC_;(BC z{{m~#MJ439dj&pWFVi`j-9-1MZntjvv?zK}ua?sfK#FD67M#MNEQ%lJFK=6YKj`!x z&HX2u{Ui|JNFxwl{@2zlP!yR~$&i_*Si6$ zru}B2J%^JYcsvqrC*Fz&YmIxKc1!9v^aFL|khNGoCZw0Q^!(nR~Qi-5H$mz9a%Nrb6bzood-m_Ffm7n z5UN^2w1i(Gwzjr_$m(+AGH$@qbSM$yzO1$7CN1JM_JGs7-*S8u4t9sD*PC_Nm;82` z4_|J0Hy<4M)qg5YCUTN>5(!`bo#nYa@$g&sL(_)^&rA0`B*?CF%1x+xJ-2+X`Z0cu zup&_H-vdDV4p<{mH1BtSHG!;_7F^C@OAw`5k{)lTpmJ=De-wYG&)nW)36c=>y9FTj zgM%w~qVh<)kIZ|AR7!kFORd2Ac*Q%$HlN-!+IAIde0k@0xbBx1hkG(Uetg_~Qj`AY zsPxbEzC&_Io@J0~ZXFNDd~ILv_hujI&c3)p_)gd(3jCw+pEI~BYIF~idc7mk>iD}R zqqR1Fj;Q#3WuiM(&MJ>+YQ^*Au;Gq92BVS($wvlmIIU~v6Jz`>G_{2ArN?*WnL)7q z>VbZ(AqX5V^5VnqBy1}43vLLx94pO9$hB$jDSP8zvkS~RIoN2b-T7hiTjgYLu4MI4 zrn{51Ww+gW_P8TpO=a*df#v!OA~feS#0L@EFdG9JW#t7;3IDt+|Lm2bJWvbxZH1Yf zPU9wcr>aF(@Ca)*aMG2o^=dC8F=F$vgzk^03rO<#uR90uu=*DN&J}uE*A_h=)rz{* zIgu@WIPLhU-eT|8A4j@fL!FWS(p!6v``?J~mC`kjIi6=QXTU%cMRV0JU+ryv8(kk) z^7Y!4V`-yxBLjtzpu$4G1&k>(FO}h>G(MeRf?rqz5&uT33a6&c0G=Zd0oG=+g=VhQ zMGDa)=0$hy^^p1n1c+Jakuj(-q>wsy7_lah#~` z1;rH-@MsQH3sN^KNbBg_IMMCXi23lA@}J-$1)A8W5{H!%?=rY^9^BXY_`9R5Lb~k- z!@la{0Qr7rK0dHir}P8kU{vbba;9tM2626>j#?+z1y&Q>8u@fIb^$hX8#NU81!)feZ{&b3zy;^E=KIY%0 zuK4hCd&qLS-?6*zvb*?hzRKgh`Z=TZ83uH;YgTFL2KW(q!01h26uvZL3HH$>RBTP7 zPeOHD=J6h)UWwzj_P7KPwKho0F@R;5CdY+zMvTpniaZ(d$3K5AEC}40c6_TQfUkUA zQ|soVrjxlp3mSb#;>1!dyRvmFO&;QhZIf%$W)^cM>zDN}PS~}e5oIoJiUxVt9>|32 z-O-dfJ=Hi{VWK4nB7JvZUS1DK*}zHh;^iA}ro2IN@%=XJQ_xK9uNIcxN2;4(F&bnJ z+|2GfQVVV{K`ww6?9d}BlMTFaz^NDk!Uo}#MZ9EJ9OyY_T{YGaq0~+)!=LgyvzwLhDhzayR=nGbDI@Fm#$-?Lj9{CP{&d+>c527W+Q*H3S6CIW`| z&r#HI{z?XY{)tEiTU>I@+>vjfx&U?GqbhfZuVYWK>3mcNj-IIn`ylJl-ISS2AwrYw zK5D@)#jy}#gU+o1Z7t#5ty07TBl_&wzZOBWQ z(3@f>?tXjjuk=|PKaTe9SjwKVhKU$qv}D#0Y;l8xDqxR;4rX@N*bpeer}mZbR(?LF zLx5S^0K3ig+^~%q|vSx1{y1np#poEww8g8a#jQoBZh?H}+g75EB}6xrElC zq;u)JV6^ax^6kW_)nMz|#fzQ>zNxw=L<7oCqAV-*Xcd~k=MX#tVeTF$`MG)U6o?Yr zMlK(L_7g_%K{IFb@fcuSl{NXHK z_XLMrICOYc>mu(c;`H6#bnAb~icerGERdoOY@5 z4Y|%!&*Q1XGVKO1PAhE0Lr2#(KH8r+IXsfMEbd8to451aZGrb6vqx$(cD4n7uYP>F zQC9-<3-$g^KLXv@G>B~2P%wIVmC93u7A%6-Ha5lumBnR!z1h(q<^&C8>nE^V)EVD} ziR8Ep;H7t(7{GLl#@I#{boB1x>5&ZE9i%uGda9{C0nU-<&55`}h5~&U3kRNm*P&tV zRm9N4d8WnSk-O|kdF!x=XNMS}dg`ZRc(A$2YxxQEW^X0Ja`lH&Pgb`+wp{2W%ky=! zd!TrLk!n_qDg8SN<0`6O#QtsW}RuYV} zY8cE2{CJ@|Z-N|9Yu1D;I#mMQpdf=|VXzcpfE-jU(N#aXLq`1em;H)^+R6jTla4=< zexbOV&~?ZZ)6J-(enQ2&Y_$g0wM5mbgl78Gz9 zzf-@qv>*cM5u5FoRKP;(oO84}{{fi1M#CA`9k>lnm7^aYcN1Y^beT@hWckW7UD5Y< zzt0gN>$9!)UR7)`cJFOTn1N|{e!=RYFaL{nS}dJv zNld%X+on_EvsiuFGJEK=r@=+z@7gXIjVq6U_7U8{D~e#w^0LF=!3?{Z-Ab{J!%>Ub zx1n>Ll)s+yOD&X2?45_|L678MV{A{hB7j&Yr?h^Y4a_*>;a^fR&gFWoEq9U8Sb zeE};X!AnDN{} zCSbWCBf}K5TL_rr;Ug;lCpku^S2Q4BKC?Wjzq?Dth+5oZt$o($CWQwblA#jk96ctf z-O2pDt&hgXOk~VCMAsuki>uK%NbNtmUbg*% zXsKQYV;z&%;&Wqn?lx5KKE9ZUCt7kjG<)wJ86 z(b?Qx)29OZoecLky}dHM>x!0wd&f;uCgV@hPxJNPT_&{QLe;$w8~=}{vjD2P`@a6A zk&p}04T7R{cSuX4q;yL+(jeWS(h?6Kjii8dNlB@Iw1AX^gh)!fo8N!lJL8PQVDOD| z_E~%F^~oB$oh8v1V=FMl6dSAc)G%JMXnfPWChGn+f#ijYi;r0D?JIWYr6qU6&zzq&_m+HH1fG;o zire=3Z=3TgZk}soO1TrK@xzpT^veReOP1kLQM=kidO6MNpoa+f3p6y70k(&Ladkv6 z5JDHVft|Z{c&1dy!^PD}4k`YS2HSS@-Jr@z_ZD1bfK>DZmS|)*_MTj3qC~`TXAN2% zl&6>}?dx~lGIycJL%>pp<>)_f*y;c*3TsHLe){x|{A3(A^(49BHL5{>V*0Cbh1UxP zJQjE3R5_h{i83GYJ|%L)K}HaDD-3L{4|m882;Csusk>UdivN$H_t)5?^Um0W{Wc-{p#X@^>{Hs zE72qwwYR>md0Vil)e(R=B@Plqcb_{srQS99&&e?Eoo%LA@z|OhWLae$!kn<%Xn%h{ z3O&H9h@xGDDr}!Yj!Ws&;&zB`*lrGlJZtkBMfitSMS!qd%z}e?ho@;jz~o2jolmC5 zabwSx5DA5h^|}}c4M(03+o%ebE~!rqzdc0a-9P>3))e>tKcNj+_8NYl`Mw%%B0zAt z{fY1UK{ILIxhZ}&`{HU@`TB5=?RbH~(t@bltF2K!hSTJ8E(IrvLr{Q90#)@qzTmq3 zH^VmJ{(rsXs@V2%653ZCwx_K z%~{5o_pNH(u*q6P{;UarvTKPi=3TLdwa*y_rI_9f0bSlyy5j6;&+yUXwW` zV;Ep3AR{bX8pYb=*}yc0%$p~rmipgc8)xc%4)3mMl~|r7(Ju-7bJ6))2eweguzd_r zQtuS>3S#13+KP5GGYsq~#b#-O{;Xe6_+x=) zX40%)jz7g6=Mib*&2sdNIHs@1HLq+OgUqYc`}pGJ$0oMO3b^|B*IK;T`I@QJv)2S8 zAw8mY*w55-9gjS+PZ1IzAWLt;v#qY~={h|^O2z`4VXDUT3{xwzuXCrmAh02AX*}R!kFz<}u zsu;*?R9o=ERsBy{k)0vz_t{3KKYAcLy zg9kLw{L(OU88;G2n>vc96a!LBF0&z&3c^CtUk?=DjJGx}c)c|vhd91eD+nktaB5=C z9kb!dfWIHIyg2?~BxDIUuNifS@k>z0^u6RpN>3gMCQ`$Lm_*r*Ot^n9X16@;FftM+ z^l1a~XUyRcN7eaZSIR*(!aOMm85_mTw9{>@vYKXTzr1gXF0?LanX za8H7Jq6s?gYBRCJH-`Q^biWX(dPlpFi6-}ipp3&DQ=X7lShS7sp4SkeTNg74&b#zL zgm(+5ZL*AniT!|=Ul9^oYbq<#tJUR51B?ObAu8+4W9*wojH|xP z3eC5W%>8>~T7kX-?oQpK$%cAYq*S=3b?UoiG8(A3Y)*^Q+VQ{4>L_0ruKh<}LGe|{ z{+2!6e9p%j=48AF{_G~wQfT-Cbn z`MbMOV>xs6*-@^K=*o4IyHhJ@YY(e_I4iD32?nI528-p~O%6@#;jga+H{q}5CTLIr z(RFPO*4SVnCe%sMbnTqlI%PfzPz3$=>J=eH2)eEtWJw1?TmoSHAPUKqT1ASwziVfX zZ^U21nOvSH1D^8+N0S2#-@>f?tt{5|4e6thz7LGL{)`M%kw``(H}zsAEUeh#KIOBR zy>qHcYqRwu9@VM!{y}&6N;7Cb!EAKZ*&AY$Fv#{uA+e z&om?z68%`bg06I|z{-@S;*^|*CfnU~2qIXoUlREL2fTag+kQFs51mxUsr$e3;oH<` z68G|@ah?2Lb?GQ8tEEnI<@hlpcbj1fg`vnGLZm(YVblHon8=8j`~6DHbL9<7dNcON z&8SH;%r?q?=jOvfpPN2-a`#DLqo6tuL@*B`7iTSZH?jAe8a?wI{ja+?sa&wVRPc5~wTnP%Q*=eERe$-#E{}+L!GVe~$_)k>j^GZ^~ zIf1Rejs34m)mPAxma*cc(HYd%@5W1peSqh9cUCw%6pf{9T_l0<7hbJY|9JV`A-;>? zOt)=Hp}C*kBnw9_A;!|!P3ebTg+Ssz4=7&&oEH5vg zFPsi2NZgFzL*~LykM(qup@$^E>gj&~nx)&!Ve6C9RUtJ<+*`Guh)<%3?)i(Ch8p%I zP3W3~VTuY9v2=D7KKMs{%sR;5+Ky$rVqGu&Y>d=ikt%+ z3hs*5y@+2}jlGQmnVCfXS%%C|QdO);aD+Lq#oaPdQRg#__*Q^6>p|AKm4;t8DehMk z^rKsu(Wfk6b%3zx-OkG`A7d`+S7Sf3S}Ji7kf8s^YWYu8CdfOLx{#g_DuoX^SVDML z9*eh)i%uFwrAkO*?F_pvgbx^WTvT0ruJZp|K<5ba{dRV*SDu5ITz7WfP8ZutEC;wc zs1jVW90X!L8F5?r&M3G&jz4Zs*GcIA$`5nULJb4eQ`5E0;%*_-N(p!*PcWvAw+vo! zOwkS>*d&OWc3qa{u;QSYzZ%iN2=1)KV`!`kBV!}KgSh%jw;Z~kQF0~JR;Oa-uUv4J z^W&G%TgLZ<3tGZhn4Klu1ER7k=Afu0>@|5cEeSW|v#j|yBxPXdP)v=z_3l+GITR+1nlvUsv_(f1kzb_<@P65+U^6#-gZ zd-;}u-hKH?K5h+Fc@S<^FWt`GIyG-DN76YtIK;^pApWz>j03c5_1-@~_8p2DO;K3< zuZ&+UtHsIznt0ot9?O^EHv*9BVaix%j_&|M7D3vvS%WoBpBA*SN6~ zf_@tYxz4=ikH@>vzt?rT@v6pFT5I88%2bFP3{~VX^RrqY;<#n3-V*gW(tHQ+f?vgX zFI7E86Y2l0Q7KQlIMTxQe5AEv&blWon+#JIzhaEN;C`L-0&^^djCPucNxeOhS~z6m zvs?Y)dz9D`_Mz@lERae`^@4PD$&7EYS=&H4+J@UV9#?Z-hAfe1_=BKjBPhKkN;>^z zf8V8=J<9M@{c2U6Pu2eUbJI98{oJxLw*>br>NZ0T$Ql7E`=}2eWp6|2M=3yj7LRus z7G2dzown~aGrE{|_}GvA{6Q;SDJU&f`7@i6_4;sbb2-bR1+@TGXDY+P(ZJ!OhWLb5 z=qxjbiGirjo$%qT&(ew(j@*}MbLIw=!_&3(gLBot@R`FZgc}!qm6xy2UOs(L-n=WK z#{CvR4c2%~)Q>r~%R@0Hz3;I{RCqB}5nv>?@h=o@u+{zp z01mKqAYbiaZb~CuoB6$t-}e>vaP_4E0ttGMQ+Lc0UQfEWh-QK$>434-UonBmC9E#u*u z|L+A*?tjS=OT~3(8iiYYfLYJ^2``~eeY>S^bu7XpDm`z0+PuwKxq{UxOl#Eoz59aR zP{95FJr#0u&6&J~j4r#v4HOCMVV%yz+lg1Te+$-GWi_+&*J3oI#Ik|;wd-_!%FdYc zeMl72Gact*@?AzD@nqfL3}!E4dh<7Ygc>Ww28*ts%-NoVJPNpO&~8+9cp0B+*Eew5 zo){awHP3xo!uA7Y8R`VgJp`00`nwE6e=R8iAAJ+X z^bOf1OxB&tkz_KO6B|~cDlOG@9N~VP*VP?;BcwIhguk@EH2K7M?0i1Jd$}<8GY1VZ zo-y3IkWh4eTb^Ouz+45}6z^I0R^{>j``_P-!ko&o#+R)qG;+0|vi>`Wwa03CZ(gbQ zq|Mu16tUEbR%>6{s=3I)gx#V1x6Cdl7MO??EIv?Dgn;?Wy???1wj+kH?dJ5?5c;-4 z>C*i2=BRn#J@1+YvD3LwbwiqrL8DXK?}jC*okc*C%m!|(fj8n*$FtL+= zXzE2>CB-VaA(1m40fB{068++d+ge;dd_E0UKDumU*2NEwJbMYoKi?2xq z@||sM0n1cYCSULs0)L+K%|e(xD4LM5!Q1fl2<6{9a~s*Q`rOl$e^tl$cP#@lc4IQj zKa!2F>2huuwJI1;FS2SCYNKZvaV^PqPP?;C=<)+~lEy2YwIoG|_TDC7$ z^;a`phm)H~^iB@ZVSSTSv&58KoFY}G&Y zabK*e=s;orZ!_kPQWl)R%P5;4f13E!Z-qLkMDbyB9g{yzQKIfy1 zhe#3g8kV=AhBX4{C&FK6Gbrc;dNePTrrZ~%2xyz!_jc`1zZ2F9+(Iz;PeqQGej7^r z6B!wkbAK*~Blb)_f1=@0IO~T~z0XmkO?_w4olh!ePl&_f#Nc_8Z93$ad>zYz2Obp~ zqgQ^u1>8oOLd^6-Q8%s_`-%R*%~5~f5N=v~hZ;w!Z63RaqU#P4lvxIZ>JVPn`*rj5 zQ>Gii;>q0X?7qw|2;4hj{Q&j*Z>5wALWJQ|uTCkP@*rcWMh}v5A*TryYDpRznw$+Y z>{_7u8BM{vX`6XdC%d(~LmiU|LF6ZpheHMtzL^&Ft-RAROnSE%3BLY$z<-wx1paNT zUNOjayn#PJ{K}d_Fl45#bIv&EjDN^{K6ewoR|NFCf!QQbjuGVIe)As~yK}F&KHJ=5 zL1&-}+lciT{5R9IGd8xamY5>GcW#T8=t=iyEG4zCm$dHJ-&Ia`39U;neDbL5_v--$ z<|lt;^F<2qESogN2jc4I`@@s)f2BIUZS)k#Z584Y{^rc*DRSrXXy{k7anSuT3Y$vX z%)Ni7@g@Nq*BUHL25Z1hLVx?h(6u?ktx1fJZ(@3yJX#jc^FZ0y4>MMCyyF2<#=(Ir z;^XD<9GNkkO)Fk-wx2RKsCN(acp8mDx3)I!Hi9dquh)_;$@DD3fd=)ZJi{SP1|3js z^w=WqtVti;mD1Lp^5lNfH8aA!)45Jxi;0eatYy_YLk_?qh1<&jMe=*ZYQ$($CDryc zDx%~3v}fu{mB})mklsNT&*pcdd~9R{j?7c9ug7VwN>HnHuLr)9cwS=LSyRp2jyIEO zBB8EUY*06!b=N#Z(yfmXv!jOjLrYI{URT`PhX(CiluzXTr~dh_UcR{g!RzcI_t@hH zmxwRQ-lsY{pNO{3ahqob(4&vB%@i6N%EA>C6a>mn-?YgUke(y2_vzLR?pssy7#{@C zslN(Xgq(Ou;3FYS2|e4K{a2{q<+@?KkRAO5@rwpxu>L_-`Zr*piHYs_=yxG`B84@VQJVf+q&aL^ z5z`IvT{sAj7cbJ33bmYgB!|Vu>XjSYR$e3|@sE&oAGdZr*ci|N>9?sSB=p)N)m3O% z>}1Httny2i_mvuBSF7iNqsF$t{jz^Ne$VDH1a<3ZQKYr?WE2;^JqHc;7z57|f4e+K^TUA1gnmzLVQcO82`Od!2%o{6C?Y`-^&h0=B6EL~`TCG^}Fk?*P4QvfZTaZP1`7Ny- zvV3R8$1Uc(Ai3@4bUMRMLXcNG6WPku$%l>_s{d}O{e{=<&M(B4&7ZzQ1GG^th_JUa2z<{Br|XT3n`59LQWdHy7Hz`0H@| z{*`pmYG=hg@@<2oPPg7;2HdH3l`88|36Gf?=zP(ks&jjEn)CJ1J~57>$v3RShn^rFu+XF#%2TJXT`=q>$G=p06Jj} z8*bVCE`;fvmy1uU$&{yxx(n)p>78~;AO~*WU}k&w1mOK4gYzlC8qyN!Boo?_Ao2`8 zP_5LkJ}jc@QY+E;o%HYxt^@89-Z`fcJ@US3C;~^;&`CoF2)Tut^jtCk6z@Z&n{d!S zS;*jqq9VgK1PM^U6*&Wsz;4rq#MMFKQ%dPd0#s}B&mLdJMKyhnp6p6Dzb^M4A`Tgz zBdB+J>fVomtHS)W&a|GnU)rD-%f_+!8GQ|Hl8Al_!*-u*gOS5MqIq;$hscPC5H#9@Jm5{O2q~zHbbDJsBy)DO{N|BMV&WS0XEBA0~zD;epf5LZH zCH|Psugx3PD`B(lP$$5VQMadXDH8gqvQ-_MkpHwOtfqK;_A9krwU%mAB~g;+OE~g> zk1VvtLVO8Y?pAWJ+Ei~6nKSsA;`kP89m z)uk14o18PeSlHv^EYS&Jv#x1AU5N>JyrtV?JsFCK`dI2<%jf(Xd+#@%EzU-qbdt6d zEW~xxr!!-zA1<`fv8qF6x;(9Qoi{3fsC~2_lRWx8wpNsSD$IvJS7Gibpr#$ndpC7x z&5+}MSheGv=fZD;h7XM&5K@6|Pc*f$<34GUU~EZ4DyFu*%(XkB)qh#SpbmJv`%hdy{@T%4GQ8M-j;bst(Uu9SW~ zefALc8moRJg%nmD9$vjg4f$|_^uCZJKfiX}SXXNKpV6~#NR`G1_zY8DAY(n?>f%i6 zAy5iDp`ZmYqI3O83GEdtTK^pj;SHM&w|<3~J91Np7+4L|_>WR~sI9$X<9n@mCK2YE zJ=W6|pd1yLmf4rj#7m)2N(FRi-&@thqBE1;*{TMsxRWCvu|(Tvxi%sEgSJ*atO<0eCAZnND}fjp1!M%X~bU7CD>|Vaie`MHxb1M#*@8rjRd85qJ{K z{%39gNB0bHaY3pJ!2hXK>%5mUum;l|$smOwrr!JOz4=87a6u0Yj;Wn}ozh8qt*;x` z=c<^AiwxghT5Hg`A%z3TiFZC2D25ZC4CPr^|V3b=K0+@ z7AVg!;0w*?qCY+tIZ5C{RA(aMSt!ZyA}q5Q)x7tnYg|950UCOOVq-ng2(T#)Z+=yv z!*7r!kshewO0_a;yxsZ(z*oGgAZbo{()4$+$QDrv&AiW|BkLbEjaJ~w>kK{o_3QbF zli1%c(DqSe3c+$@_@s_a1+xHYKX(_~#o3B)on>SCC8_@bgaY>HLPo zi}zQYN%fl-XNL&LWOeP~f`uBoCh(4dWSTYv4@;vX)rKjYUo%wJ!M6bmA~@x8?jaCi ztg`KJT<4^rWy_*uEmZ#TnlZB1+4k#;vFu4B?7oPQhSxN!*OX%A=<}xdN02SPhtf5k5AqL1*+R$cmJA`k-dCY<$3Mow* zFyJOOOyhEaJIWb4_Zs7F$<-2IB&?|kLtVmQ2W+s-bjwUnc`UR4RT!52$FQcW2c3`K zU1) zob>e5tCNmBp;54*(g7XxevY^Kkuf?^!iLS~-LvS=u{L#S-%|2du!^Oc#KmV2F$0Vr} z-k3=3tI7Xa+Q7)!RBMwPaLj6Q_Bo4P^WZZbA`A&c4ta7Q2|$h@a49!EC>35!RPd%p z4BYat3W!wU;QDu4LKE9{TvaedsnC=-gtbEJ;ZgRZN*_wb@k3L}eA{Q$o&#C71As@} ze-F4aNDuCSQ|<1@l?1ttOG|v=zzgr7ppF%x`|3IKP44$C9H4QFFxCH_)nN(^s0gzx zaX->)_9fuQ@#KyP3JBcb?%}nA_~Z#77=O&?v=CqbJE*Xj)-TcAkz}!cqlVNHU7J@e zybAt2C%hXY`lMGp73ce6b>AmASkQU-e$Y(OwsJQ;C^hhP{AW}93`(F?5eT`D)6f%q z-*u2&L>2BJlB-t#so<@Mo#+eWoxNP)9A2-|j*fLqw5a}-$V3`6#NtU!y1uq{pPsrd z*^imIh2OX+2=VOfIQP~d{mEg%>WShBf5+fO?eDpzCajla9AEso!Mv!@Ae+K~y-w3y ziOT>hQtHc+GRnmMg9p-4si~w>o{+)|un9AAfDAM^mY2l{hh(`@Bm5UR(}p6<2Fj2Q zdCy9jfjiO>IT$e=A$2#Bl=UvSw^BQ1{VD~{8F zgJSQBs{b@N;rKwo|FEU*p9aWCk z+!`YXIbwEMl==lE*Wa28T7o**wS8CyP^AwXmF94_HO1t2pkD zU?7Ca5ToY7?xfQVMjUCl;oaJMR19H;HpV_{DgAUo;9p^&O&psdA~6VqCWiWQ*2-@{ zyt_5|53x4_5wxSNEx^NLqQMbQ6%?w7&00M4;;-RSB`@9md~zV`TrJJGR0|HFd6fS2 zXP*GhW7x+P2kVHB-%B_kyc|Ha#pb9!<@@Amw4^Zrn)=DzpGr8jLKFXf_pn zow4bx?-+cCS~XPJtM@NBI1Of{+a4ROWkncOJ%FvsO`M#X$|lZ)mU2DIJ@lQ+u8X@Hc)gt}m05;VY2pCemZxU#>(>?fS;#1b#GkSV1)i>^7vjG%A4mDSwhf$j9zk{9ce5#0~$pP=( z?PjOKCjgMN;WT`1Z*LKimtJJ0pQ6MJB$3!&=j;8*<}v~1H+xOnl}qy5e%Z!%+#ItG zV=phOTFdy7*IFwkg-krdG(>+ubj5HRvpMBA!RJ z=X26F<Z-_Gtvg?> z*X3Ta6*82URNZ`l!(-Z{An=wS4=rdA2;AahLzX<79?bwWHLn401T~o#aNZG8ki4JI zBJ}tR>i!9SP}OP&*-$MM@O7ZwSp^30{#(L*Ro6Cke&~Em#!$l4OFnLOR%CiKcRKaQCz6U0+<1}XZ=zSa+g zmwGfMjTAmrD?~@cxe5gM=j1#?PVxF~dT{499aNh5PAN#bpB686c>fAED*4TRe=;$- ziz-heid%<`6fP{|t4=jn3qS{N3>DtDpFK>e4xe6K zwdA9O8D|?OOkZ#On6g`9Wi-br#yjXtT!%3qWzGhRWmnY;A~>eL*Qs#S?0gYKb-gQVeSQf z|9Ws05X zpa~Zk(9zMZ34#6&R<-B7Zb>ospZNTX@9I8y^|LeC$Sbwr?f|2aRgJ7sKwk=(6|O^^ z_6m{al#XSkWFov8f1c?mQuJ&tE>5GtD_8wnr> z{oFi)!2+0j$g<&~5F5L3UGMA+>pr}XdX#^J)>{?5qzJaigYq0;636y}SacA+v?=tx zbwcb#JJq*Rv}-)Xg5Zx#hu>F{S3j>O@OY`6FGj|KoP>>WVOy?O04)~W9sr6>g+jK) z70NY9>|v+qXHPNnS(Ns%OK)^fNLB(5XIonvc>FqF#Q||m5C{O*f1&pxWXq8db&FQo zYUOd3i|!8s#GvJC_k^a1va*n-l`@X#gc-0WzHxziX_tu!!LggZ?24U75NJ z*9lm?02Lw)_u3c2&p zx(4FhX>r0`{GCQhd+V83Q(A-bR|wQ*`W0}ij>w+)6#qP%^01r7IA$GRLfe&Hkx9(bQG7Mpdd-A?3$#e?)tD&c< zEjLNNVW_Fy!_}k7;6LWslu?3pj|z-FevUt~0}dZt!Lxfgv!(fh?r>sB+sJS6hs~#<2xF zYTDXaoB!p^)6EwO(`EjWoT{}|W}11zv2N^l_$BRnTzB`Q<4Mu3RjwY)z*NH8ya!k_ z*m=CsZ-+~ll?m|kFLN8JApw`SZ-+#X--vjr4ohO-5wUC(;w-_r~R?^hle}O!cosNqJD`*)4#xf5zgj|GG}G@JzT1F z_4P-9xxN0A*0J+XVx+o-XSd_}>IR+#{8He5apM(~m)nEa4*1L6b+1g132#TPaY9pv zpK!XHcgA(}Km|=*jNAeaQ?R()y?gg$G3c77jSqo9wj&cZOjPEojyC>rSl*AV-0tBC zr?0#emu7o&6L@jBU()U!XD4tS9K~~>5N4{YdG{2LI-$;ASt8fL}(`Xd*E$1 z?(J3c?7{D&inW8)-OYsG@SjfN%V`s<>hc>+^2up8<@5CM-G!$wgk4#NG}z@gj+dHM z7A{KnNf_t65{A@i4pv;Ev55V%SK#z}TFTvMh*&Hq5Dg(abC34XGma-)uZ* zdguUYS%c$B4pu0h7`JNi_>2ST-JEl3%hASg?SAyfZ_qYcoMw3?Tn4ejwMV?K=z?7S z36xgKf=->jOFgl;xMpAO6JBA@u&s z!M?@dB8wO3_qUJA84n-dO!F~xg=A!UYFot+Ce``u2?@!@Vrc>P@6sCsxczvN?aMiq zOa9qb-f8IF!F!vaN&4(#`)|d7+o+xy)|bMT{3sbd|22QyaY4-qZYc5EC>r?J*h|SK z_q6CvvRrHOHpLqK_Mi-bxUBF%M9PTe`G&J_%@&8{=L`+^+QPfU@f1acb`kk3hMGbf zajaRahMFI{;juBztSoP?q$skLd;LCpW}*b4`CvU@Y9$VhYlP2}*HSN)BAz0znlRy4 zgl!nx6vtxqzuhN+Wl4`kdv_R5R0FM-iX{R$?{6e@VM~qk&0IQpc<|+pp>-A{N;KO~ zafprKLJwNfVMHC89rCb-!OoPH8Ctznofhtngk1)cN`2QJm7aR#DMuO*pU@>FLjP5# z`&(Z8oa^{ob=_YxWJA7DRur^iu=u0J-Ucd7{!=5EYh=D@p}k)`e@|xY{V0OI$QBy& z8Z7T@;aRO?!%d9Q+reAh8F(*)Z6%>GI(70T|^y|sxtcv zyDKf z<^8{R(-Gf$_TmvR1aZDy^{-u$oBNf@Js=6fspsf&FQ@|++F1<7@c>paleo3)f}U_) z&Na?=tTQo3Qxs0;=7-?lm1c_HR4nWz)DK_xH zN3<`t{I9#eBcS++zAM6~!&P?}!W5yavEzJw z?EJ4iSLNQy!AILnz3_fvg2*0Vk+nE4$sk$Kx^TN$Q(vNYPzkEO;Z9X67TyqgzBcgc zF7!B+?!AHeU;&P31=Esy*y-jLSWZ5{zc)9#sbA+XZ{d?XzSYd_&CN65Bt=}lIH2x33CJR) zMC_wWUCA%&k<*eB_LY-$#%}(7nLw&z{)CnlRVEP27^bH?u zYSr^hS}2EnRKz)+*ko@kS2aZ`fwQbYtg=a1NAzFi`5We@iFwwnQAxW$aXyU_i{2Ch z_9ZI6XJ&`Pcz9nbAHAzRAOCAIK7@u~lHNKl`a-j?OfzC#Q25Y)edciYXGBe(J96ud z(trrpL+QceN*A%xEs>Sh^=Wo!@3ik1Q3WB&lZVpOX+IbB{kR+m+MZ46o_I$RzcK!x zCuViLE5p_1Uc##vDz{HwIJ7Xob|@pRJ^L2kd3U^**gen#!%O~oW`y?VIPQz|{wkCM ze<$bzq+NWvFJY!ns+L{8?F%O$`2xLr&pK|knsmRJcp+iCn^nb}p0YI4A@=?i(Bhs8 zyvJ=y6~v@l8Pfs7A-Ehc z&yOVybV?-p^36W@OF>cz+h?n^_`i!VnC9}_=Z~gdR7)>+ANaS_C+a=s!wovpU6E#cmJHM#Eh3( z>ZR#P-M@EIWz?cGbp$&3&*=L(A2*BMUY%E6HybO9u_1P{B}7DGIv9za=#$=ANKz@; zwh?=h6g5qD`rP%hah$G3iLM4U6&oE6WZP98?JPF357GrxNwUS!nq*|cU$tUre2-$2 zd-!Inaz>a5oia;9n59U5TG?mCBMUb}^Cbd-9mW|);rReT5{%AoCi8Z$EN5w!RGS$4 zS)=a-R*%xXN1fxLTJS4tOs~c_>E(x4iGL%0zAxj{Qw7e6@&^En~v8m;2dUK#2zBMkU}chZz= z`p1vTvWJy>TU*~eX##vmy*NHl-+s!K{c`Y|x`}d!NKtW2g7P+HG6&LwBTwE(TaGSz zxXHrj#5#;M48f4>Od!hQMbwm@uKybaRkqXdSLA28WqKAQ!c3l9`hf=O4gZBKOt1>4 zGNyF=(GtBk50VxZW=dd9vDC2b|D~rDtMK@h&qHLAO+o6nPW=1yr zou#m&YL$R7vpfwhyt{CrddvW2C#_pMLor79p}jwW-cEy}8tobTNoU~wWE)dTllZ=p z(go8h8;M7Ek0)4_@-?v|kl^=z<>lhHjZ~|nIH}}=AAVB6HxZDZlGy}l^Uem32%WWito=dy;(GCf`<}16H8}|QO={~Not)&3JkU@ojybls=*!FNF1L_daHBqP*fOBy z8_#AOZ>Qy-suQuk|J!Ou<%~{x=sSal4odn$sXGcWAe#ntk1(eipR=Rr6IE}2Wcou% zpp2D>b+BYsc$eCFGGsXhkvhMs$MRLjD7|^YllpP0pP=D)pDs+sD8$4=3VDY68O-cR zJ{*1huMR^@vcC+2zMht@G+3b`<=!5g)W(?)e$h6OI>y*B4{XQhAdS6H_-;WTw(2G< z_PJl;xJHWJlpNCwMRmMFQAl@XLg=T=>vz6lisIpRXcHAmsaES4dhVRkid^JbnVFPy zbS7=Sp1t~lXwr&yE~b-(2J%?Ox>|IIfikZ}G*NNdPjJ_jW2j(92cZSloR?DcgdETmO82E%Hq%;xzf>*1;67e&uR+$j;FDwVWkeDsaI_CSU znxA{4#Ku&tq>jx4p@0A2Hz(O`WDaJMq<#CyL`2VfsC`kC$-spOBkGGo8gkcVXlXLB z@#9^s=!R))T3NL0#q3IH5Ei;k59e>%i)FETi$!4(u+lJzs0b^OBf7WQP1TkE7cM?*{UbvyF0(ji2O*3_qd(D^B3wYHBLBQ zPiK_V`Ym1d?oSkQs^c!G@3=GlyRz2&utiIMg?;u;+S(O5c1vdhmbb7^k}p2*-&U5v z@y{ys%cPt-UvF+=xFyexHyLb5Fi`};UBR{CN{ZeeRn=F&gOHwO_mI;h2fPQ%eIW}jox_eP?fbYu|y?lvstWwz@!4eZ9OW?GYyWC}pylk4ubRUbLFPlLcRt`p-UIrRX<@)Uk z<8ALxC)Hs+3tLjh4nlnV!G(9hu&i+J)}z$0-x8d$NroI`@$z3~9O22iVZ{27;uqfz zf3P6Jr8j+P?ZxLjvumzk&!@uowCkgm#GU5>k`r!0$t%oT$xP^-R(`Jh!{|j?)QxNl zy)@Py?eFGkIo^e*;u0aA6+M{2FO)Xj^|MOn?)hN)qHx?S1l0c|nRDO2G zfAonS+n-J}f&EqtJ@R49ry4oU*Ot9(6!{g3G0z^7221%mlvo^{51%R?wG0nzpliNn z@-h2>y8WIM2SX()*61a0tZ@)FqEmXJpHDam<3&m1HQ!&E_R+CDy1UGC^*t`n%3g!W z?fkE;wWm&e-_#dwoZ5VI;wpM*B!W_h*9IW)S zZar#?-fnhoKPy_?>)37Hc6nn)-r%_5COph0^MHnu(p;QULo!Ye^-o9(*qC>26)*#C$!1VM=2MI!qsSyqlj?y(O4W1W51Dx2|V^jgKYaS#cP zQ(E`NZv7ZQYr!V@=QR5P-pph(UGgj4f@kIn(|!(SOR7@Da?5@-_-fRCJH zq3v#ReLi)AkeqHOQIK8v9n0BH{xmT!lEqrQW2biL#tjMI(195YA~^9$t)nPWG}mIJ zoQ({5*UQ?>_3_UW7BZ)*Bo5fgrASMeea^86)9PV@pwpfk(fn!dd2)XQ8y-MBUp%xD zCru8kJ~|cG`D>Heh`k9ZCBJ^@H9FB0dcYiPiV~2lJ+8#CJq=lecehvix|X}k3(oa^ zcv0a9l17Pmruu2}+7DFVYt+*`6hO9nWV^8`g=L?=oXHlQuv7UbDR86XpZfl+t(j` zpGxo(#??>E$Ex-8I+%p8n5StX-)P3 zvGH(oCV||&q^c25qkdOQ{k{txk`y-nvbSMU1%WI!tm$>McsG#GR?1YG{AjP>{IhQs z5f$f%rMld!cM2g8_iIM@^&RuWZ;Ypw>sIt^>|_WHCEz$mdX4Di*WPF6M0>Q3DoG>_ zZae7bgFh%wCUV~uMD3d+FLd&5_`x@~F6nCtf?;)1*F^5zVzNvdw8x$Z{0Os)k;RJ< z_$of)lCmpf$DmY5^i-~?a%fffi)>mnXS5`dRx*&=!N14D!?S2T z$1y@ay6LewbLUL(Ud+>GRnlw}l;8;2zP}wLC=W&^qCb2xlpA!gw#pRF2$%kJVI>(j@}kY zi-o+gaPSRVgsz}n-`k0bhQWdToNASBcxvPBIC20hF`U+V)zRW56FHS z;_MKkzHN}o9P{(^^b|~OhcGx@UfKLGcMJ}e$C6hol6sdrul#nVxs`0e2d&%wCnZzt z56ni)xbZqfm6h#$(wC;_SWL`ADtAR71j9tB1U}VPXs~D{;`_jfwEgJ4vya0-Yw%!- zYZIe=oa5XuBl_n?0%yW+aoWKB)RW{5-uv}SgP1w3Jo|kWiW~FBK*`m0TPp2{ev!M5 z@R82F&jLjwUe}*#zGf`kN@kb-Y=uCenU%HpPCrhOBbt1-t%Ehyc)k)isCe(o(-Qpb>QTbf{18l!jZ6P`=!R-1jSh6=C6NSr#SkW7)M}z49_s+bMw^qwL`Z22 zFN(2dltY~TIDl0o91$#x`bDGdnY?SNf+3gs*t}Fa??6_6NGl$z-T*|x0MGE}7|6m;MmEyz)S*s7&ID+ZScB&MLhp8p_mh_0=Gp7R<(A0@V3i-0t zR!V9M3wvuJt*dzZrrwq~|C)FOb8lz;K^OfucJZ4VsGchk@aqdh1@(1VnePVJpF#PE z=N$N1%g|YvqR%1lY47B4g2=@IH2kCKBn&im=>%GF9K>_NCwD-n!zPjm&!+Htx$eOS zx-G&5k{ae3=zLZQ5z}pcf=XGH9ara=qTl}Pq{wV~|L{FfxmwaNV{_Jbim!epCq>gF zzYsdYzL(yoQaOuhg}^QpyY)oQX82qY8!7E`iT&UW3rE*1c3$i4aJ9Mo*S2>FrIZp=a*Q6{+y@$nm&xNV zZ=n)mOtHU^hi}>WRKirQGZ^fa`}zr`{hp4N>X;3>*-H+Mihr?>rlzk~BF{NHF8*li z8ik8TKzsyw1U+`E43^1bPo)KBb9{}rF)BD!Sf!XxTdMi}S1(W#SnVa|58hs%|2`@g zY5hVDuSXXCsUEopnptWIlFxC`%)`L>8xez;qoxzB*r=OzXBh`DcrAH2wg*03`FaO_?{1>@)`U6u7|Xct!4>f zVc4*4BFgw_S#?Znrja^>JhcoTHQs;?op0H$GvYtzsQ!ovv_mP#6ZL*!`W)}6|8&Fq zZC^(2adCH}Mm@IC3?9rNNyseQKl6v7xOd5*g4TVE-jkk(z4XR_M#=vQ6{GC!uFI$x zUqy#l1%dU*xBQKMBbIfU5I#-JvT%Bmmam^v>KoD$<+05+-E6d@4Q~}PRYdPSpW@iu zKk4VoWy21+kKxnOwem>JJ6(QnYf^*t!kgkz@ij6B9VNJ#kbC}a=2R#G9qfkr>~5PvJ2N9dMFu@&KVeR2mvYSmPT4Yx7aJn<)Q`M9IR7O3cM#_(s`0)~i20Xz$EUD^T zjTxqp)Uf?{Ft~W?a-}k{Mum2Ea^2ftV^=S=1Ubig$<+N4RDE5CY0mN6CLeU!l|u=T z*<+suYE3CZr8=uYn1`r{$n|nC5yQVu^M8L&cV{YYJ8;CDl67qF&&5TWqFMXs38c+E zljE>_s?Zy!4$i@aEDnPL)vu^u`z-+YGBw+p0h}wOUx|aB_`P*K<5|kRdpn#NEEa@) z&M9j8^XwI9DzfFg)MgrnD+bjB86zc$sfjA$7sJgpB^*o6@F*#*2QzhlIS!61B8$Zo zGBnFqSIVIOEyn8%?BmK)gOginy56cI$JztNP{`99xirii85qq1QU>y|+#DkSuFw(1 zi4-CD6r`7Lktd(V)EIe=c#dWg z?&vx2fqX6s6Jw&&m%9LN`F6w@0!?*&oSmMkqbUlGwLnCg@}k>>3RrP%A_gtsi5iK4 zhsi|(RC0CD$;eQ>&%=$eYXFHvwy;^i0n;mZzne>WLb-6_(x(v@|D43--f(j{xsn>}F=@_WJlZ}>wT%B-XVcr?oT!tTOv>8Ldb zCwT4Jrr+Si?Sy!2C9@8Jl6Nt;Ej0m}#VT_-IBd4YT6N?w2K(^p-YA0WpKx-kWJKOZkcAj%vVF)@5z3UII zvZMRJpHa&+HQ;PtsvdG?S)fzC!8`W6F58dUggRoCIh=G#xtz0FhR0 zj(SF-@ka(EfCuqa+vSF9#)>-#AOJG-CGhF-Q3tgWR3rA>l0ykiy{pWk`oZpbW5c^s zg%Dw7mr7+JPz=#ENpx5MX+7IrG7ME9ViLSnx835`(gHMoz<{uK4=knG`lGiQ zwI(Gx3o1EsjK+Vr*G|xDU~vlXFHrw?Zx4oQbN{g)B##8ado&X@EO}Bp2p%yK+u!Jr zU*c95$J^hCX8`nFk5a>_8`SQkg?yWCs81b=&i2#HrYKo_@nFjG+cmxSY$`9gxjrf% zOp}J+h}w?_0l@Ltz<{L3o_}GOuQOJjBSl}xT%B1fkXeYsUXUzGdkmj%5lh@kGoelG zt2+&(azw++#}g5A23F2D1Z4OVi;JUXrXaR0Un_ZChM`kGceO)*q82;3DC#|B!yC%* z@?D^k*qttG0S?NFrj7LcRxS6=**GBadO{W@Db0_$CX^CH7#J2Lrz^sbq>2G4WO)2} zb#+Nq2ym73fQ!xj`OKd(BC-?UhSQDB0#G0Cv|imyZSJ(a-@jFu6XarPOzG&q)$)>R z^2ss8I|)Q@XF$N+q*&~*5Cp%oE&!_RHY~L8fE%4@fp%0+t~VN_XLUwvbI~@-xP(^c z$d*mM`O%lrn_v9PvunKiiFS{QgrB zYiFu`tQ*%LdbgE4_k2xHv`I~jHj-DcD-eY0vS&p;;iHRec%DekM8c(-0GELse%Thf zmtU^U4Mm$kQH4r{<_iXk)5Lh364K14&0{z{;J z^6IN!j-}p;lP7R)8D;K;zU9-oc*p)Ro-iO&YR3K29y)c6wU9Wr`8YSrk<_^QFYJ2I zX0s&X-hn-5zyBCe_8<4#JNf}!v0O0J#-Lh2VR+& z?ivIH79-0x3+^T0;RioiAQKZH@Owa@R=6EWTKADvipMSHZG(Ua04?8=#`t(?yxJun^rcl~(Lh9Fj@Q`w3q%gpTx;Uy zP>^CIHgmWe?g%_D)*7}h(};KJOuoj?FFTN8%=Z1)W3kku^CkTU-_rEz5J+CBDo;f! z*q7j0lklnFV+Vto2q<;LeJ&20-FKaY#;buBB9vCnC*PE5D|hf-;Fkt$=f@)f*-Ylk zEJV|cwk9N9z)`g@^d7GDDP7uhXqUhJ%IUZ;P=2`T5#(ZZQ(Sn-^$5Ilm(fIihrxW0 z)GhUTbtx2ChDbCK7-!PBeg3LpGWhpqd|eF8}oF*R_Q-zvJSyoc|xW zWJ{)m0RTBfL`3{-@mTwUq5V~^P9ALrh@ey^fLhxNq8li#@4rg8`=6+{`b@)ktC4C~f9(BKpbODs*TBmJ!vz}C&LUO<$C_S8$R z#nH~ckrC-_YdT8*KVvf0?>t=;Y5wt^0i2lAqTm8O8nYOJ1`CIPN_sFJHNR3A)0}Z< zPpGC8smI9gw8{1U-MfZ!PPKicqe{b4QT{Kz>{)78K(quLrbYs`i^RA6)x!dzAidW| zj0m!HIqCtZqS${tdukxd6tBXa?z7_)V05b()^wP@0EcT#1v;fIg7e-bXWq9pj z8YMET;2f-SQ2cp&w5@vmuKni1EGrt^K#Og6EZCW~|LaaHa*((Vpi^#GG9@|RnN38b z4{tunBlUq=Bef1wClyMltq{*E3`%G|39W=DC2$!4CygZ>M7T8ka2a|ib`-(XB5xgv z$B$Vi4S~a;z-2HJ#x-dn?YS&DN5vBMcJ2J_H~Eh>1NElA$vVI8+Bf zbpb2(t?s*vBFLxOxS+kQEf^*mqm3>hDSTbowXuU9%kjJIQzAgbDK@-Qq2SCIB~nhR z?tLE*KQ*_via-@CyrY)q!FyNjYx}Rv(ifX0o7&WFz|D_l`QqN|s==Ap^DM8KkFkDh z6fVeF6KD*{<&i)U>MG5z+_z|d-_&;y;Bp%m3KC7}UYe5qcXLI`$|DNHp1m&ni3(>B zTZqTQm05K^LlydV-Yef#o2eTihERll-W3WRPR!Y4!_&l*MR*^b`e&%BX8BmQi}AfM z5mWHV^1VEgnVA`gqE9Y>1v`h@@vE+#l>C1pVu6wHgk&FT zt^)!HNG9*`eR@=vRuJ*i%U+z5wHz2^@IqkP+Ly)S=|vlw)5cd>Kfb0qP$hn6gu#fdel%dP*cIwlA$MCUk*i}i(w&gZ-L3j`1bsk zZb)D5E`RHk@zc`@=M*_yji`a*FU`#~h?r>g%lV;vtMUh?%KdwUt;BhHHlR6nob91S1OTE3h@Yor(tZ8sg8uVLmUyx*G zWcVocgVT_iI!LQO(oA}`O@vzGA71y0mpMQ3!$^TfG2R`DAb#}q!R;~U?eR9S?fIBU z1MnKVPL}}K`}JaF7*f;Ids4K0u0{e_Bw0fcd-p`0mL-~PXsK9RJqw)dzdPAvMx&z8 zU)(H&*P$9(w_hBs@|C>B6|#DrHX@YNkW`$ThMh=Bwt>qn9XkwTUiY1)QnXb|_?x@K zMB4@)QaXEh7Ub7;@a*__)ei?<$*sLTA0QlV_)&IPDbk-e!AURD_@k^yW|2!-R1onN1jh@4LdqTVn7X+mL;vJil4&vqHx=UwVUR-tzL(b> z=z6TXSBP9K^%-3x#itd$>UG<88BKXrL~e{oP&tEyp`*aT6bK5apcymqP`%%)}A$NT4zS2V`ox^%Si+}wJ?W#4O|7&KYTz$+@A_;ydbhA6684y zTh%m|17aJH51b&Z)BkUwfAcSLJKRcO_XN8Ec~nnfwqN?V#Ko~xCcaa0zKu)|zQrLc zqHxSHsJa+0(Ln|_wS@I(L5B~vSLu8IBKLE#E(s=@D@0QY8u~Oorvi>J(OlB@5v~%sA7!XyJlnAf&1BXL}Q;n{Ai6C@EW$f9$9#KXwbDLX$4S_QR~kVbQVrN1`VI(k=2d|HNQ(|O4}eS&0^rR&b_os zfRhwlRTD!RV;$106vn78l@UB?RJ6k?G5S`x#$}1CjXxFKP91;z-TyRpdo1sg5}z3| zhvDZpYfO0K;6MRlG{mx1!BUQ9(oV^Qn6>=6SYt{d|HOnmMx#XW`-i@FQ9(}2%aRNA zAX;XD7`Ly!!G6AWdo}7#H&5~P7DLRqW7F0C>gzHnkKtks8E)O&!G8Umhf2hM#R&+H zu0&^3@@tsr62F^OZ3#RBX6GEWq8Z;}0X*SvO#X+RpFonulqLD?nD;@`zk{3CE8_R> z@USP1z?eV>0$fH%M?t{Py|=z%#we2Syo8(i&LUyvI%F@l&aaMe2YS0}MFygU%|_U< zD>s~3tRo_cUR&L63*7s@bkWbJ@?gRW*kHlbC%oYz*v$n3kNH0UcaiU5CyubN@L1>i z3!&jCLP^7w3_!nB{8luV=2eN3VQ3U~tfayV1zA;>9brI`qFMNCWiK`t6$G!e>p31& zS5z+yj$~cldY8__J0&%_^UjA{O3&j<4$|IZAlP(AZcockDl7+=*y4G=(ob}V0mYF0 z>L=x}VFOu+Y5I4V)mdh|-!N3FU^{N^r<9_t3~9rkw-wv?XR@UEVwbxs>{Z8aV4NJi zU^tHKtf~sK1Tu$)`g*a`Nlm%)o7MLoH^t(_aycL?GcpPx0}p|g?>5J-&%Ra|Yl$@+ zwpQxtn*3(_DGnpRmJ*5v*?QqR-n)BqanZSHd^5t6Urn6XoUP?p9Yo5d^5C>%mi()p zBuX{BseIw*I2t4u>E6(A?&gjr;i#i?s%P9{tEs6|n4yOKU<5LAX+uo9*?<0w;xsty zH|o4dz~c^Ev3GC)?x12lgt+tI!NPR=zAt_A`o_7@!7P2ttKI1h>b=h3wsK#Li%a6mp^6#~1Su|ZU z>Sf}&FCMHiTFR(@C1?@LCdwCWq?_OY9Yxk)GXgIBf0Kn`r}fc^k_}oz)s^Di$80Ol z2YV_Z5N<}bDdSc3f1$^GadTnCo{fy+zV`o&{ji>J4k(P`@K8kwD)AG%O+)jDV3mjM zr@E!@rCPcR4K=xMaI!2EYj7K8LC|(I;xNC{s&l?PG5o&mNH|!6@??!Wq5L2GU#4CS zrTg5&!$W|Eg9Ps`n`Jap*m9&{|GfUP+gbfRG;PXZB$|k@?P&0+{*4-(JAcxheSzDd z#)8Dfi$k+td842=>aup%HSy%PDpu%9dU3_oSu?nru^_jwh+k zYZcN-$))f(zc}3<{n2$XDJ?^BH zAa*uR4fHsi`&f4?(gLYX#QgW~K}cvmQ1j=$=ZKeIp5%>{cQ%PmF4|KMYvyOh(9^Xt zkb-Ws^r*1&a1^^>0PjZ;=J2`;$nWJ&^ATH`nK=h~W&eSSNf(n&FkW*->17di#=pj* z?rIC&!3GmtJQ6o8*2_M8>7ZgD3?hNSkD0L7_Gk`P3zg(jfA~F!bhtkwM1JiVbUNY( z&RNT>1DnG4NE3-l!dhGN$uK<&tBvf+?{hpFb%QBAbUcI~EysvNsM1*U7I7iaw9$-G zXdYXx!8B=OWA_qO95l|VITVaPhn_GZy5|gTLpwV=zz_?@UH6|+9L+Ysk$>g)=N3JG z*Y6;+O-%-tzfHhBnM88>b%p#bj!{&to7-n2Im~f>rTpAiRLxl`mJj<}5&Nk!A@ymb5Z(fFpH)wZC|Hu30f#%$Ml7xdZ8A57{C&qRz^bEJ9&{Q1msFOM>}pgs9kIiA2cJ zMBmT7JUdHgufk@RGb0%Xd`_h7r2-t*;b}Wm{oLJSZMtpIXs6k8|DSt>1n%c%y}&!j zH3yykdKrgWKNnpB6&d1@$S6_uY( z-Gq0oCCO*pkDjDkNLO+JRy&#i9f*XqLI>jk`CS=i1@sC4-9QT{FXyn3&hj}P087M| z?AztRN}XeP zx6@^rFPDk0G^G7K^2)rIlvIK&Bst&@j$OAMaa#cEn+Q{pfWBZYll6x}XO(Wcf|`H2 zi?vWx4z{+PhmIMhSHSReeX;hg{cx?1`Ry~KI>7IxM-pW!wzICp4# zsZ4P;RwaU{1+-;l0Zl7@sDYwR#fv)j6cn<#?_qBQ{GwZ3DtuR{-28!Lf8j%ip+xN@ zh`Ns--f}7vgki9H>)qKaFLH>RflHZrTD@idSZh3`pyd{puZw`FOZr3M*?b932@;Rl z`kylkY|yTf{Z}?Jufa3x?4D!z|3Eo_d^%0y-i1m&!!$PqO&JM+AJ^qV2|`ABcwQxN z!`#GsIuRSvE0*x)@lU=@ob%}L;MWd za*UQZla#8&(avGvss;3E5jKyDZK3ggO?0E z{E3wG&a`jQu>y3x&;OP#O?|KVJM~3e{9;LUF!!T8aX=8y+u6AuBhLAsUry%juDrcd zqV{Y8>TOWvnz=S@CNlV#q{eD@Iu;oPG8sUuOF{34?`q6c8TRoFrTL_ z)k+LL`Z`}^uE+G{+Y8obgqey&U$#@NwuhbfcI_8yiz^z=f1nKRh}^&xV2qmsvY>Q6 zySQUDlF$K(xCdwuKyJS#;?f7y;1*&;<`lm_ItnWl7e&lKfgAq%17JQzy(#5Yc*nv% z{_Fc*g@Alht{m2@MyO3c+Xo)n9&+P61FJblzmpGu$-C|%Z*%IS_2BhKOTh=;O4#v- zrEBIiWd_`?mMM+V1DcsbO=ce%0{vwc;%kQ4a}B~S%a~#(tsd{Q;fnT_mD}qbvuxh_ z#v5h}ixSaiRKF!RVl#>><%$i&uWT$;VO>cU118Y4BY7sCzDG0Co%ywldGek3-&y$4B`?HqYIa1jE7noO0vpmPsuPiAO9K{^V#6>SbXykLh$9a z{A8imlC!14q}0*trLUE_e^)cVK)%(iaMu*IpLJD)#nPrx3C2`$-Kc#wKW(nlF_H^+ z`Zbr`cKFFL>KO|$-f9cw(t6QVM_zrH>7Umg{;Q1idW)sw6y>`>*XbUJ-uO!Ix5l<# zq*gp!v4nG(NRD=>+F^*5vbu!Sl~Oc?{}dgj@%^NFBkJ@sAD*C2;`VaDZ{=3-ZAe+4 z1P|?-Jy(pZPsJd~RU;y%B1I zI|xOjDrXTgg}f=^Zy`4eek2Z~dYZffoh6!a&l<|zkmw!2G~!WIm$Qm z(eSOLxi(|RHcJP>mgTYti_b?m0tiiU1E^~d@*$?BbZ>se0|A~15CwmmCwNef@BYwCt4Di7Laz=5P2mHr?2 z3cX26vf=Z7eLaw=Ccr^7HWdU&<^BRD`pfn4kRvE%0f{U$gIe;cszd?!va*={?ah6! z6;Q;CxorKB8zhm|Mzn&5Y-k3M!{AS0-H?vWx~COtZdaU1Km>j2=Kcjs9tP>FkDDv> zF)s5H4<2Rz7Fn05!2k_`_0^ApnKijdR>R0o)FK0q-%wXm@rWToa_?X zQy4h+u6K0WBYVt-iIaM|P?25i>fnHRaAX=l@Ikcq@xq*bF2lpvsaz)368TgD(1T*n zKV$)1e_q^iy*9&Pc@x_Fv(QT3Smd#gLtT$-lOv>Hw~OD82? zrRxJSYH@II=Kg|UkUc}7a9X`T$p_!Abln_v9RRDO0;Ca`NYP9{w7NW2?wiV`1M71v z1TsnSaY-(4zN?`Q%V|=BsF)C*Q7Z@Z4|chJ;=Hscx4+-@yqY>LG4Rp-{^Ko5vM3Q$ z0$q)K+zv+K*cY#J=2k5UxO;seyictM9>4t$9qAeTmk1FW8Fyb77w&`s5Tz2@y#n}3fVx=1 zPubOTo?HE}Vpq2tl!&9Z=7w3(CJn7SRe}K0|D-O>OiyrOgs>`;n-R(RBW z`Oj~HcRUE^+;S!%Ke|(MjZiYR4(Im1z%Fc2J7laz|3HQnMcnEZ+ z3Az-P9>sUgP-_}y(DwQT8%@F90h*@@3ZZu6=p`-%T_04rWtuqRQ|6LlA%$XUIZKxw zyyx)uSH`znHHa6Y8#Vs#jT?FwWDC^ceQVB=Fz`LkC%KXZ?i_s@Z$Z%SLec}6{Oz&Z z>oKML?;z$37cz^ry}ysmF@+yR*-Oqpx-2Pp(X$eOwnISg9Tf*xL!2k&tvoSy*xqj# z)=={B*PcuBfIqqAIw8)=lF2-xdsv%6eyfX&g^U3s_vLxF7)rg5CiL>S~D6q?HAHm=Lo8fS27|TrYtI zX15tI^!@$)pbX<+KqCDsE$I0HLkK$=HM%9Mh2Cr&!2SM$GCwR19Q44cQXQTbgb{*y zQ)*0|HHd0<{p8bc(nNZ|Jy5;d+_2>5U856+F(?Xzz2K6A+`VB%ky1T4#Pq}M!RPZu zjhvp<7{T%JCCiMOAo!QPG-%Dl)=jUPqQ1C`H-tRG={^Hr$30dkdUkNw*se!%5%oO` zo@gA-fz*kU#L>=#%8L|5Ci$KUH(6Y%RAE*KWL+L+vO5&`SZYpjDqo9Oe)3^?teyUq zG%cd%VU%ljz}pjw|JHqObAcqhKC=iJDRq)8%y>)6r8h2fG*K|(7}=Q$j7GBd{+btxo3xR*_s|SN~`L1rk z?yTp}MdD7$J6%&1V9f3wD)__}uNKc&1=Q3@@}!(5BgbAFOn~+Mvm7s#B{vKbXPGu) zJ_DedZa&9|W-dx_(tSOmc#&(xod!I5cYi*nKS5|yFEjTvuvEwn1E`6%m&C3k{rmpif z0e%q%@{ty5Z6|=?yJhJgxc=(j()&^1X9&86Y0Qt0qggURcO5>WvF;wP;!|HKQ`|F8 z-)JfSa#qH7tcqDX?XxpnZ0?0rk8b!n-{Me%92ne+n8Aq0M93r}AyR=FGx?MG9Cc;y z&Gjeq%gsN8y-FgOK&6MhqU{2 zA-A5y7I)6Ew13x!eFJ{>{b44Q$ueYYd5Pd_b_kY@R&Y=sG_KvVxXaxMCffJ$nwfZH zSnAW+e|W?Qfk83xLeZ-+_FgYzk$fh!k3lN5MzAodTnuSQ!WqQ7X1aID)jE05}?T&)Pm{o0}WLc@{!-NXGjrl3O{zbfQ26ca`y5-(JEF>A> zRIEk~#5&xUjME(UpzZIN2Nkm@+f7tds)CVMf6M4Xm<&nd$KKal8+szm={mOYf) z7r2-8*-|gPAZLV2HC*EIhQU(j9#Racu*#>#wGfoJ&War%0q+>rq|9&Pp0@8uoyAynrIxyz5?Z0J|#2gdu%!)X7_L2tMO_+>2xtF(uvVzY1TDH9dfQ`=G|58}Q+ zGA9|N0w~WYi3_Y;2UlwreK906lX9k-eOgNSO_aGwpEDQFE0zCMdV!X(;D;D`2KGyB zw1a;nG5A4#m9*erjC3F_fw%mSpppYZr&doi0U?MUMkhHdB@+uk zN6ujk7gFkqzymk@-jwpGD32hY539JKtVtLzE+#sANkgwmDy%k+=q<3^fWWBiF>)v- ztKzC&C6$)8i&jO_R*Z_GlDH7AXCe1RMQ*!>BrZw^Pq@`c&oq34_E58aMvLE< zO9l0Z--_DA0*6TK=epQo@`|Et1#!=(xD0vWs=;fV&{1<>qJ64<_$YwQuD6RfIWUfydyShCN{` zfngk$`_J0g1WIvwb=*GEVoTAjL2LFNr&$lQ`ckKQW^R2sr+>! z&yn)$Dko^?DtrnB5i$s*|4ve&kES!gsUwK}oXlJkgk)5VDV!%)t+ahW}Ov z;Hh2qppi3Tgb<^Lz@%^?SW<>?hEO&ybe%IyuTL+2+DL#iwBx@s6g%3A8|ZV#Z4zO? z#g8eutN_b8u22)GnIj?{$0i=*E6-=;s+1wIXtL=h;G4rtY!>1*Yo#=U6!{WJ!J3VuWv5$ zz}Ii7m36NAGTpACi3(EQ<}z_Q^TbT{E}aKdlhG)-qd8wl=%j~br9LqID{pED3e zfY?Fa7(K3!<|N4#sW`HmT4&B}Ku&xn;g52wklF9%9l_>~1LaQxL($&%DoO028q{gZ z*#1vlUld9C@`sGnK_slLA8I~XeupP0ra3v8Yy_gkROu2(N9ZH*g0_hIVx&f^97-+J zW=4eS;gRU~pS7R8M=4aD?aSyGpEoNlUTq6M93>#2ndN!C)0m{Hop4{oDWSkNy?_)C z^j;i+SVHe3E^M^!KwmNXG3U5BX69?7YeMY=7{XwZ=sP{>FZ_z|6-F~EHpvpzxQCL5 zySgq>aT_(m{0x%vWsxrr6|XmU4CQ}YDx%3q5&LcLEG{=cH?~tFgPsydiVTzgH=`1G zT>)!{K-Huir2?2gTOPk+B8$Qe3P_-+W?w5!aTf;f7s~cE4bDF?`-OYh!9e9C?00=p zZrH-ne(eH$RA0{Kfiexq(}8mwWUoR#CQ^k-vc&YQ0jT(3zWMaL!E4R=?%GlbAbwYI zJBAYww|OR}3S?wAPC&a1`DpjM_q`ZpI5U7@WpwBv6kbLrIDrA`{p8;h_;!C>U5n*C zL**}&FV$~<_qhH?o5b=6%n_pJKWZG8#PpKE?-!{5INDH=(Kwxzac{$_OeMDI@*lYq`K0^Z)r;ReDKZ2mn(}zj^Ky9i?E^#KqtV4(@oWFxrax@$ zf5*R7G3M|6`7-c}!amTEHSFEGiy#EF3tShkI0S7Rr5AwkO<8RT(%sIQND&MT#6E;W z@ZL(R&YKpqtkY$3;2d0@Vz{P~{lWf?Aw;QC10xUo=6MM`SCZgrzjYJ~eo8fx)*x9j zr1A{(^gePsK&2!TLifX~tA6_1rihm)R9iz=O(p*$wMJR+3bu(tSC0fnalmSJeie_| z89}uX^I}}M^BHU6&r=9Q0i;sD2-Qm_jgh@`Qv&9P^6G zvIOae&Vl3f5#@dmCqo?i_IkZR<>-)Aho<7kG;hBOdHtB?;nf+Y^{FQ&2w#KRlaa=I-j zok|s88$n@?N8ppX_x7$zm`2RU6XYWEj(~Z`fJ28hiNmO2Khwyj;cll`11{>i^_u>z14F-+s%%Vv7f-)m7Kg zJETG$E1NYJ#h*)`Q*IeGMQ||154~C>cHg#u0~k&X1v-V;$-KS2L738ORqX0LU4(r< zkmh1oy_*LOFTiLx6cU%qmL=rNO5zyh@#k-Ml>{<*Yg>o6JxisfoQ*igbtG&;j_9v6 zpy1$<^_F-m6o{|9k?G>I^EE;#=^#v3C|My8Jx&Ah#A)lYIA`=msbc@<;khH-{CV$U zHfitJ;cwGig5?XSUNYz(mX!njRAf;{Nc661Al3=;put#d@)^0VY^76011!igjWR3V zw>bq@wrFwPv|jS;c(^CyCeBi-$i-5`(9%zn6w*-aP1yp$=)nrxziWGi%xF$5+A`m% z)o-@Cocs+Ykf!PGM>a4b{QsyDr&ut~7KBOB{{Af=WD=D6CLUh2g9!oP%8FUBR+mW{ zC}o^3j3#??GV;V30UCl_1pA!t9%yT|%<0{vLo{IF(l>K(_50vnq~$m!L}sD+ZXf$l zVZ|KgJk2G_UwhPi{){l2PRuXQZse(S-#fT>K)OBU+bGPi*e~c3xel47i&ZRuGfSf= z7R!Z4zW-cu^D+0*Vrp}C+W6<$+=@9Te$Yo0UR0=Q$!R3oRDVD4BG{7*hDqe2G!#FL z+rVK0Z;tcEHqFsEqmn2a6evMkLl-SinsSbs1l?W8gq`u#JbD|PNC~qy>~1ds-9K&i zz##$bgM_oNT6;$>xLnF(Oh!pmzUExlw=J8QbPuGE4wm_&$T7~+bWRFqT47OsBunHD zKF!6YCM~&r93MRdDgzHHvJorQI>t(pKyK(J!xe6vc(c<{+gLlzx~?32N5}iwXO6AM zxg-9|_+g-fiRko*Cz_;a=9$U_Fj@#598Qbu6-cng5s4pN{o5-C`V&6BrqgnQPv)uN z!R{-b`xpWzT16F@#d?>@!VhS3771Sps1K{AYX&R&l>d3{-et-vKbK}TOe!W_`7I+4 zgKP!eu;gXB7zc}Ykk(}YOloNEH5x<$;)Ft8fB(zBlq4EB8kehx?!x41B>R86ssOnF zj}YFS4ENekd~~>|B+|&E-K$SpRzB$m5`Qr~Dg=_@in;7pLH9@Kwf;#;!Y~!E z6&)7b>=)<>H2Z>%eJYR&>{gST4`PsYqjLA?1ur#ctg{89Y$Gw{-fON28F z$-peMNiBQaX(VCNNBrnt$)mUCw7lH<-D%a|V@l>tivF8Ne2QyXuC_D#{qriz2l>P& zcd^H`!AOJ-a1_N_k@+=%h>`@cKET?q{s^pW2F~5jE7MM6d&pigORUV87f~H^>K0g4 zr$$P1egC@jeadT`ue1JDO;Ji@vqM_w8t3RhFs~()o9&)u`TPb0P5KvF~7?@*=kLivob1VICZ`NOR(ZIk7l-xqdh7T4x zkUjch|GB3wU8~QbNxd=?I|EpodbyfgTFk3-v2eSrE}e4z5=NrKl2@?GPJxWcaAq8j zjxqtPNF<>kyV6bm)NURJK!Q)jIf?M4kyKy4Qk#1oa;g5fI&~DeDDzLUcuEq-{1Nie zTH|xT?rgFx#pP!QDld*qRn-m62TjG!kW?xmEC`e6JEkjsqo+`cPy;KU)G}m&{M= zFxa6+g}H+UI)si}W1uf`j}@=*PQ{282{ARzCEkQ|TlYR9i(+^8s?wE-F=b8wv1Z$D zLJ0#P-~q^2#FufJ>7K(ug=e$x)oaD=J8BgCaZ#F9kmcs`^4&D$-g<|p>Ykjq*QTKJ zY+Qr8u*eLHeW*);B#R0X0H)h)K_1#8r-tIu8}p^bUR)slSAV zmU@O*(GET)f2{z@gQEjoS3E)QMs#@fRiRTL1_wYClw@?DtOQjxQBR|f5!)> zm`~hs{^mxalzG_c@T5Dfye203gU;vxauU7xLvA$O+E6`F*~y! zbC?hnFyl(Gj973Nk(naH*9012xS_B9b>NI%DtO<~bh#^mx2OGM_vjq;>-dEQ@g$0N z)pq8SpBgT>8x|$_nDRp*G4&qSyDWX*K0!%iCb8vud| zQm@m;!%Q@iyyjtGw!t3S65;1R1EyOvAiuX(WyvqrV*T`?l=BPw^x}iqhL@d{sDU6< zbycN(Or;@;!TaKR&cNmnE6VmZYyLPy=-yb-W$%#MtX5 zXsE&9=HYE$py9i9xo5m;8WMV>+^3O0CIbND6)W8!*g|NKCV~p zvysA($X zDKU*5k8HqKXH1AQiEP`$Rf^2(`VUn@Wk|3#?a^{M9U>x<%8(_WPU1zT> zv``>FKK{c#O4$H>29T}}&ar1b>NYKuuXG{bM@T<55#&E27io1T^3Ghxcl_6?U@-l) zIAL)QsS$)JuWx_;(X~6grO8AvLp^A9HeZBpM2WI2*oHSH{yBxvwwtkWHjE)*K%T`J z_1Os5%r7n`3hqp^rb}u3CkGmYv2RsVEEBiA4O+bI>gI*(9sugmVBP2Um8z9uu%;Yc z&Ch7lxe(YO#d<5xD`w1;&~VCw)JydXh?cZ~b(jLwnY*cLdF$IRccaoOr;SFP3N)rf z?pG8cYVZ(B>}RVWSE4vk>T4AV10Dv1h2b7NG(0~sk@~gJZUa@;CN2VeDhMQj^e`wl zebwZ{VS9F>ZSQgLr(%Q0h#&~0 zc9-;Fg7__3pL+Nca!VQkii`(c&;*I_Zr2}`(EO0N=Vj3ktZ^am4@o`w+nQ^_=TA!4 z&50(jlhC+D&j?v8jg6POy1HKGpfPs6f6Q{hjhpu2!(B3zmz*D+Gct`3nT8`%*7~uY zp;6T7pM&|6AEN{b5c&IKSw7eh?tDLVBpy1#tU|A0V(vBjwB6P)<2D?)FL1zLDWlep zBPI$9N3*a3iqq0&T91>=Kkz5vVX<2}QiKspzQ;0qE>3=wNq5gRfdP2+cyi2w>%B z;(z@Jt!`}8EuAu|_c-|V^($#3Ed9h~W%p|# zNwy*nSeHta1~w#`ni!cM%`FSxFiXP;CFA zPfFxQgn+}~zHmOBh620Wm0@83v3B%tw%`H?*g8>a!A))*1F&=j2o2@3O}p&>=IInbyL0IW}%xkfx6 zsg5I5eO8HX4~b?prGZXGEZev&%tSJ6>ScdJ+vy{wUeHvpwKN!WcD9Rsg2A}$6Hh%o zIL8UTzl4+AOd63W0@SAN{bY4nmQO!m&Pc+QJXdfknZo{NB?f6ILNNk*wjXRu*$xpl zXcfF06P=5g);r+g!WPu4RB)gPLu?xSWCt^&(4AGb&kOMsPI>!%4Tkvnooln0JlI+G zLBmZ;S;I}LZDD`}&C{gIv<^pdIc5r;RaA6$fSPhh7cOG`fhy?}!;HYv29BXO-KI#; z(3DbJe*Mk;232MqV>d;n~B-V}nn z7k?}z?eem_@14%Bd&i_%hIdv2umO!nM1ZE=W>6>2O#r&MlwTyX!)gkkxxI~|4A69b zTm<+VLPk&$#JiJ`lk1mF51s8#X}j=IjZDQR42T{jRXBI^vM!_v%uZJ((uRd|Ku^JPFXlt+kc!z0jBo{DFR5Ocn6~>=z=_ANX#~7a|Wni(Jr|voeuN(Ic$sk zHg}23&u1baQ6$Dhdr@_$ue={j4@$Mwcz^V>6g}uP{V=E-y&A79@q9X5VFx~XSU>Qj zwb|bczr2`ZIIL}RBTCRt4T@Mz)u3W~lc>R#^!hvHs&;GQ|#;Q zJ-+neNC8bX0I;if=yOhlqW`qm+q^HCi|X3*LIu?>IQTdRGK3#oDPjt~-qWp_%S(J- zIt7p)IP}$Qol+E>DrSRf+0OrVy(z)k#aFsujjF&ww|+Yhnx8@aqZYLm?b=H?C}0__ zAxmNT0}w(2ur7fK+>BrfN`xtp7v8h{*wB@w1QFzi{V|pb8XqXOPK58p=i!(l5pjjYtXVj8K`AFtoB!#r_Mze7_u==Tk3T zbPK#!1R{u!!5{lhH-;8c7raJY$3NXp-DR^6s}O{APl+oL%OQ}jB&`3>1t2?QI$<_} zD9$0QqrWzrk!r9zjiCXzPL8Qlhq+{V9rY^`q?T_dkHWD0{zKou>4 zD9f1@tyZ_hv~c1$8>`96r0Mmc&wejvkaawUv8f`hz~X4DH)SS1ojTEGlR5jecp67M zlNlTXGRmc{8g{SN-6Sg(MKhxxKtaAX780rdgRFn{YtrsY13L!6!bF0Ix}EyWUp*uV zWDC>bZ&mh!H8rM<3>u`?yh$kko%-~d^>y%T%HsH-AU^l@H8lllPzD)jM8MBMewqNV zL~_r-lbqe-pA`wDYMZAVaS8Z_vEshi8^@@I>OSd@@_gBBpDE?>a+aH&xAR1QnCv>vCqO|# z0p{PTnOwc>afLM0o#)=`6Upi6Vz0xX_1wzAP-JxbWG86@)(H`hzD|kh$L-_6pGl2) zet3$>u*=k{$OPul&FL9wZ$P)%qUcUr3wTzw!8Z}Z9qdAbKKA3c&fpe zj-tSe43T!O71z=wx))EPl15fV7D~0}&=rWx6CfHW9xOxy<2nW!!4L_iUtqL*)K&8~rL^R$|&5*PxsnW=k^;m~dm1w@g@Xt2I ze<=2`H1hp8*-XL>+R*`T&n_|t7jCG8)quZyJ&F7BPxR}aI?nNxJTqy8%;GsjIt- zoekH1X6Tx>f547@&$2Cz2l9?;O5~u26RGlOvf>D$8DQD7XrPhC?8cPh0w;}vcIjl7Ek|8$*fjTW;E>}r5>l_@8} zKR(_;idf$A`^T+zzoa z@X+e?ztu&m->zq2n0RRVhPW!+kI|g86H}FG6IS3WuY|ltxVx{euRAz_qK+X-2`K2U;~mB8TO8G5W{DaqtqjkdCZ zsdv6KWmz}AnBcXSy$xYxhIFd2-`zhK{x=vvS# zNv!n$CWdNDB?$%bgXUErH~bG-bXD&q1 z{b=O1uoV)g6KKM6LuJUGN#(}BLw!3R8sJA9@;7HzE!2UFg;b`|aPSm|K(?-QN;38( z+q8>kz#IJZ#um?k8Jj5wvRoGOf~u!Bz)2nR6{DZj)BXcTzMp$y~Gk*kunJyxU3^ zri*bhGZro>3{8%jlv9+V-?JMPl6)NWtCU$<5d&=6`5xx+Bt#$3=a>_zWcDJ zvzb1&qng#Pi3xnjavKBIOKRzkaE7aoLIN-WO&FGNKs%<3$smdZU#C4^iMp;WLvCpH zuX2gdWVNuGB7bhX6j5$=#y!5B^k`~w+zK7m9z-%FS&b9DhJ+hmzTCu)3t0)hr1&q7 zQC5&bnrxuKP}p3IHrT|%D_hc&UuT*ZL6w+_)8zAh&d^RMeoWIvNAYh?Rc$J@^$FT< zg5IdBY#aRFe;~=gL!#H7PQz;7!R^>t)Xn2GB|-c%>x=l}G5zxA-O539QIa3IH~M?v zb607x{g(}9mAomhqNgNzQ^Hq&ex$tn_Y&u}=l+7y0ks(J0|CZjHEczok#`i@BDB#n zpvwFH)3n|9lqDKY67t6iH)qlcSBfMO41Nzmi%m@+*3GT?s0UQ>p>(fqdp=AQS_d-s zK@WU1pQ=A~scOqLq^FuC?Srz7nwLX?ILLm9QoNw!Z?7+qVr-^B$|55r%h@$o>-5b} z5&hm_4WAE>(1_- z{rZKm;V6~ibM+UbdyQ2V18T!iL9qwTay3ippsboYM-l>nHQ}LuqV`5@um zZgH{ti-vn+#^$T&Z`s1He(Bm|z1<^L+#`3?4|h=1dV61P2bk67hAd~sL=??H5^HYy>D4vX3 zGzK!HCz`S+38siTb3I$Pc(b}+4gc#uI49?}>+r<;uauFnk)ue_(wzRr|sIq{P@_#dWBsRO%4PPn9qjDK~;NWXW#I zB1$VSBUswk$1bW}yFy!?QkNqsn~8-mT#R0Rzj6Ns?`_Eo-5ciw&PG+>Rr4sGUws>C z__&=D)sHD``&76#kUvH+iZrtO=*Y2XvQV>V-SHCJ{zC^)lrysjyqj9>0I4vbvAbTn zzbhyxpp}dIcKy;HmqzeQPf#OVQOdGzxo6wGQprn(Uoev%t{4NA!=B zuE{@It=6keMW~>0psnA@%T_KcgW;E(FmJ{t)^1}W=WjM66WTNrJG?Y#_TR65ADf<{ zMH?Xw6VayuZPxYmS%_Kk{*Sw%RID8HVaBX1FERE)*#^Evq(+ejBSE03X{b zDBv{zm2uSjtK0p$Ia@6IpM3G~4$iT^)n+;fm~d3!ihMLimXt{>o%fI$e$AXM{eKrY zAs`b_;I4tq9aF%-@UT|Vq(^hhx>?!md5S<*_8cd>d2(W$@jT~lyybVco|-g#0bACD z+HqpLibane^W!Tqj@Q^sr-@7xaesNK8q%$x{WDA5eM>i@Ut za%YAG(LKd9r#{phtct$tZ?Ag2OpR!;hO{kelhcJ%LnNwZiYKiyHY20Y6MHW%dc+ss z@s_za#NXxo(C*HBawj?BY%^Qacxv)E}66f>ySNH&&{I64?C$o zd9{Ld?>8=XKhaJG&wN`5%PyzgMp5l%S`Fgr#_AU2!Rl~j+JwA^?>tQ7G6R&io39yZ zH@R>^bzjuASU|l$AFikOCZzbtL;Sui9L)|YSxPACd==+8&9<-WKeqBz=a`sR$aIE6 zv~_hsX}$D%LF@p5fV^}MperDal!Z$ur0fyE`+yc2=^j|A~e3rz&f^n-rcoAjPetOD(P$?N5iion@vrM(%XwSwO)Lf-{+OB7S;5FC@28iL%qB5C8ICMu|@hpiC z^X<|3yx8pc?MJ{MA{Tv^lTEOqxqGjqa1t zrjd8#(%Cam^sgU`EA;JnNrIq5?*9cefv+YGc%>6hyKo7~gRt&gcsyK#Y9oLKW9p{{ z4F<;sabuy+ z*NNJdt#sx$xV=-G5u392#r`SXH#??pc2|thb!8#<*z2-*s&YFg(9{7nwZ zseW-&A0WAsJSg&rUcY{k(i8+Ww{$+ZLh1VRxWf@9kP|=8`8Zn*zZ)!r;AyNA3mQ68 zf{(D${({t^<6!P4j(J|}B7w`DzT0P+e5SW=lfr|Y$G?`2`nxKzHmAC|JdOL@8{j>j zd|g>_@?oe_Xb){=Yd1fI)$gH`dg65OiIGCY`4_J;{&SUd;VvP$H@tl`Fjfi~+$hya zK|x|b&-j$D4gtAk3b>ueqWF@ahl=NBeyFoN-MS@HySp~IaOxma%ZuMy_g4Q7(fh03 zg<_M6W`>9d`#i_YgjB%N+-|`ewv}a-RIw z_MO$>mtkR(zfW)~K0yxwATjgoJ%N+;K;`_W!#c`Y=M*5x;|{C4Yvq!k*u~t2ETufj^ncknc;qizrVr*ND2?UmW%0 zm1U5`p>+l2h$tljD=I(A7k3xWKH{Y2eY$+1&ix*uO1*-)bWYw=VM`j9QA#KYk%+WL zqWS`JS*7{a-X36?0_0I=i55Z7sstVCPN`bD`gCUO5hdSR-gm#51&nMa`%c$`yZ*k( zoHh=TwA@UbrUBiM`{(23mrG7#^{&|_DXRXQn}mL@i^=Wvf3XdY9}PE{v0}($c$cXe z9yHgc4sN2$uC_&I9}GmdG&`TD@wv56H^sw??;u54Cin{IcPlH#ED4w$oJsxQQKpG` zYTj-=WR}ivzBn&+YYvB7&AEDJib>j#coFmBrIZr8+ zWRM=ox^LbMoZAIAO3g|htd|gM6v}ZYWN7yXGC7oIb5mA+#cU%iT9%YzM>N^-icPHz ziXY?gg76JUgZo&*j1GNHio#=J_&uH)ySob!m*h2Rg&>%OOirVMr6jT22nh*C_EK%6 zA9a1hz?1oGnKI*FG5=e0++i?&XXBMbD89p14TebwLV-F5D)9v$x%_}15~{5jqVbW- zdRu5c5X$^V|CeE1QD(&F7*4w&|D-+w1OW>n!zd5#R#2DoSmF!D1_ypTqr#FBV`#u* z31MSG`dGgR`ra95z215!Jy%X!VTQ@8j~iX!?0VF*tg#M0>7J>t@4*2I0^s46uyq1} zLU4Nly_@~m6w-eoq9Q`gf_1i@r?kY_v=|%BdaqG`GO`vw^i4HDx%`%Pn>JwEn5?H{ z<{7-N{w5}s-A_+`^HoT?<5<0BNhPmS1GhMNbxQp4goO?|3Qjs}L>1hM*5z+Ng zd1G^sh71#gDyrSwte~Z-O_^1XWZ;Zg4Hhb>`@(x|H~W5jnsC}Ck}IT{!^EZrBLEn) zX%>M{Fa2+$?|^qB$X(Da3E}Ww3pcu>PVj z?zpkBvjec6DGb~_P*i~h=W!VW%E*lXuU!+$>)#;p>cNrV>qRGH5L80meM9N~ccLIx zL6@-R_`g9Ax&fc@GFG|ov?8~wv*yvK;8%@Jkmf{79o z>)i5A=r7YrF43FrWCTg#0#~&&UZ`|h3LKNTN5Zllt+Lec$wCYaIS3x2`yL-{o^v`> zmByOQ02wc`MD2-|t>e(nOANnwIy6`>Nh3PkGX$P3G;SJiMH;%%u4;|e`m6ke)nFx^#7)SYZQCm1FMR&4Bb^I5Xh5r8^9LK<+U<{bQX zMo6Yok;7cP3tjw$qNg-;zHam#6K;+^M>YmGC+CP=otl%5K}ZO6<+;jb_!~8R4JU8& zT3Ep69ZFtp}}-7228K|p&ycas(kQftYw=p+x8^tNo__T^9L)wA<>cO)!jiH`;kJ^E{rM|o+{T3K#b9Of86*D8kd zyC^$45DwCIOF@_;jSlbm!;7$a1Mb~2Zs+_qh1{y_o1d_b;`}_zEHz4}JdzMZO5Ub> zk@cY!Z&FzFLvkF5ob=s4_t`%O+Uix#6Ox({`zpKBEzOd&z6~UKEmQ@ml!RRK5>d_y z0*O*afckPyp|Df$$wuN?{f>%nx362_)Fv3iLxI|9gEBXDG{23OFrBT+RLrmUC!IB@ zErLSK5O2QQWdU9gbgo-8sjII)uz76dHls|rV|ka4q&#twim)3RzdJ45dL!b`0OFcqw;(bAS2uHH8?WQKwADC_~6V zFRfqiWUU~sKpoSXkcAv11gu^+KiC}ZdoEoAEk%baGZp6WF=tc=S0Y(I!;{X7mNIFm zQft@~rT`!T1kK0Wh|EJrD=RQ%BHAv&RsImXhh9=xH2h?6Ztuv;#DM`LAlIT~cNr$| zCU;ah;&^?gV0I<#;huSCIM8$x(k%C#NNMg<2WNqI{+A9kavFHw$a&!to)X=eK?47n zQF70Egd*+}>cpW8L(#jn_Dst6#AWBk#D7(^OtYj1NYEer5kd0R{MfPRv+j>ql;A%`k*Lw_s(w^t z<`B7o=eXbeAO&rv%QJ_-00`L3Ori)0~+eig8;DbWc^0l^Lv0{_6#M`*L zy92lLm>+`zz#M#biLk_Edj0*oVg~uRm~Q6Zbv(Yg88J$?Saf5elt{;ay>y^=oo>n(-5?q13^YRl#?SF>pZ0oKJ#Z z0f(w3*Ew4j4;g>jRr4yK5CW;gincEPu+wicj2O~GD^NAF=F=B2~(X5lYQ9Pp=-HeRQ_5EJ4$MAo-` z$Y0m?*+aSiqvf-6|GrYlE*UaX%$AZ^V%UvbJiwL=OAi;slbo=dKrS;dN)aGW;+_@f z*MX5~Xz;Hx*$kv-ytvrA8c<-)tnUmLT|ecWw!?=sQrW78H0HBau}6@Z7D-4x`;hr{2%e|@+jeD)%!p@-*!>`-WW0ys z7Nl`6+2qa(hS>M2;2(8hYzd61(-J4uf2mN* zRzQy|Be{-WEP828_U~V`=^2L0^msfNeIt5$Qgp7{Q()TBq~b+%rCop#T@b1rTOm zHjT9G=CkQW@nIQ>fH{y3MPqgk5P+D1Pw+$40xvw8qr}_w-4t+5eS9dqhrpnZKx7)0 zWvjiZ39R4&EJqCFYS~piR&*ceKGUb4H|1Jl%-Eze*;VRLx< z)|fRj9xrUcZp(8ow`yGc>if|y{p!f?#sUUnLj0s#S`^E6>9Cvcd&_d>#e!rd-LoeW)AfTOll?*5&QaV zdz<6=0t-OFfh#hDqo0hxlaj$llGt)bEPt;IKDwD1u|E%``f!}sZw9tGv5z3?pNSxC z^TH56VfitftSrlKq{)e?^A@ivY>z_b6TRVm{^DK zaQZ(NfZs?!E4od0M_@vs$m4VC^qRfp9={e{i@~IiKrjnbs;y>g@z2C!=7i~}N~$nd z>xN7icyP~!Uff*!Ho(4Qi=1f^ncE1Y_N_tupd@l?MTU>P%R~hTf0x55*#IJegYSqfOdZ+%lQ!v!Mc{(5%<(WpMi2Cy? zQ~?(?8xF{N^YioV?NU`UWMpLO_Q;dvr0HW9R6Pe|8Y6X^oe2P;uzF(ga%ngo&4MtI zW7upeEt-c>MagE-D>qsyyB_l$+h9ETcSA$6xr%9pIoB5^vrh$-yOpILo2799rC`Jx zu<2Fmp^ta$=&b9$C{2KJdmb@;I6bP0p0H4HZaO6Ldc8nziK0+C|3UpJ?aYq#Hc1b8hFs*`L`7U(x(HF|yhOY|$~8pGFgX?4h{pGt&H?5&VxlNFY2OaGf0Mn_PA@*_`6yg;c{k zGw}hjUF2JFF=GZJB3HH)Ck_3U} z8ydi*Oi4{mO;5MwB>^C_ZV4YNtw+Xp{dDb0fhZG={bc7N3_B%L5zgL*`t zSHo*El|-2DTopW)xT8GR{YOxMts5Ks2(6--MR3XzcTkiy2=*J_?^eBj>7B_fFt|QD z6&)ED5$?~oiTqf-7nZA<&nXL}tsBReAUjYDWM7HlbyME_q-?qzw7>iG^#YL8KH`wi zCvk=Na|(ucFnwCbMmO}0wX@OE2k>2~6?ug40$06TgkAl zK6PMGF0?yRMHMSEo~w0%b&c!Q*xQndAAW3 z%KhK_(@hm&(nl>|OO2HSRfE1C@8%YOcS3qqi6mh}4p?9#MlUagVF+V3BMS){V>-ye zSAz!mQ(o=;I@dc@#J`vf)@ih#Ct2*N3MBF^Pa;JQ!q;!H7j)T7wCVn%l+-iX^kY;w zbc4Qg$@}~4nCzApAlZ?N(_enwbSo}`I zRy~ZA)Dr-^6@xh5TQ9%foqPxJR?(Ml2w3O{Zb@ow>vY+bPNP57#A5^?_y8FMK+#oI zRa>k`eu}x=fQKhc{@59%OL^R;MmGekQaGP@I9Bl)!R|U)?V3%ewLnYELAnQw(7Cm~ zzUULGbE5yw`4&)>b<;>A9GFd{bgCL`LRCY5>t!foj&FVT9HJ}{9yZOGINs0Vm*7Kf zzUn!Q4d6$TV3#hf)~m^mk2v-V4W}+;o(4unlp8+C5c=$*M+5w)c>>LU zmF+#oonDAUZU`M%w_d&Kd2xr%xM6X{SUW@^!driCt}*Pwmn@KjjxU*vaO?mZKk6Wf z%=8tJB&6|?{W%XL`)oz)Tji$TTl$44d)yUFg$$~gA41D4FvHFl?=e@!6Rn7e+6>fcG_1qo+w0pSno^UBY zlZng02-udbno*~buh*BwrMn!lQ~(|9Svb+uRy3kNON>1nF<^zBwa@#(0`U&ZSVC!I~Dg zN>|g-@Rb^47miraWZ>*JxgT!*Y_m`G!JM}t3s&pg=@0M9-H)|b&g%t9d*@|$cf-KCS;l~!F*q=(}?eTpm*jgJg@ z@TEdp-T~>p{wU~Z=;*-B(RQx;NAlmlf7e6K8!7L%0D(JWlh~4X_{-9LiILB>$Wrt1 zln6b2Gv1mb`9RyNp(IGy^0=~z<2K2Sh4^-S&`PWB3pPkC( zky`8^>B2Y=AEo@>_md?5u64QhU!UOtLvp>P9O9c}4ZIs8GYHQ72q{43J@Qg`NBKg2 zH{xwVxAiNhmjbP$p#jR-A{>JV1zwM|d+FYkzQ=#_sbbTvYwKJT-z_5M6sP*T=l8r- z`b@PN;-=p5|JNNpZn=m=#|$*dOV=H){vwTmd)2a@ljf|_>EPnPFfA@xYhn-kP$fr6 zOiCd&W9;a7RMA7xVephf^rEQss_5&@8l%DVo`YafSO^4c&i1d>@DYbZ{iDyOM&$D%ICc=bQFaEY__!2T3-HbA|~h0J#aMRCjkmFhICS}fE6=*ga}?YpCftD}G=8{WQG@Xo+gH__ujd&;}bR;^M!rQ^fd>6WSU zTR;K%E_dx`Cyy@wE_g+$%XisybxX>#p1{8;9`jdv>v59NMQ}4>*)uXFZs;shIm)K> z4m2RA(e^@jTR4fEdEeAb<{>fh+_*h0)3NZ2!4RJE878d8)Y^K7G>RECNbW0VdDtm- zK0+R%UH7r6&Es*79($g}8{}B1r9-7XlS_Y4W6hfLw9#d$cJ>Sgpx`ypT^QkrjtMll z)6!tjNsXaIpq0oWHY1|1SIDK;#-Zn2*`8yQip*H`&Ip0No!Gj*29cf2-p zc6DNN6o7!&Uv zK95pICE!3~^ugqn#F2tHA&=pZOb4(#$A&5tfn?T{NSpI!eB&?@TBF6YYbUzOU25?ib5N@h_l7j2hg z;G!GOspMAW`uE*n36$I&_LA4NoJ~Zxq&|K*R38s~xKSbT_)-}4ATdJ~)3QbvkbolH z)S}xifQvV&3<9RfLLh}BW@74BJlYcP&^5VP5kbYEA^zAC6 z3~Udw>zO!UHu?N|&D>!$Cp!pzzcEFRLS1~!V115hkWjc+yXg)Rn-hb%_`WEa-;*vW z6MHVbzF+fPJi2=2Wk)jTw6f?a4nRK2%Ypmb>HF1wBkRecFUH~m%5w^&fXER+8qeKV z4-MdY9E5@UrY{GOS0Ti5nNS+c8>WMu{wJsF?&ir~Z0_d^vVDpkLoR=gdfk_62w8HF zU*BwsKhM?QyVl0`P?n-5^>O}?dD~I2ky-Cb3nlfYcKwXC+jRM_^~1^Evb%bOFnf1~ zs57s)pjAS5XWKt^@!M_oq%|In$u{=Up+}3+E`wC8{E2YL4~A4G?Q1#sG)@jCvw5Wx z?c^)xc#=UgIe^nyf3?WlVBTbPa&yUl{@gU|_T8wyGPpYNQ=(G)2xdHrdhYv7KMe5d5z1Gu3U}p~^cwfJcf|DUJ&S@#URG%08*DjO=1LZd;f6cJ6O|Z*0lX z^7c^ex)nB)5%2Brx?uvqH;s6eOqgCh2bz8~>_2U#(I45DHJ!hHC6^QWTKrZXAI+{* z5S)iRH2)zi}Xg z+p!6Xq*Ej=+EQg^rs1`zhbgDu7Fe*Np4u=TQ--Gw?;22;-l$GrV zFqX1(8|)H1?6iv>O&;3ah^=`v96ahWrnkr+N#=W##n7J*Y-UXv$xx9@ux_bXdi+`T zK2_G}w#lKC0uO~e%S6DZc3C@gYrS+qxAU1nd##!6{`1G?w7BzdneUeP{a@e9GT&1H z6@DXPf`>3$|=+BIBK)xae_0@gPh;=;Te-S%e9`Sl+?4! z%o!&Y2`0%NBLhy)Am7l^{QW(E;U;&I@?Iy%3KZB+<4Z!uqe5CNMG9xY{`eDvka*V`GUFprF9+LE%~ zMZCBJTR&mhpVS#7p|B7K5ChIu`2-TRYIATB*Mg@nFFRvXj{8tSR+=~srre92#D<>Y za}U|qym72Y_Vyid@qH`9IWOxDM8EB27t+gV-^VQ#|1MH`UKf0)oOv;O?qq*``07I+ z$zblfz>5?ArHc`C3a>5CXmXDYkVO9a__m||jvBHYqQKNOMi+l*ZpIwd-geAHZ&>t& zBYrHnW$ahp&GObi_Er1F)x`8vxr~nQub6{TpW_X4xJRekQl!`qParovKK-^STHGLr zC&AD^fB~Udf7|_AB(1?^e(!ZE!?>1u6$cP1H;sLKk9era-4$?-T$eu0n}Qy-AQh;z zqI*W+mjCodp4klZ+@K<}6Us{!;eMW6s~TOF1a({89*492C2_uoPi{yTIGwk9_P#wL ziwIcAn26Vs_&vhJ#c(TRz_dyS0;q+64h&H((e!lOPe*s*)V+96uxti$&me}s;uptR z{W?10<^T)X3_^8gXB#AX9Eij?Ithw{m@%+2J8S&+p-2Z-@b$y8L96rm`U_=%Y90er z)3a-@&U=~2mjcpq9{ADs-~gxI(qTL*n<{<33jPm=;!bVpg6=`tG45KL3Tr`3pSfnc zc9iZ7Z#tP!Tl;wBk%)e1IvdEUn~&nKb(pvQ6yCrV(PlcjD7LmstQfhb6bKh9oY3C` zK(te22e!3K$OKsBO-QCWpNYN(Qv_8GLZ~)XCqrmKpt8W%c&^|(&XiS+5`#&KIrpFY ztt}=K8&_9N;+K$RU;}^j0NMh4gxub}Ur%YgczP$f7Udkif&p1RAcDY5B4tfnU8l~y z!Fx=l!!hlUW{S~Z+$<3HuEX%0jt`VcmOrAs8DI6D*Zpkz&Qd1FE%R&J6(HKW(dn*Z z0LS=~#%N2$R8{R^&odyojRnH5jN|s)gS?xsm@avtw4m0WUp8$#M))MXr?$;ocZr z{a5;P;%)cDs={E+&vg};vxcLFpgS+=+9!*svVUc9G#HR%m3`Jm3glL0V!l0fvJfc@ z0WH{UB@cdidAZ;7!}mO78(@X~Z>|pKRd4<&JjL%Xhkb$n`+@gYu5KY5 z(8t>q@qR$S&?L)${P+N(5mtMmr>*$t10WK<_hB80))iOF3CLMr^}u&ixG~1yxhT&M z)o&Ym!%UT2MO*NRuF)u0RRrVyqItQL8|@e3{ALdNXuq z>xtuiKj+r^kD&FWO5FQ#nV+l^_DJ)sG+pOR%6;3XS#ipup@{&h#P{q%k{I&Hjvbq{ zh^{kKjL#BNis7h5SUkW`L5)fsnM;tof6l(X<-?A&hoA|k)K-l%g6}z^n)1KbC$4Mr zZiwjn>$6BZG)U`0H5t)P7gP#q<(L=mBa*~yIU8f@lUvtX`+R$6$3LBaWNmQ`sLQ#1 zGoZ$%rluc0eDLt_0O0@3g!tX6IC9%`%NZX8MnOSANg2H=nADFDTL4-MF)_g9w5~}p z(*a_rUT++7;haPPLCSCO+}$4A6Chx0P~)eSyW6TqseVyL|FJl%%cEDaZ=IXtEv_?g z4i|P8R(z?|t2&An@L1Yr&OAbaxo+NT^Vh#5@zZ62yOS1A`}wLJyo@MWCuOP%4yAFT zs?+7esuD(Xz46Jm=tq-pPC1BNs1KTnIbJb8dAh{2HZPj7s9$ZPBH5}ouK)7kAnj$# z7C7LWg`m~z^=jPArf1(4Co}HzBjG|*8$*yJ!itGMha+wGlSh9N$E^R1(2r(bK{K_ zQo?5+@UT)@j{2L?@gJ4``R!}HU%}pDGII0SUH*f@#6JaQRK1Qd&SYZL{-8{Z%JZH@ zJED&z+Y{gKhoj%&N@xF-3_yiE9>M4=sJ!2DUj1m1;v(MC9YG~lth0OuV$7|ZMf7-h zGIoPH<>O*wt#`>C&!39KJ?iJ0;q%hqd#?OnfmL{co!wRkFP+ZM#K@8lqsrVbDJ7>3 zj)B90PB$-JHuGyAfzn(B8AyZjXwK+0g_*=aB_|qN1f#ezz@=UWcK(RpRyCYY$?#Gz zINo|pP+?qMU2(GMlfNAP=P$f@U{fS zrw1^ovEdBz`@U~DoUobOSEQOg(*6j6$k&fLiTa-ZF#HVpIPTB8#1r4(F3J=C2aR?u zr6oTli2+Pt`m3RWQe1RTQCQcJ{r1d}-u@XlROh$XjsX&h1vq+hE!3idy(M&1qaWS@<)@nMIiQmzF<{E-%8eG>dWzAjE}5e4)4Vo}x_fecCgB|=+Ttk@lGR3v12tFK;_1U7vT zbUIo~c!3(Zu`SVsVmRfObgF&)Ov5oIhqCkhRxvk#)U;|QV^NP7GRY$)#{A7QN-A_^ zYt5yu)u$)#bKQdbjZ>;FHo?e-@HiJ_$3gDr zR&QTH-oBg>753*$ex88*eXaZR#GRU(-q%4UdI^kTVhw;*oc?!RR$25UqDOHobDLqU zWA!@(y7oK6d(lJjB!QGZz%P}xa8Hq$4w4DvibzzbOag!u^@W)G1gOU>Q(&X%5hy*> zWq6YBk(TILa8Y+?jlV$fC8sTRONRtuy4o4Bb_#SPRqe z;mOSA{I`H6CosnGVg2R4JRKS|K=6@>XN%vpEEpYZ0(y+!XWw{;W`ouvuG$>rpOA1knPMASxl| z!{_`dry-%u(w!9;`7QHS=fA_ix3lVl2`dJz2TuS=6&z};UG=hfbh>&!M2I4K!Sv39 zJ_pW5h}|L4`%*_dej5prTfq)g@Gb89>?qkLo~5mK6K}+?+MeItxIBCL{6N9Lj?NFt zjW_mWRhFr6@5hErq`Y(m9iHH$xwk^8=Ij|2Uj{>eGSeCuh00c;;YoDk5vGpvJlXp= z%&U?V*g#|}YOwVx()4ofc$CkafXsDnV}O123)1vRL(T?$09YeT3kvMcR_w{iSCqlo2+_5og;_pA5`!Ksz_`-*+&z_&X`V0^3~|>ex`Aps=jhZWp}fM z?|fiZEtrLE0oz%Cq&d?qfc-OG%@8V+B`<}wIezV~!>>f~cVwCGe__siCCmI~!DhW1 zL;j5CS>?-TwdOf6W*9{u^{XkV08@d~Nz><4GZF$M5(KJ`CQ^3v_76X%ULM4Jsj<+s zyZ@TMT|A)m%9X(#aaCXu@$(xoPjGBf_}%%x>BUy9+n<5D&?6P=bjaunBNE9@ z<~Jfd=B+-$*PYVFY?-vE{-ge6s3AsXp0xNn34y;j2UL{$In_sHmm5DhYuXZ`wb&(F zzY<{F9L7_#y!CN4Ztx)r;59H|FfYKw2+j*`v7mp$jq#E}xx{&^p`o-$VHGI9KG0*} zUbd8NOXkE!t>!~JD~p|lZN+9k=k$VD@DdJ?LqL_F$d{g_!~kRxW4y{5cv#-h zruPor1#)$$eo;FgSC6I?#im^*X|_OMhqp)TQ6DS3uRrOzFW59uXMsQVy?mdEEb;zI zZc-&oKe$Rc?hSFW7&j9_bTD@dlQ{Ek*J?abjvjlllaqjf@kXs*5cmuHrZ~? zX5gUE2Ghq89mw*1*m1pVJTL5@v-{Q2B4~GBAQf{Me|VAOZOL)F=FDxq<3Z{58<~uB zjf(T;Zt=DEKi|8!vO+>?X}S(oGqROYW9S0sCwXfnm^&;0>U|(^AC1tdiWU=l(WuHw zl#3N^UG!(Q1u;|LC22-ubr;TZt2!gsL`R1ynU5Qsf0jS$4C}9)4F<1MhAl`Ov8$TBTJH(c4qCowG*2by!?AAl$Zyp}8@;Gp&fuh>CTy8|){EFVC zJ%#xc65I4*Ybh==?)lBW8^0m62w{K>SSf};AB!u^76H4*}OfiBAJq6WUt^01K1A^O_0>rnL~ z4HxRq^1LN4V*1y?l!$<_pwE~&%ultxM>!F&&!o=@HGa}b3>mRy@%q$qI|#H4M%Oh) zJAdv@2u`(nE$%*aTu!C;t)y2HDHaf(+E`uUdSb8o`qri&1SV_;#=agPGKa@mKHJRo z4^4KjBGGR&x*l5CmOHm55XYkHlQ^@CPB0!z{IIIDv3@xqwaCp|{W4fBhzwP>-GnFj z)JjJHvyiTnvqase$uc!vg|mn48OzkzVGL|ezW)k*5W>M?h`w%eeJy!%>MQuruQ#SZ*}-5 zF28i1`;HpX=0&RWb^KYc#TRXQtl?AYYE|&kS;JDgPT@m2%CT>5I_UU>BZZh=v>csw zp{V}`1WbVj)>KtYY%Hi+qmf*x85rpVb)Bh0yr4Rx-zO!ufOI13Z?!~`@8T|0zxLgX zJ@|%u30_F2aZt?TwX>Ax7|AQ>Kd_~0G=IN>QtOP}{Do|h(DvSO5?c18XlS96?{Haj z!aoJU3W>#5&&ItpjHT>!P03c(zj=AWe2o}*llgEJ=~#7f>9Ag4ehA6E`!aendAB!8 zxbtaQi%XLqr$qIAMsO1UEVuCiqYbuVmcaFT_L2YjJiq_$zH@a7-{D{+EnRLOOMw0JjTV=3PXE@IaT z+eMIb6bT2-GRed8xJazJsmFcGWn%3PFj4`t6%AymXMe}X5IDdp_R_(tR}n6 z?$$fGA~!`-zMXygVbz7H1;HI-6Sr#%1Cymytn%FGa8XXCVsr_Pl%XJw%koFow)gj2 z@2s3X81DbIsfI_?on;rYDpY?^pPW9q74f4i$!$PFYoK-^%;B_jv?ROuq+OF&K ziB86qSiSRFn|_a&4Lhr0VLw-s(fDzC+!j79#%3xBf`YGO%a zW}>p8^eA?cSxui=SC*G46YkbrI1zI-i7{$0T3(V~SG`Fd4dJ{2{_kPi9@;Nqw$?lX zoA>!FoBSQG;Ki1^%~WU-g4sD~X#k|_H&NBdru;Itb^^%G*d3?xLQ7z841eghdDYLh zI6!V|8x>U$0C}j_%iyfvJtO+vON9<=$~%=rxaU#1SY(W$SxO3DpX}ZJO7%}pHz}xP zCU7*SCt*lIw9xh=BJ+3GTc74Nq<*53EhUqLaT8P~-|ku4jVC9>3aUTq#%Dn;<#%kL z5n1Z(9bI4v%Kqb+w_Z-|_f^~b$PRJ!pk$lUCt=!xFq*cKY2+zkwEy?r=1-MkyxA9D z{ufhP?sf$n0xa7;XC+BYJ^nNSoZzu@k&@jR7Q1@F zFo|E@EWxj%eo31ze&R^4O5Eq5)Mc~{bffm?h3m$=LyscQdT?eIVK)xMQrtz;kE*5IFx;6u$~ z9uwQ|sxRogslMk#bu8?)34A_ZzTAwiU#Rfk5-SN0g%u(-g+C!IbnhI3HbH5Y-g5*t zBFgWFhC$7GL5D~Xob<%1|JtGG?8>r>$8|T8|4H*O?z$K6g-7LCWzj$hh21z7mhZEe zV$mmI7I}tZ{Fz>kq9Uo>wgvv8awuL{FJvi#xyrEccKQ8w%>B1wksZ`O-zsiAv`W^c z)$Z^XQcL@+w$mU+8=@3s!t`MD?^1?N#f;oyj+!Z1@n7S-txKh0=ki_U_X9#9&~c}x z<7donl-2JdvL6pZ{T%((CFTbsAX@T zi+TQ6$R1?20qpo@SYz zNKs=GOitLEijbAtY2qyb*_-r(V{3f_D*ThBV{`-X)pKftOZw(4rIKKpA6peqes$o=DMFzmmNh@qU2F}QrA z;L=VI%HvM3{lJvHwRYpVt>;_$Mwf9C`D_XIQs%eqNsWA2_RDPkpH+3L(P5HtbjGxb zuLq_!on|P^xk!`?878efbzAEouApzu`c1F@No@zB<1P~VU8&eLF{HS0NdYrj_H$C; z(LZ*>l^RwXt7licXA2MI%XXTpD3m-GD>M}KqQajj66xm)eNc_`xN*EZ*|7KB)0wy7 zOC8i}cG;P!)KMXsmR($m%H8@Y0*!2V@goWiGDbq#=SXP|nlIVdC=5T#%E(aVf3nr5 zU9X+2T2)#3iup;O3Jme98JX-)FPn9zb7yg+=nXR|_c-Z&V9sW}NhBz3C#4{_{OK~+ zM&O9;joqgv7PK9N67D|?i^R%`jBL66q9WOKxVTGhkPMtNYNr4xkFy(N|GoOCJ7gvP zNg^ZAk#^dM;2o`JxDr8c<@&jBd`dRe<)$axJe@0R>JMA+2040e~p|EL9bx;!zZy+Rn=xzc)p>hO`8%}TK-d1Yr6dXvL zkH10E6Cf;!zwd{)s=LVRYjf@7<6CR~id%g?gxZfkfJD@TB)Df{9>1o9nVYH^EODu( z`(>DCUuQm(*Qq%FKE}9d!oVKUH>_c7pW)DqcESd+FT8T z`yiq!-G#*?W#u#HFttYk`&$vMJIhmo?d?YZN?$oYzj1^FAVFHaQ z^&2MQjNQ#uu_|qWvTaY$cObRAxpWZ05lSO>Ck+dd+#I(0g|5nFiP$rgE%lf4`=O)s zXXak34Y)V>mfuP3Ax3a{B;Y0#SLzF29cU2~K3*{UlFBoUQ3$YarKiMh(sM!Y^)F&K zwbjdhpWl^mY0@&+U4;!Ptp@+sh2c zweTTy70f4d%gdr;_=oLyv!8btnc!S+e0Tm)<$5m>_PPfFt$AWrIHMRKiOK zmxjFI%}?gag`($hHgoIEkv$ly%jiee7x%(t7JF3q@;kROGWYI0_byZHcF%;toIWAU zl)ILpj^d_Cw?w0sOI$ouh%LT#NejR6tPcf zuOX0tukF#2-{XAy+t)>Ru2AyT5fyfEkI zP~BQj<)Or)^Lc-2DBU^3XsEcy|9r6n(YsgeWCJbWz4>la=yfwqx&r8e20y2)+ccaRlYRSNM2Hj+5}G)nAz zvg5*8OcCC3&F(k)8Qhi}HE+ZOwh>g8Oy6(KmG-L5|C*5tQ{U$-=x9pcd!xvBuA*T_ z+PZgqLCT4z(-@t=g{j5`z2E)?c(eZeqNWN_udpq#%MC`gK z+wQ99?w5Jr^b_JtCD7Dp{;}sZiyEt%+&CGf^K7i$~ z)Z|sf4(fE(yHBx>td?>d!=LsTd}=nb;WU(`z`(00&yYA|v)FKST|Ss#RmbCV#rTjw zLE&j6U-`EbA}%81gP-5J5$vryXtSEuM?cGc{&X0y`=RSEb=*J|N;AQmAxk!ztI$>x z=j-#6c7lTh-7q&U7;-wd7AvODmddNBqo*gbYEW&%R}r%YD&QokK54HgcbauAO3K;d ztZi0E6L<)@ReaR)66+)xzoS9>cG>D+ zGfd}LvWh(h^g$_A(ECvGfjw)`Kp;M2fb{9uqes6W_Y+<|J*~6Mz{bWNNAWFFpWv}| zcCH2er|{b~{0MR}0ctYk*xJmDBc;*s1Pz5d+^7_9HS-WQAn~0;c*Oi6cq?t~p5EwxF*teDwcqpSAD8>Pzp z^P!A!FByM+`iFV4ygHH-RpZ5j*u6UgM3;5NwEa&O-_N_BZCoCF6Y?+#DvjeAQD(@= zl^5YpmCMM;gE65AaIDinL>`BdAJZNAvRzELOtt4aJZ=8F4f9#ykKx3~t9l9R@^pG^ zs9yG2Y8G)Jqe<)!|A$<0gQ5~ouO-iq1*hwxJ1hH213z6fQd08OOGb~^XJ)kwGaaNj z3JSV^H{|;7fTF>tn$naLm5)rM$%cjGMb;JRrM+r*6m<4uF`^*Xf4j{O$|$rghx$t3 zp^nMl_snU%YCaghISjv0G?$p(*w!_j6p+ZC`+&DG4ce6Rf~sVr=fE|tc1ME@pf)8*OhjawED29Gr$NSO zYja%ANLmWGS{EfK4u-&X^xDaGUsm}G_&NTk+rPiosEJC#RaD&f6f56Ii@hTa)8>_? zr|T2uEv^+F{Tt>hj>-|F4zJj2&Ip%`_MlCcd)e4K8QpLoc}C1$ye3m7b1FQ_@xet< zuTpb5wp5RN^)W1dSq8=`7o+?9(vJyOZ<1qSPiIKfd3fuZ{%FDK0N@?bh>WCYGa8ST z80lf28kggXklP#GtETxW_1-#{)&__S(0w0M{m$L}`ODwEe)(&Br|$waPDn95aNA-fJ2uG>?WUHAyG zq#+kaCjkrtWjlQZd9b2cyD|;)p2FntW2q@K6Y~2^#d~1Q@;7EQMx~;+yZVD!H`6Xm zP?gZh+w(=UkGW^l0q+yyFr#5dLGN717~@nSDFWqDtfZT^Q1OoW`JK2Tb)MomUD1d9 zU0t@uwzek+!A7K2dxz%!=z7WpP&bVVbw-7^%`f5{Zyn016QQp*^NI8goZHVqjCwSRA?$z47e+P+h6wkv$8pO z77X}(A#+4d&;a8i!nlez)r8}bM2u74>aM(J>R7)kebwU@^Qt@3(MT=rXE!31o~Bnc zSW`1zaFf3c24sf!145|G86eqsrk$6j|D7vrbr?8^^NOGhI}G+&86dEP%gsWaXU8Gqbhx47gyln<{!Co^tE5aca@^P&&DaG`qgl!TW z1Yj*PX)uLH_m){yY%?nv2(dH>CE-@nq@#bE>mK-)@~cG9u&=kgtlkYxc-zO(LXtM^ zL?0As9q98K4;XSjUsc;`52k&XH6%kDiwjg!_%dsAaur3yQga61rXW8nkh1fN%g}(c zT{VLSALkk7QJnt6F2|I=!{LpLUo2yJimW`kw$e-U5k2zMcUk5V?Gt?ncgrQ8#9wtb ziVJ|?eA({epb7;9*y3T~QD7+Sp8Q5fw>9sso0;#CmjrkjVB9{`$anCBpVB@gXkVXB zFgP}$c}tD-W4(=tyouwtLRKoCPvV}Bq%>+GqLhAJu*z)D-lbvEE>0=M&R6Hibu`Dl z%4iPz_245m&|@xxN>~vIpfy*ME>FTr+1(1vEU;Y4&5Z4FlvSMJB1qMpw&EpMfn)cT z_8*K-r6F0dfX)t%)=v)1+C~L0SQn*|UH=Y3a&KMzx>2^ne0< zG3L`%&3J6$bUi7P8zwhrJm%9k!cBD>%ewCN_ATdfNHY+$A^YK#JEecL^|{P{mt&_n zZ6vLFsKh`lFdHHyyIRBqjx7;4w-~Z%^vO0^y{ng>-yMZ_&X$+{sie<&7kR@?gv5*Fl$hSgBm4G75Evr|itcUX0uncE z-SSJ%U#SW4n%(_boBylUFF7HOj_M#B7hK0L{#^efBVK9%Q%3Q8!xP_%j6d~Na$_@x z{SgtB#6)^TM}!H$|A-8+N-IADtw3BUtF5GhXuf*xX_AJ;W{dhpl(@lno3QfFtMstH zkKv<++~0xWfT-ENjlZB^+lt#-LvG5G$d~zLoI{^Pm2||s|6bl)T{UZq0KOAJ7I}dW z!vBih?;!UUImzB$91jfw&Nzkjh&KK9b}%MwyTMtzccbcGlkXEFiVTdZ&1J@)=TJTg zehz8XK3RFo(&1Wh^Kn(47XzIruDRH+ldjuiz~dd)<*ww_{?}|}@-PO>P$fto>I=-y zZXDmC*qK1$xiLETRrzh9o6ohk8`g_RKx>aJGwmiD!^)z!HiE$30+LPeWgpCJ!= z&l(oKto_7*Y`;LfCFZr)+>1JzVt(bDlAhvQFMbUG#;?8F+ z%8eR#Xca=klgtO?P`f~?-x*wW7Ol7oLdgh@-?h`}zsFB;i_g6b?Zs(e1PjTVS8_=u zrP#nl%pJA2u^B6{l=rb3GVnoEFm*!$jEfn1;IzwBkW|M^z?%?5ji<7ISN-HU9_>PS5IhXn8h%K~ycbt&46(Z$*q z&Ro&Kb9BbbrT_5HSg+`___rR~O@C)ov#|KkEwZxI6cX)N@k9YTSgpy+0)>2ADph&7!$sSW=Pi~SOd|CXI=0eOfPVew#E zWSW9r=IEkz~gE{M<5M`gyLgg2D_RljLD^0>zDSC%9~*Bnr>zD=CXL{M!_PnF6d%*yi!m@T2xbOARRpu` zY%gXTGMd$fCA8N*Fdczp# zK)Lx+^iV2FoB?@!HK*>Y5L3h5^_#>GX)fk@bf7Ca+d>qwo_K}Ls8-VZsjjGiW_`@3 zfAHnqvz3*bOl7%TJ1>}if0Z%q1aG|J_Erf|b@qU6hO)A$g8WK>kSN3jA4vc3W)%n_ zzlg{ay_i|w{U(JWBuH7%vx^ps%lJu^-LKw-kEo~fMg=}Li$z5KoR4V7RtYV4OH~D% zyZu30@wMgi`6yA@_+X}vE9yIut(g{0lE=;j@K^F#zw4)W z4g7U|+?$*_Rd4!hxK^eR_TZBVWxtE~1%NU)8<) zR{`&lMK%c$W6`Ov*g(8{dJnf165)THYq#vtxaR&W{aICO{f;Nf^z2MPFeW|8(ywcL zEBh7Zjuu`0=hITq)|e%R5Ma_R3uIq5MH!c1r`W!``De`gA`_RcQmvwMUuF>+5&`B@ zDR^d+)4bK+>(sRGsn7GbXlG{I#q`FnxVRY9-PWwILg+G^)_JjQ_CPuv-&;+FK>6){ z$`+~CYb%D*WfapBMuKCkH+vsB=D+$>F>RHtx5A=7pEt9tZD0Tj8A)O?ZcGpU{Q(ti{ni!L+YDDyIzc-!BwJ!dbuNJ4hzHW zj!F(o4$1~+PM(n3|e`Ah+TwcGqY50#IU#M-jYL)n0jzBOrMgkv8d$)O-R>&_T=wt-P&* z1?wB5`OkYLD)=PS;m1Cjs^Uqfg_E-GQQr3FQ@-J(fg5q9IqRz6h!K!uxM|Vz zvs4ANjs;nTFR54*A4~q5js|K7<8%qUlP_56n*er4<}jBtSNfEz2#%B)pQ4%`Lp~F4 zZ(3_5o(wFAN1~ag(pj-SjEdVE=HI;2?%sIyTMl72j$H^$XOho*gkb_gDHk_HmnFr7 z%-F6pklTL%8{vIUH#Nav4Fe-%qy>Qcy}es>*+7+gy;=L^R)D4h;7!dqCSSG8B4bk^ zX3MkvsHMu9H0IqZmuI8eqDAaD7RTd!DfGb z^pn~DtG3Q_Z^Dk!KDdeP@r2}NQQ}Tt??Fh}s`kw?>L~$$uW!6E1DJN1<{J)(7?n!h zydxg zrUfN@n}_h#Rk4ZF10{FBd@SdRAwPb9g&DoTQud23Cv4xT5jtDO1Sg`krocAFqNwQE ze;+wz;M$kU&;PRn`PIX=ep5IL`@xdw&O27qc8*jpKQ>pZA*IZWE0bM>9|~poe^g1> zTd}7!a&;_~lJExG(UB4971cG5D+lMCdu~R2X?2uLA>Ky8-;{A*X>;~94A2+-W%SDo zCCf0Q2vZl7k6UM#Wphcvb+)2Qr_3b0mhaD(KCm5i!0`fq910SK7C!f7u+ACMNr~~~ z^o~=YXY?^ItNE(i-gM}-&FZa7SnNh?EGm-N?8Cqf)W?IUHPlmPu!JF3j7W<|Vu|xE zUWw#o-G}GU>?|9-8+t1LI#IhxM84@|TEVH+KM(;wMFh>0*2Q8Uw3x#Pl?bQ{t#!_m z+P=i*Ku=B~!*}nT9_Uwitu*O)9_ia!4pw?4pkb-769=*x(ZcGQvJe2xJek++CCm_K z)DA#~ewQR=0We0J)4!&{6*pRBoru-S&Oq?8t+3X-Wo-c{Yb)-*uu;IP|8(N`C)(K# zMaSP~d$af&T+f*-ca@bH*@p^U6zN)h4@#khyMscDhpSE-*8KAPv)S(%Dd-#nXDj8^ z+mpDuv1=o#g;KpuVcC4~LMW#~;GLgd38Tz!d{|ZLf7vR#EsUdd14K{p|T=IfF z!Hi%?=P_x}4x`i`;+Q^Bh99M=s?hkdsK}(_Zj;sNOHfNz^@%EHyUn+RrqzA`B)0oj z_!uua`b54dTb!yc%NvI;_;?9ko&cQKXEbLBgtnS9o}sWV<66g3Q|b^IuT0ukUbtGbt$R9949Iz5}sc2f@IXLa5hnA`-3 zP?MbnlLZeqK18VVB_l&3*&Pk*f-{MjtaC8ybG3LPH+Olp=Dl@fOHPg&$CviPQ2+TQ zb(K0W{rzhW(Gp1Mx%GOx;aMD~^H~Tfb7y5G`Vy|<2;O%)2cSWj9}PxeAg98y%$_QH zwxX1qHeZb;#uR$a)+=Vc*`>RO@es(88e3{)sTL~(VWc_>eaH_Jt{s=FIXA=e=2q=W zh9X@Z9cRj|IX6ot-!*r?4TLmtJ_F&lUH~G zbBgJB!8}~1CN_9EQZQoW=g+6KS-ofh?L`Ap5f;9_*%1>vE)0n&8!q-+Fx*C&vm5wfe#a&pGYW?W6GMY3nHXFX9a?QMf_ zM8pM)i;)MR#x+ba57*c8(hit#&D&`5GHGBOf(-i-Y8&sW8i0Y!$}>+B__$D3E9s#^ zJ_KzSus1`SoVP~49N|$8-TkTPxWMo~?NjzUtI5OCBRZxxdW|&^l8(wOZwG|@*+J33 z`QaODD(t`<;ywwYcWmY&-n59TogtTAo-c(|oirdQd26ag6sHLa?7e3Jy575m8v=od zoKhoiM*Tn^m3E&?r)u}YQBERT!IQZZZFV;bt!OQ`Mad`cvN>_q-;xRW7C-y@rq)FH9$kIT|U~;q-v?fC~3a@5~ z9*rKyR?xV;CeHH^?!;zamQN2MwfG_Nu}``Lf(FKL3uH23geC3`?pcp`pO?>SRy=!Y zKu8o%69_F_WL0EcugvxG+K-Hc_s*zbpmI<`%?~XCG;hgX|36_31uZ%u5Q69_6%;_p zP1m{=r>`&1+`5%YGv(giBhbj!|I(5ZT3HUqudKay?1b)Kr z=A=2|k|H7lHC6Z!-*vAd`{4^SV}xjiY2bpd1^>H1pG)E+B-5TcGZj%dO=CaH`Q%lz zJNO>Zb9XK#unO1Y#n!cH8m&OQ@LV#IFmBCg_Z_WiR;FCLC!bJmBhh1)ZIm-Utx4v% z;7&(zR8;Vi*ZgQIvTe=55fNwv+^-l6oQ6|bE||QHdTTEVcZK79@HH!Gun4Bw8+T1e7h^F`uB}*aVv68i*V=<^!EY-JsQ72gJelg=YSxTyqcd^ zADQ8Sk+O?+a!BH#>II@g?}y4qiIq%CzlnQa-xaH;1 zNJFFc=?n{q5GO5t-mD!EU43Bll;)Pk*ct@l-zb{`I;W|v9#M#09YkvA$A(kinPHPI za*oP+%XjYRugJ(7GXcYgIACCxpOBZZp?&$cPF=|f{??PXE?sSH8@B4cVut;c)SAWt zOK%jSb28-oHWkk1n+jD7NYU*HIytyEw@6|RzP;~R{US1>l#+6|Z(gg*wt`caXBgVM0q7gtfNoSJ2#OL0#wCvCBlU@ja1UYgutH>MxH|Td)k}k0MOk+c$l@%TADT zri<}@KZc@VywWqi{bN1q3m#Ss0An)CGc>o!j^KELZbe<9Z z_PZ}>vU6?AWysL~+~A=ro`*&W@JGsi&4;bNB`4$Bwv~h-3PEViHfP*=L~536AlkN3 z+cf{lau=Vm%P^WWKngTq-AAxdc9w3@JU_-LH+BpDcgwf)L_bKTm9B^6+BL7VYFsV* znlECdhh(_I$P?KkI6fbe>^>R)XM?EMd}Li;Uv|`F*n$m*zg!~iI0gl$mS9){>Q6~b zcz<}dF>W7+UL@Gt2^!qhogN4!$3+6z1u-XuIj%*Ls$x9GZ=*J3@_~PJGdJgzQXx*I zB^Azq2SmElVuOYS`8qW<GD?#`{=(3PPeo@Tch=9opV|ZW{~bU94!u z-%mNsXumP58IaZj4I}2yC6Y2V?UF{fbWm^?t#SA91&;U~c_ii2<=dnP_3PN2!*R%e z_V~2YFG3QvpPupJaOtGaTB#>d2-kgY&G%HM*8n{a* zKZ`bIMAM}g0fHPQ0Li`nLe~0xQvV1H`0us8tp=@yY53y+`U_A}uW5UnTpjfB2(haW z8nsz7r%imZ9Dg^y0O7+vkt3Zy4{^bD=8L`ElAb zfZ%Vc9G39Tme0F}{WBeiKr+i4Fg+DL_c;4$!ezX(V6;+vo9fQNZ~yGiAj%kj7z>8P zjiUe)1O*bXHWhvR=i|P(eXjSY!KED_4$933W0*aZWNR{_dD{(ktZX@Q_3HqxA$t~3 z(Y^O7nr-CiWQyMfaY(5tI?e=cKp+p!3)$9d%P(5{Q#YyKv>}%c;697nN1voQBvC&x z6hKSJ79V)>4DB`Lgm=)7iJmga)s4`h3hbT2GI!w|tIBJO7K#f~$o8`bS;6on<#FU1 zl;a=tE4k5d6FP6Fuhed!R*?8B2KIHg7ZG!uXhsZEk(AiUN?Kt8@%4Zqb(o&6KCmyV z9Czir&xoX<4Gba(Xy=K0fw|d1seMNhaOxw=SF`pzr{e^ij|U-u1jQLtd7m&c|>TTT7Wetcg?E>jgQUTN21s zKV+Ro@fd>uOp1yN4-65YWY|wUWgK@K?HUUG@GkC9l_-`6#=yP#*Lmm7W3HwU$E@nF z58p)`^F27NM-EGXcokdf8%6Pm?S*=Ls6QA1A}(h5IIqxQi>>Uy$Vz&)v`N;gC?`ZI zS0vH%*u;xG!5gn@|6+qAUcwC4) z@wrM*KZOqnj^xltVm^w&yitOjwuuf%j3FP~|2H}+k^E-B%S@V(^a9hDzveJ$^K~Wt zeYlPX%7zqX>TnOV+LI zjXbEMx~8!G$4DO;ex!8A%fHI$C5jXM0Bm~jar>r_w_a=ot-=rGqz83ggA$6*02F_t zPHSnUm5lN0;yD}JnHLG(uL~!ri`YNliGbgo@B~@H$KMaI$#lf{)4zJq@@8{V^w2E% z>QF5UEd)VuK2~kfSlj_~0Rrig;ROM0r)V)32RI7c>JS&0E$oKGX+G#=h4VQS&dae>=@5AO$cfG1#9 z^ibA@!@{BE)KRt;%A-$nv*pV)oYHrRlJUsHd6xS{7M9-^-=TII?keB~9hTfb#vz$j zm~=8u11~*+60AHF+%>}1W?+z-rON!wKJ;|UDP@dmm!g(-s$qfaD+4)Pz>i?d# zN@FrvaGuwNp*@~CNRnB_V9+B9Ej$M9+>jQn=`MbwrFM78PKQuuCK`t--oFxvCP5V} z-TgO*1wO^2mp2>d36ZW8Cy6M<2`R9`kC)$8R$3%6pDc@X8N9&aq;xMR1)n`Jx0eF_Ho}T`e!|3&^{xK8TR#$KhFiioT8r$rBOFY!*n& zdX*_M{|rKk8oU0#lNB5@U0xomJ6VQK$eM12Qk@iJ%SaqFPFByIk>Xm`p);;aN=pl~ z;IaiUiqD$DA$)|ZjxU+!%OeMTvAiPW7!x`QsXjUkNlKrcy|I`$Vp42rrJd>b>wa1- zAAAc^ijHmbzwsRijs8LPtllQc9>b=d@#ATK=#nUq6;7l@wMiWtLX#m~`{FN%2V6Ey zrE@M$^u(yeb;mDEz6&G`P%+f~`Ui*LQB)7zh`-7(JmxK1>e0#V`L9>5k5Wd!RSJO3 zYH7KOrIEktZO0g~`{5p?--G?OhelRZ@cBatSyyxdlU>@}seAsBK&qg|=bl6JZh?l7 zQ5aPQ1qsB^gG^0rvTASB$umE+;HS!$uS;dVf3G)ZrYh>R4myyCPWK~ zlaTqP`>{r%YDEsYXXhSQp36avD_)NG>~%WWpa4q6SC+KGgjSgu&Z- z;KuoKd!<@aI!1>A+RMJ``=PqWQv6Ajwh@$tbmUQIn4l}M?#Nd_NRo;*ooq0&B2QsN z4;TR^`~zvZNLObt8$fc?HF z|GgOS5+b${vtkALaemnU8xU%=K)*kCK9)i8M1z{_g?vAtjD}5;s!|78AZKRk%RXE# zlc?WW4hIP&{+MlsyDF#G$zz( zrAyCxx`W^|Gs>Hl0Mub0GG$N;D~h@}%N~-9tAL!!s$+49bvXR~-XogM9!zQSA70|U zwu8)d;E@n^XQ*Kcs<%wWQw1FH;J<_t&?`E+2_H}RT-Aquu(im5D(Ya;Hf`-SP9DU9 z8env{d=Qr^NPzFStc4_;6SH^r`i*}j8d*kK ze;P>A)6Y^I-Z&^Ms#u7XF&Mg?M(o!aj&|)Rpth-?T&W2|RqljF{&A20ci+S*6o{SL zKEfL2J{g+9r0p!q1l=>p-!?-fq3&MjBd?=&-`VI5k$j3`R0X%#thU(FBHFLc=ZBVM z_zFDm^ns!HsmV7z5Z?x$F=-~x#baI=k3?88S;iP|-gK%lSr1c41gli7OCHv{ z#NUSF3zJookpV^*tJ54xiH5xSuwsJH>v^vbd~J0DRR%K#7#fzG&eaa*HTKp?380x* zy6=$4N};2IVa@;F45t&RMM`%vICzXG78oh&&COIv%+cSP3jA%1P(m;}nL5^}RRpVqzmF4yA#{6HjISV8e>W84>f85JBgNy0hWBzlg7A}72 z7p=?Xdu@eHCv1h+4KNu|9;<26Ug5+2eP&VlE~?hT+!eO>7=|iwG(c<-Jl!l9vY8s z?Mk5|59-#(VKCZR{qnDI5mj53Rk?>CW4*qr|7Jr1nR_Ke9sww9V6*_=_#s##WxIsm z9{1`KRJ?ZvH6#P^ih^!^K@o3>k{V7yQU-YM++4YJqOhv69>=m;J+>r8{>6nM` zsi2mr&)I+e#|0o^(-j^IYPnC&0ut8XX(Gjs`uDj!JW|HwU;my30R*2qUHZ#pXX_Fo z2(6L%SztJh)H>1CW!V$}N%|NGn?fYMSV|%c(xgIQvF+>Qx4*I>q>kY_4kZ7Pv-?pd zEX}|14`+K5r6-6VcoOOhb76{g6G7q4GflT-Y|U)FYQ2eSAO>NOrbN*&ej@jznG$~c z(c@GH5)k%)7y943eEl7+5i92Py2XR`Mb1RH;dI(>gay!vKbXnF7 zmz(827tezT#6xp?+goq><9Uc|hPJ3t9JHW?MFEF9ciYH#x?>DHp0DuQR%Qt}MG_@vkA-2Yz+cP4u!4=fGpsMd?>xx_eFqRKTkvQQB5H$Sl*j#C?tulI__+Do&6GOI@!DRuQ z^k4~*e>F3uDpS+uKh%}46kpR^PW0F1;d=Ca2)|`@^CG7;-kBtOX1pW8bQ_0pwL=x- z6%W{+0N&91A^ajc1Dv1TCoNKjj$?0LO;1HIJ+!PNC;RN0f%4HHZyrH~&i34RN%U6W2t?^>Rr71`eI>~t^Lmh6WQ zoeDBWPe*Qi@1lv9aQxMLe$jg{(MO>)j*DUaHa7dA#DXe{^1vA2dw~r#wNR|+#qmv? zN~+Y$QuIYe-b`{c%g@4n@l?WB9AP00-G-+bC;=#-jsO@B5(CGCrCa6r-02^jrH~AK z>qo^C2zleo!>X6{BLgh2t!1p}^f%Ad@a|$@pKf|g$dZ!3dk7(Yokns$AC68IyMr|h zc?zY_^vPlogS4!X7z!`^m}AL)5bjm`XV2vux$@h-jt70x(0Cdhl43rmR{;zmMcB8W zaUIWb-otPAezbiC^ryJseNeG!!>LLC=w9!4#vG>dA!DoWKy16?QH`)p8d7Mq-x-%$Rji`N2Y)^zUodEyMRIv-Grth~Cd#qV!?1hg?MyxX%u%`ZOxA#^ zBf9X)eaOdqk3;IZQrp9Q@tL5+%#5P1mh|A4Q0KC7?c{WUhQcb+P^OT#JdbNDXTR^a zU*?=MrlUoMHw}Eg`3~v)B5=BoyH0~Ik`X{Wog7SRhXN7Df0Z)(#{RZPCW=~Eiwj38 zPIfLbbm$^B$NTq0S&3JhJBRvBXGeqA-l(0=R{XP~8xQLPe9@aL9e4YoEe2{cN)~8j z5!H#&)i@@c94lf$dX_D1p(pqNBon9ZO&fYHdfU(%?LP6Y@fO|}Z6w0qs;Yb95LMj& z{5b`0?_RX2QHX^LHjDu#ZD^%XCyv9PbFnP;d9N}b`3O*NKW5|_e0BJp-oWqb?e_A^ zSKqJHa6HL6DO6NndATx6tzAsWl{{0IYURyxTV`Y9%(6lI@xjJkV*|*tAbH9y_-v0ergz)zNGm?8ZT{4>@ml=bzx~M+5 zcrH)Twjf0+H*~Xn65VL$TTOmZ*%-#!C}O_o9CHE%X2}>efh0#Q(T|p%PDFa*tx)gM zXkE;bzy709%x~}@51!2)O!@{bg~?}M_vFV)^I>M1DiI&YbsRAaNpXL^_HuECKBWQp zjf({7PyLqbv&y6ARX$$6x1aTGK=79eRaRR^*UHUUJ};2dzcevn+f<1t{t}JYdXoh;_VX zwWC7;knIDbO&T2C6~zC?(^tkt`2}sSfUroobPEeh3ew%Mbcd8mmvn=)bhm(XHzFks z(%sz+($Wp@?f-e6_s7Tmz`4(vGjq)~*UUi>PFU9|uTo+9)a0?rT;a1@-bB7iZ!7Vk zK*91IJ6BR>4f^C%WP|a}#f{bLYf|7wwE3LGyPkMEwCU_$w$@;=CAEwtF@{E!iuc)X zj%(4>eWRGzSJNhrG`o5Vm1-k+O%hIl`NB7YFq;(i&zF4p=KHbf>cv0Wo~KATsN2Hc z#K@$)Ud6@I$9^~Wq|Dph%+h+YcnX2Jb=!);bvu-x_2waUbMGV9cZFn^fhv#MMHWvn z`sdYylh!u(Qeml$Y#41!T(oNr80V;|Nver_d0mHd!^f$9wDOpuqzbBm-61Z}Xv-nv zRj(@_KQk{`Uh$IMQY?!Jkok;BZ&6shl7E*Z^^a8#-b8t7k|S?vbFlp4VVzr}?Z6Oq z;^pJ$TwJemW+7@7aWT}j6i!R-v$xeiusf2G$(zo?H2Bj=L5hsWY3xI$_uux%MTzTY zvy+jWMcH%2N}tshg8LD#7X+N*} z3a}rNv|$72sqI(|yM53@*q0*kB>LH5>xrye6pK0lJ50KAgMw#M@0!C~u!DZ8V(6U; ze*6uy!ece%xbYJ0fx)~|Lf!ippx-L*-AG|XFHYSOX=ynZO7Q^*+oK}uO8Ib)LnZ9x zbWVQ~&ra=Eom@#GkKc0I9mOsz;PL4Bfw|K`6e?Ln@ir`K+bIn*2TCE8psEt{-KSNP-}90?)-FG(a{&PHI1Y{QczkTRx(O>7+OJ<-;w;)4h-4`w7_Lkay(UGk^Uk`Ku{FXRhBg}JRFr;dH&n~SSzjEf02?Q+V`2| z>F4vnx!^7e3IFnlyG$Z&Vu3BA&~eq=a#SOY)Ti9i_Rr3h3#$YO7!cU{SF@{CugCT% zhzgxb-BLdVINxc$t&(Wm#`|rL^eCIv-c`Mu-q#)|D_V*R+$LO69=hVlAxQ}J41guD zB_unMR1hp&&)0aSbsgQ0h+}nhTjipGK=ceOm{qP2bhro*x6(rL`mPfTguXaDpUzmQ z_p@Y8m9VEda0<+>T$2=L5?Sr91Obr*sX6gLn|8Kq@HG@J9-GUBpZ$&Os1L~~ zg3e@YrJ;fLr`ZlBEC>V&`_pF+XgL zOCFBetNR)_>Q|6&0htk=EVZ@7gSbed;OXz>tH&)jg%uBdHdS8`SD1TjTkda0#80ZY z@kPPQa!&XW*k@KAZ9SV5uT(n3oSb_P!UJDw$Kicf4r4VXn#q~0Tlk1^rIWj&wQr(P z9|C!FcpCR<^zkP!%GVua-P1bcsB+if4`iKBbs2l~8RX+mq8YGY$w}y8j=NzO9~^Ti zyb^B5H43AbK!TDgfmFivu6&xVSMMWGslHuMyZ{X#a0_@IN$dSS|BApwy^Sq3at=H! z1AL($gPaFT7u!pnm63s2Fw&avg-{8a83G^9FJ?4r>8rY# zD<5?iPLcDMPgx_8hlY`k8_mMVHRf`XFVy8Xi9yWO@DsIh{^<)@HMjc-p z$+;Zla}{j$i3+9;RMx%rkYPua3dNc83g|L>WN}L^v`wG7&P9ue(L^|E6&QMWOx)zR z+aV1gPy(-w@s>vMtQ}=PL-PIgNjt^Ax;riH+p4lY#!fc$CcK4PV|OQ^pVV|`qP@ZJ z^~%}v_NiGaOEkG=C1vBVm?#61p>mECivYZOjy zXwB(7x?O$EBjx%gp529m+5GH8342AUGDUFfl5S9cJ4KH1ENQD2EMd0BVl+d7;Vy1} z+@bO^C!01^4tT%&j+{nv2SGRPGkYBo>d2AR%7^sKMI9_-nch9VkCCKb4m(@g}9qf2EQmmY^&K#xhZf>Do#?*{A8xnk2dGsW~zg zu=P7`kQm)lK#s?Eu#+U9eYQWl>MAHC2E?*PWZ`5qGe=_w91pga&_}h&j1MS>gY=QR z5z3^@(K7wW*ºnES}-d#SwudkG{Evly;gSYK6mOrQprMjh=n@Ej-Knp5&1Sq|0 zE_Dsd)&k_dU?BPOjgP_Oh3t5(`!eHWhE;~pbs2wtTYrRM^H#g^9T)XQacP(+fhujoyKp5Fp|7>x!zAAioc6D~4LuYrxzaT2} z;O^`#IOKt_^1Pl;-dOfS95X{#?_qE}S~&T!r+~eNcmEwn{i=Z1t;6oxS9=ItLgwPw zjamYqdYl~drc*#+h&CT=5J6^|I=BxzJ*5xH>0-fy$NOlubs4kpmt#gvs>zyr4ivkC z@1Z5x438Bc@35bwo?h>wBs6SBxkHN!L7q#?5(M>Ga2$`K+X}RIx`?8{dI0K19 zUzyo{`A7fAN!H*lELrs4`@)>%nxHP)sc7~(1%>4vqb}C@U(fT4aS1pPtOe>&b@eEZ zimK6*@qKn=kh1mwJ!Twf;Nbb!{(k!qU*HPypgL0=PhJM{%c;}#3WNkQ_`$-ea9@9c$znRCDfaG5Q}VXD+oiRU)>R4M3zc}}2ZG8;cuN$FmFniY2> z@~cOtT`51+Ftvs3p2BVHu)j71ax)1@=auE%&79_T1g z9cA#Le8hF+<74Dg=`x0m8n1lfdt4I}vvcNS&zt!Pr?o%l+IX@W{!h=F;XZc!zynN4 ziQ&+<1G$miM5}jC%(%EFsggu8%Ix&Y8**oMNm1bxFzh&^jn`sevN`rT_u^Gyvhc;U zpkp1Q7Kz|V+L{FFh*MD<1NsT?v_gtx=#Kek@J)D`flBmRyy|Hanw8x9;`a1Sfvo*xf5!~ za^D=KD)su@{T+O{Lc9A0L7E}~Sz^7kyZ2p1uu<|9N*tvucs?ws<9pR-a87`7KuM07 zIcGK@RcQv9O4pp^`0iwD7@Gl@}m&1g0nUZ=`_-r;O(UTfV@G`=ZOUo=3)Q718C0%7Br(ZltE~uH4?snV#t{>5qRh zXT9VmJVO3;xZ|CN*Ox~_XJV7w$iE7+_a%N6iUOY){YWHCd`kB^Dye7eRRh3^TI7}U z^sRuw96+iCicvavVM{?g-~mB`!mz$@);OAdE|CgJxsXI0)OJEn9k=32KJzY*KR;X4 z6ZE<`?~k27;uPgoiIj4eLsB-0TfNs|cP(glnzt@zb>#bnu9|a(l%CT4RF(@^2l==0dFaf`F5xz|NLi z|NVS-yE>bC$cg_UwR}fRe9>>6k7ckhZ1OKdua! z!-FIV*5E9X=soy?i>vyLV-|ZQ?Djlwi0LjT6nzUKn!1VHw`rnOg`@3s!lz^hK%(Gm zw<#*3JALIUQR#iw-p432_j-mu?T8?A^}WsiT^1=+n@@~+D3>Bc()hE5rE}q3d_Xat+$x@0WJ^)HUKEhT9j+m%3KYoVbRp#lLQjluUbO{1@BC zee&D#NuV5T&wp&mJ+Hba60#DkgwW^+oOgbR3&~-1fKxArl*4cH-+5>P&abFxfeq8o zcedB>&h)DuKW z0hm^pNcPK2U1F6jX;?iGs^X1?aI%N7VFOKRZtt{Pe(_}2-kUF)$F}eK!mBp($lL(26HnqqmuMVT%zpvTH<#haO#&ox%f^~^OxO8wD6Mtg%JutD^e>I*aVdXF z28an&M=;Dj_L`OOT+B);L|ImW5Vgu_3g^xA3MiVuyCf= z8tUEpEFBL`7>hqTshXwfVtUXDpOI~P@%#_7?>Ag^s$8W!SW|P4+ViXU9J&YrL;-X? z330Lw*ZYr3sNpaMBXb91`4nS$n3Da^5N46zklg@$^#`}ukf3|wG zWRhf#3fyn2i^s3>Zxo$0hpxLgRvbO5jG;6( zH|43%8DT`a`((q6ZqmHVnTHcZB~d7o=>A?xPjKNQW+;M$lXvfZJPLQ>L+XmOayCmf zK56Fr(O-O*kC#1PB^^sY*^XBiEs^+g%j#cPW{hD0WI z7NJ#7sPT3^p4ApsbWHA9`PW0~4ep)gFolKe<^?DW+EHMyqwAyWqY0GQ+s{3 z*W-fd8W1uRdn5KWGwN|aJ}@+03&{n8Vw8o=E~5MQzE)7X^rK$jOHuXy`*>1P|M3jZ z*C|Di_ET&A_q_uJb*S@?F$JEVc<0+bM%dq-BzjFczCEFT0V;yMjPQq{wEq>*o56~y ztgMtvdiTv85BMI%k{-i4LV4}i9>wJ+!|a+KBn!k=imClUkbPj1qnFw8^ktwAaT}9t zhb%0wAf!6EVQTK`ga2p?r_->BJ!Jrr%o>mqpin@xOafhGU~?!sph%c>?$!BusvNQ+_mcCKm0VKP=Bqnd-GqFTXJq=J0Da|cOp8@zj4P-5 zEL;`h*FO3~%3-dPf|vt0W1h`)l>%uQCzbq^gj7TN5m<^$&oXZUaP)LrRW!(twBi*Qi`Ah0W`A`gYOTf|NxSkmkl;iTQVSeC%=Uj_ z>R9Xgh^PwwY9_Il>(%dq>?bh!H#XV`{fNu7A3Zx^wtiy<6+P43VMnH^%T|`9pZRV# z)Vg8q1Uq%P&QItUhquIx$iWDc}bL&6gDQt?2(1zXVn-MQ_Y zc@>X_a$D*(ei&vI{?4sGni+QfDYZ9h>(1)Kc31gpvz`b(e;L~{PHlH9&K6DurjelG zbcL^U-)adEMLw7di2K2Cs98FaCyYNtdRfE6n_4|(^tdELHsE#vswGha{e&1oEV!xk z?~Pq06&7xmylDM%NI*5F|3kS&;dF~G9dp$+MeZX04{pFOla$l^WT_{<2<~pbxG52Rb?d#+oZ_9hzWHue*a>c^=o$x>?7~vJl$+31RaXwguli85l zR6F+g-#Mm_&OZ~>-7 zM)ncaRN}c@P$oeH@%+l| z7M;Q-Y+8QtpZS`EZStg!AFf?AGnx*i&S9c-5RafVoI5>KoU9Ul@+whI1|!OXXx~zm zpiA;_c8TJUAKHFZIX!!y8kfz~r!wk0^`-IsjVBT)P5Os@j4@KzrglbJ8r`3ingV&b z3c{`n z0+=;TTiF9#BKO=>D62-Vg>2YG|InlD41pn>{&HVLNF@L_%s40AOs{{e>-p`(ihB4m zkGQ976d!A{D)F;=mBPNw`!N9dW45v0zVDZmcN*1>M+*xU!8YNOdOHfRGKcmt7E!*y zt`|uoE6y5Me8)h+O)*GnWkP+@f+t7_7BW9AU}D7wj24_cK6V|MtP~b6YbNDBHF;^S z{PB@|gizsrgO|`P#;#5JY6kUl;sq$f7+^Fw3DMl==Qc{GvIU4$i5Gd!yvzK>u+G2n z#_1>$PPVPmLDMQaLe@g|XWqq@D@W)#%Cf4av&SnQX$=yG8PyxcG8h0CHep~N)8emB z@sF&}!tR1WAsFn8uF5v9TCs?gcJjC!cqpfVh?&C?k4_s`vSZAj8T$=?78_+1Pky$C z*;cCDEfVOVc2W8`KhHKZezUWtXanb{ga#O%nq?u2LoHyNS&>)AcJW(RUe^cMREBCJ zj(r8XQ0W-FD*nDLSolmMoEA3%E36-`Zf@Zbli*DcCLcrHE~<>K`Bl6ZZ=$MM@bqPE z4G`}1Q8)rKHvc6}Me3#eD|$-NLTBz<{<)~xT0FQI^TWRk-yK3&Wztr49=mfZgueUa z)&8Pj(%7BfQ7iv}Ojan@(o$Wp7uh=a1b!YKNYl1;(k3(YpSNQ9&eM`%LNCS!ManLM z;8Bal1SG@YfysH&Pv+7zVVV&yp}skyNcXt|lG2m`<_rjN_cZre7+-QG;W-CV1-a%M zI02NR1yB_gcB-ke82^z}-{`6#)j6{MIIyjX^EfVTN*-JC87nm%9a}bfyc+^cr< zGCmwz(Lp+44fW!~w&f2G>%*go1tC3t6olFBjWgMaKloDL9;uo7?*$$^A_sg-F0SR_ zBU!X4dsjHU$C47sC`A`ZS0yh)feV)O!-8T*1i5sGisH}sd5gvhR{s43(+{A}C!|7V zcXL$=Ac{CWo0$-PpUs;kB7fkG+YhPmU*#)@qD z!muK3HRP;mOUhn$7s;cOb|&)S#;N`mo3!PdN1Zg_oWpun0 z9Sm*Px(TPfem*;v+FT?FCO?c0s>{vZU}P*U{P4CdgXsQn@5Y@+dB67XE0%-Z-70DG z%%@adW8*2Jkzc?Y0G5|&BZe${z{yYAqnFxb;K|a9RaJ{ZUqQp^g0sLeaze&kA9@d-~IHHW$ zXZeWo>DrM)t0=dOzYA`X+Y(waW-aTJwa87`7v=P5gh(=N*!f_bFyp`<=NppJIUyyY zF>Z7)U6ME+Vmtx4e1Lc%#0t|6I_^ry_pQfE{AjA!+vQK;k@Gs#rk3Xjx3~4?#Wp*N z(n|!8Z>L>+{O124lVaQ)tFuL)tL{-7MuqYKmjF_Ld(Q@3qFjq*e!_@txhIG7_0<{B zJMiwva3Y!alb*ulNrq2DTXAR6q~`vI3c^iNGi0(e@C8@B;NpSfB8jL9-AYu;?;LFH zvv5!O;%a3?wePEsh{|G>!Z~Hg)IRDo0Sp1yvh>{vJ+6-ygHsNVie_npapprfN)Fi} z%ETc9xfy?JF;gdpR8xu+7fJ5h3FBL6ja}XvO<)VgjpybHINaYCYD~vtf$R`Skwk$= zt6ox`RJsA6V$v(VTcHD%HrX!*mW9AoZm~ZoPU11g?^|UEX$V$@Ve7 z5m>Fei9q*gDZlpcpUpTT{Yk|1bF?qa;BWEW%&Z49UwKp(T~^mlOnWl$CUwVtA}_1C zzcOD#>(8Nk2l_SO>Fn5|G3vH4i&i)u=aOuyub~Z5}wQ;{2a&zyc~AD zQsc_>d6$>M8io}t<4tS`1^Et9U?L1)Ljw$w4|`vLO5Rfp`TV^Z8KtrDs&0kEJ1QW` zSX4CtmBN?W+FbwY;far_&rhX#LJK;P1x~0;c=$&Ag|;<(DQOtP8og-gh!q#Qe~Os& zKg7uTVVSa=2amQsdL&Q;;O0nI`7VQCam(pNQ3hBKT!pWg~M3$qt&^MJ)d zAT@so6lY2JEg|98(fIUnkHQPLuOwlv3kfu(g60$qqql}DF{Ix%L?MBcvi1*I2?Zr4 z#5gj;x-!N!`tV|%vm9h`!rD_5$%F}%4CV4r>z@wv=Z1Cy@igPOoSXroIGtW`;@(jg z&Hb!`u<_DwZ2eDVK;Ifc*MEkaQhXVRk}-c>aJ-_Ea@I}B>x~y~Up+oCIX1In(L6IV zyEvsXCh-QYvDIH2=ySh4THw-5Io_o>_xtCO>EhcXGhJa1ub=s)Bl}a1d~-Tmm_}Bt z$y04OVhM1+XhW9bdp_A>vCu}^1p3GITLNy%?C700bi~JOqI8!*)OzqJ*)9vZb$*;C zA~2891+;f}Z^bj925Zv?blIjq{Ts4@wi`c-CnZLS!2H)`0-vDqQ25p}r( zWlDD6F9mBQsbeQ=d^X-GcrrZM8eX*A3ND_(Zl6o{lU6=&~UaAZ~#$}2Fb=kxyQb@+?xC&^48^DxY{{k z@*xzcU!})L*2UxC9Pwr%Sg&3UXlN}&No)AGZt)Mt>k47P=k@GFaWI%>-1hc@-ApjrH^PMPM0gq_dYzd8ZvDo1W>jmmCOmt6rc011ueY+G1T@b7~d4C$y3_Lqb|x zb#RG(lfgOjs%ATjzqOO2^+Uh-avP@Sl`WkK9a6F5T;mv*-T6+*rG!_)0_AE~O(4Ja zF)+Ah>)hWxtSwzmDx{O5Rp5sWm{vXgd627c$&8joVD8dz8IN|rbMWr*f2N~3-hBMYX4y+M?5 zag))WxBpS9(zG7!Cg4w5%gkuPaut}*t2cEtb~#0YfnLpz`?>B1jY?4*IP1`xPaIoG z0E$8tuu)81+)GX*5d%R0^?`Kf|K*(?2@^38?Kzzm&g;LluEGl;f7zhgZ3BHj3oTOK zaXL3IUk}xd2w1Xf%P#(<#KrIua6B=?shbfOp#LNq5M@#^)%0w4!~MhQf_u?28&&$W z68(dv{amD}O6*JRV>`|?2dV%s+DjW_1 zfkppmPeoqF;N8ZWT~$a5KN)^mAi<#LMG}RGaq@LWj|x4Htkp&}npTf!E$F<~j@_-( zc=~*HKyto`rOnt+jLvxQYg%BI)oywDUTk(=Qi{pgFCi>ya*rpS2pEx`+fq=Nee^|^ zO3bOh?rQ$fKL(P%dTJvf{%UxySeK_c%PPpkN4}Vql{z$e+<0G7*T*xS>@8gmTmDm# z=P1q!xIaz|H9H|^De=ZT-Y*pa*|a#mIS zvh|x$hhj~8v_9cm>5zU;h@x-g)#`k={C`vS>V> zD*JRdN4|7hT1k@0EdPp{7}BYKIF%aoq4B9V$$M^cZbZLeD;ibWXo`eyU&m+C@Wgii zVX=w)*~yfH@f(eCB5r)Y3;YTRUYfD3h5YT$nKAG6YiFK<4w<*K1-t%XdAZ7w`87jDn7HqXFC>?nw&q#qU zal$ywc(gfrDjBSZo|p}$4cEhtre2xFfbm8nuixCHz%!>4Yz=$fP~t+vSP@^cfpCKs zmkXZqn{%L$f2|D4KL7~?l-*M4d4DAMWKfZIUhP`NqSdv#le371?Pwo8sS%)B3e!zDDVlAqps+D_ZqO3 zX)qDS17~wU;&*@Lq`&j07lIcRjgqEt?O*;87UFp9bnC>ry!x3Zu#8VLlgs+O56%>< z(%YrnnEFaA8WKvc=4AT`O)^B)4^j{!8lumL(})cztjobiT>NAy@AGl9Ttm%BqWBWt z-^(AnQ+cmH0cUunz`K2nnCVWLww@Y83WL*&AyLWG`(ufv+|<4nF(D*s*mkM=_K5>& zgMyccgrv!7PqkPR*av+AD2x>C@$wHX_s$zZExkSy4s@};Z0=7df1YzoZ2^@`)%P-; zxg#|=eZH{A#Wv1riF!i8Yxf}QpFAmtoB+i@rQvjY4tCNMjvp%5F}n?n=Tsj>$f%ww?`!*?i_ByL#OSEO%(vb1 z<#UqK|FQ>q;14Uzyo&$ra?^Ijn6EV3)7QO>5DAAcwDx4tKc|vYeXNlhBROW%X^|IT z2{sBpy8Qmb?5TwUadIKjO#dbi&t|OtjD~KWqxqlLZ2djdAYXCP&#xkSs}D~ZlQjQr z1K{`9#W%c34DaS?^o``lm}Yzj3LJkoF6|Qd6(~QT>gNjj^_kYfW_z-Ug-@B zxgCCB)`|32v%PT{y)XQuOp7F73y>DeLHO3i#}aQQ$O8e*C zE?|C*shy`|#Y}QBcZrVy_AS~zE1^Le7@5WG`egqoqOnbL@k3r35>;1`iL{pB=<(5M zX<-`d3%_F1pQrOYM#&aBSw@~#fg0E1&{EoH*1cq69JBFiIwGu&rf8)FZVDnd!7c6T z>)DA6k;V05s$!pR6ffC$Q!_IxF@e$DgMfuq2TOz3ug@eRy^2DiI#EF)|HTsC&@Rf& z12l4l=qLB9_Kqk`<*kog0=xSJQOt~%+k@W#!otF zZdR_gW-MY&b(Xtzn#lV$E-2aQo|$T?W^b2xr(LILX=%^AO+jH)oLAYy=HM<-5p94} z%d3Tgvdro7u~>KJb)UCR)7uCijXC2UTiB4HIEA*3Gc7I_e=Rd4%|G4d&t~v*<{8yq^7!WFBm{LQe_U&5Xmc%oDp^ctT?Tclk!fhBzo5eT^PwKkpM}OG#40qm5m$se6r%9vQJTa8e7R6N)zbzKdwF zDRX2+_JRl5T2j2`GVEW$XHH2Y;V9<$X<-sb2bPk_uLB+$(37k=7T<9>w@x`IufWMEBd`uJ(HBJ^fl(zzMIc)LO+dyIu^fkl_yY?V<5R&WuMoIh^?uZQ zW9?2^B~tZLltqj$@u2kc({lE%kKHXNph!(~ej}qEpUA>f<%!)6&wM3b9bVVWGh*2sR zkG@#3ql%!4MxqzN7DE5W?tNY8;o2AFE!_6^I~`kxSCZ=Z)yM#dszsh$^crnuXYnkq zl`5n!B(-n!fPk{ZNQC+;F_E%C4Fs?YX+@xr{_azw z`u=+W$vB6CRcy_7XF9r8qm~KJ-5pSoSO{JDNk%wpymp7GnXfr^@iO7l*0d_`Uzv7RoiNJpV(^qoXn(@)|p;T`qV)(>r zVyOyBIP{?L{B2d>+0fPqn0CN$@hW(~ttx0o(AO1~r21YwaSiS(&M5_|x<>n5u1H}U`wtM}71FVp^ z%hI8=AB*!hGry;~J(!(mo0yQ}6VXIkb(5Rx_}ZA@ulant<$bIt$py}Pl;t!d`_DFt zvyHk$2_u$WW=UEIS_N6kYPESOq+UUxGBIFdAJXr4CB!SdD0q^~)R=%R_uv$SE@DkU%jrxhqB$Ldt@@bc=`xPH<~3rz3T37AD>5$cj2ElLtj6QjU09N6RnoWvlsenIR&9b9szb=o55EnT4?)o zR@dsFWp2*i$LLg=VE^ar)6Q>4fP9#`K}5h5rKjcyF5uB8&)EHv5!^yqB;8L;1ejG^ zh6pvi&i?_T`*>i?lxl@oE;2GQme^P%Iw*#~ljC9hrd(;4+-v(w$1WF6LidfV zhyBe|*0S-m12I5Us5aKr-d#>yu$>IL`9>L}mXB~Zj`}<=q3thMelJ5*DE#4i5pDZ! zcLgtJ#Q4jPmXqlfG{H-opz#YM1k4v$G4a0pgv#wxEgQdoLx58qPz(6ykbj@fAGzFY zqk;MeWDL<$?Dg~%Wt0~UVvWWMFh2aIy|p> zULG%9>1bg)km4+!SUlKfc-_}NnUx{4_vnxZQPQ7X^lS|0)7!$5PmiYwnKX4gRt}q% z-p~56Dy~q)uZ(RJ)$U&`#wB0Ivi@As|8x-ju32Dg>GK3h&GS!?GS5FNe>2smo}7EU zTb(`}J6rwD${G>Tzq51JO~`I6K5Z9Ks*w-aC_q!@QrDzFw)%b_D1|e;fNqWNA8MX& za_^82-)MC5CUmlZ`JIARd7nGb3WMJLO6S@eFsdVu4bT&4zU2Va&tZIG6)>enrwJ`Z^K2G^hr+n)^s8wM|eeXU~R&)pJV`&^=n0B#Db(}_@~MnC1-GwuvpAD4qnf$^-kazW|H@iU9vHQ}~9ro#EKfi;yE+9J_Y&BAB}&0 z_&Ye786~{!#ZkxImdX@GexY}}Y_{^J#F9R#@wMz{7W_9KQiwlzq_7g@^>5U#*zeS? zptWEePkH1)Oxo+NPKR3bh6UHCPyd$kpckMGr>_b*))r<*cB2Q0NZ;m$sQ$rnFx4)8P%alNE4z}JJZ#BQ{1 z)&~xU=TXSzqeo8MsB?@T8E^(MIBHsEyq+R6&Jl;x`7|`~MIix@{Hf~A$5dOP_>eez zrF&VA=j##O6We21G+jWWZFJS{LwtYf&XI7*08}Sa1qoVRpCkwqKCn_CIK<@IqzYzi zhZ8X8`g7N$EKgW|5sp5q%isMXv|1U&usnJ$zzp^SG;^n0f(I`^7`z7moCpQKGuykV z4iM-}8X9KiakRQ}(^R36iQJVeCNsmlPFOHve(N&Y?PGtGZffR*h5ubD75coqy%$>k zzUrjhi>y=kv(V+t_qT;43zNj@@W4M(YObrPjZJS}(ak#`G^Smy9((Lew+^yU6yy}G zUSkJ}PZ5A_RnH!QC#Ni!`~8JHHYB>gH3z&=Z`gW*IAn=*^Sk_8*BVQIV$olIT)>}Y z3bnGgR>J78bDU=Cu6`e^JEHkf1g!iab+0}-yF7MOtS%or7;2JOy^EYj5rU?;@P`v6 zji05jgjb}sF6mduAd60+Hia)*0;)+b$5VUtSWID`mieo)rfa~dAr2P~P)i|ib^P9I zJkX)mXd^xg5Bs>~CcXV_48S)XrNqkAajD{N%sA@JM*kfwW}aeCAl66FKdd-bb>8@Y zS^#WWze;I!d=oJ+HF^)$U@(=&2x#{L=dpxmed%oS+3`u)bac`}? zb{%QCvFZg~AQiLNm~}p1+?{vzP}ZWJmPb?)-w*IYnT3$ z6i<~YNT!EzSG_a%5wHx?)osV}Wk5b8Pfl(Jsa|pWRlC@=2ankGEHwgpJX$&F>u?!j zV(%D;bk}_uUU0HyE#ygvkG*J!1n7=EeYSU?H5ky*G;`2UC-C?*wJfDO8U@J@(Qyva zE_KYfzBM!m-D(Upf*d z#CDiL#2QxBT7Bx{eK{CNcCs!CiKzTO**5QdTsxWc;Zr08saOELQ!6qNjm&I>!&RX| z__04dy2Egaxl7ED!*Y-?CbqY_Yy>}05L)y`nF_H)!2*fpi`@PTD>XGWdVFLK3w`}D zeU_o&VT%V%V>!7&*S7m*RY3O})6REt&wTCu*yeLveOms$4HC+rDj)lW^%v;^s?5gI zyKIzkb}In0czUe1HQw!{`j2X(7dS8m%jBDBB|>cJD6qt^_-4ld@!PEKLEB*!kLo5t zw${zl*+pB!ZMZELzL7%^YE!Y5`{woiyXR^%-IFrQamPl4RYYZ3LZj-HDeXn4)`rp* z^Dm9H*drXiylup$oR5ZUb4a3pj*qu*eS!8nT{MtHPV29e<70_$T4%^2k{050P0QJm z;)gC$XZ^2lDJVv4>d155f2wz`#D4|2_yV`vqYvlND?SdwuvYPFhV=`U*vS?wQ(AqFU!oL-(*qrASfLL9M5)29q|MBjgF zR221M8ri~F#Caf@1i?P0UiE0#k^g;r;TV7|{oDJ_zfSE+y_4k(^mcOMXq$ZrN+Zp8 zqF#G+I9{K-LlCs#mWqhMWKYs*s;IkcoA%ijvy2uk96jNa^D_cS)8!AldOWMnF8tW& z@EaF1aZMws1%oHMwZR74r?d9moE*|8a225|@BUMFx8^FT`^xXVK|w_%hc33V$ql#c zYs1pg)1DzgCB`(5C_L$x)2vw*WVU^DpzU`|#2qHfM*o5u2TRD)SoLS8S6&NKe6`dJ z4{rc55^45U|I9+g4mlY=a1lGe+S9~zs@YkDHq)&ty<*sdGtai1VLqMA-VBK7VM)268z7K}zeiXFp z|K)J)hlI+3fI2n<@OS9h54Ieju^MBJfWf;RpEu9eYyaX0a-XRHmU-waP+x93OB?VU zEE@Uqb@QbDKaX_TYL;;zbilEg9JaV(6rnw|5P_dM9(P5rl2|Z9u#!%Cd$C7#yS7q< z*-|`X=(9aF7Cq8pmz}FO`d+LGorgh8ng<^huT@yu#2>(v!)_VmL=7(iPr&y@V371- zze2IUzn+S!PPPRfBoa9H%BJGjEtmIXn5Baz%JSE2iW71Kt5{9D@x9G6`)b=o%Ca%j z^^YPc&K9ocXq-AJ4byMpizVpXu1{CpnwdwW=9RM!jJS0g^fHMz(m$t4i;ygwBbIG~ zxdTL;{Qw+UyGE_f$)_u)4k)&lqUde{q>p;N|{T~7WNjL_2O*ry9l*^4DU29@ZP9;tcEY|F8x3T`>C_b#3HE7)$IoB zkRjTleJ%O#1KUfBN;X~U04P`#_yV*=mc1pt{7Nh6sMuA{;o4=kRuxVyL6cBWJ5+=m z5c5Il&BL%iGfkZa8#0j6q$5vW&SdyJmahVvAc}+(Qq_!u3TSHa#LAOz9A2?5^v%gG8WOTIri~M+`iPM>ghl-^&;WDFaFzJ;=i(Y(~7!C;JzH zHpTua{H|j5kCrDs08f_PbEOlWyD$(aBI!qIE7h5=E3pk=f6zbF&!85`%vXw21Ahs^ zO_?+kEk?)n*SwA^Fr#E?V^z?R>q*=q# zQR96BgeM?N`U7i-{}zsVFUS|0lP!i2p+xku^{(uVOVcN>BqQT3{C{QnKqGGL)Wcf* zbZGA;tJtL^T5##LUe4w3nWku)Cqs7*#?X6VOOpoj*PrfZE1qwH33Oewk03}dWLPDF zc%;3lOO0e(ARt-B@4T48m|0ctPfAA_)?Ml_(9uPi&_P+?GMYg^#OtkT6xC}Kk#71{ zv-_3;C>CSSc7B}-BaDcd)W7pyWq&?8U-im;mbDd6owPC{`W0}1q(e1e2-)f0O1(R- zTee}o6a&!-{v%~>0qw`WrwoYU^;EYy8)p<+EeptZV@>N=-TM6P^6s(qyKRSNF&XI) z2AH^71cSj0$wHd5OD;7HDz*wZpD(EPAaeOf&+~qV+^nJ=z-G(i?GE}z;O6`t|I2Xl z_EL-?W`X?03LgUKAKBsbcfW*f{^$z$pBBW@`N*P@Qc`j)NFb3$7tPK^vy5qA#xXT% zfT|t`3@d+aaDpLt{>lOPoNL#o>G1LvuJjkssRN6Lq$J%(y_LJp!NQRg4AY1#eB?YF zY6I%E^o#ODcPL&6kc#fEW7vVzfyl=|xaF@-ksN^rqQi^YCMK(8cE$8;;J_Q6I;R9E zBX>qhb$imTBKEWrTkERXvuv`YVWPPFbBrU~%vPu3^N1(9cvq44U-mz=)d}Fl=BqO2 zu>p<2a6YDbz9MxkK>X~xvfMEW+7*yrL|)ygbBWM7Vd%YEHEQ9^1Vryeqe0FoUn z;r1%M_S3c4Wq*qQ)j~y0O6Am$Uit(cJ^tp@)x3;oWx2Ws~ zsV(bL87G^0;mJx}a(Rm>@aPdiCFsZ@K@=FoL<1ZQVWz6`rUrYFRiRSQR z%A@En89-yC(Pm$aw-R+C^nldT&J%({Z)=ghvbDwY59V`hf6F)@zDg+zRtY#}RA4%` z!Z(lsB{T&NZwHge9mML}zq{r)t034FTgdx=HGO43l;6|#QcDXW-Q5jJ%Yt-CDc#-O z-7P60-H3G8E~Rt{2-4lsA?LfF3M07TW{OXwd1oVTTKD$Bss^^~216s7 zZWta$_W&DxB|;1)1gw?W4$w&vp1KvdV1MdROrSV^qcsOcx)jOAd`_st|^f&B4&7#iY`LqY&q zFR)qV1=P6pj2ylYk5?7mx*qcu`=LVs+L5C%H}!BdwTs~L*D#6deOxmLc&O?W$oTr6 z0H@LnG=u@j69VK30aZjKq<6#hK%uTchj^<7{I@;*gs}7IjE+T;&v5dJ(YzJGnL2Bz zb(eAiwWSE9hT4sEoXaEU4j{t`H(yZyQsH0e?jZh8<^oXsTObAyIlTfD%p1ycQfVhN z^E>N$h-vln*Kr1gI6h>gVBU8u39*~vKxK~>WfIAub^iH0A|q1locQ! zZ4J>^^hj9oBx{RG}piP2mvtMwFG7)BI=K=UJ*PXK`wPPJKP4}71d8b zi!9*Uv9s6x)`XTOuV?ORz|`d<3dCn2CUQ0CvDqj(MRHdOD345b_!*u;f9uX@wtY+E z`mg8-8j9#}0P3CvF1V;aYs?ij;k%N?B3AAta>T`N{vQ4O3??%AKDLe?G!j=ebQDqz zB;9Ek%OutRI(j(G z6ZI7L?j^=|+SUv!dTEx$MbK1R1#a$j&9Xr*$3A=Mo~|E^PjJ~_9z!Cj3Jy}mfS(m8 z1B-?WP{5K9peTes=z`tyMNv6d=A+kbG6K!TuRe24JmX+a5NnVicRP%GM~`ipK|9{) zSSSeAyyVz~f5Q418L&ISNb>}&$3LKiV8Lj{3J$fGl1X4hPz5)!NnG!h@2Rw63k*qu z#?{S)R&%|O7?hTLejSngV=y8P%QPGdcvi!>ZTKT*qpKV0FCGwi*ndZ7Yhb5(@Jf{n zF1D&(QJ=X!2vW*>fTh(rIY-K|Tu8wQ{M8O0N##2W+|L{7e+*H7|s2Js*mvp;z=NemRsM7}71Bu3tVVoA8v)O`f50 zC6;C`lk*~?0_slEdSsw4&AUcaMn>8%?lIj1!CSh;J0eJviwT5sU?J9PD4QHQ!a6ZP zc&rh=ODHflGuVEe2S#O3!g(yY-M&I==Ta;t3vhWm_$lDiLuf0yIizda?E1->AtoXY zHCp$1JO@}PopKBs<;H2i!K5?>!0H%KU6Q7Q(<_*~PFJDoTnL~fw)peLN;r zOvB(XaOnPPWyapEUU2kk`Ioh`rP~5kq)}o)rE=|r_<1!deIaDeircYy9yT42*NYVo zJlqTfp7n6x^U^TBOT=R679oNv(|=iuY0NL$yO@i)+FN+q4C;k5AQb3y=lRvuHR`l2 z$iK)ftS$5D3Fv_A)l$Nj9o`pVMvo4|kNE;dh?nICd!tFv-neLAlzV0Re+}E6vIt;LD9DH3h3TVl&xiBCj+l6l}DkVd5V1 zWaxx7%w^-d!b|Rz3%|4rF12U?ctnnYAu$pkm;YewVS{o1aWfSxARAo7KSiMjk zXfB}{I37W#77d2jH0ctp793mOd0>Hj;02B;>K7?NKyeH1k|3Mqn#hnc4gHoHr}C&JV|sn&v#pj-9gfiJ#R;X5Or{8bCvs3i z5`j;k-SKXp)P``Farne+^NZIW!pd`@2FMV&K6~fvi2xXok|fCjpN9k>q0#_H!_S{T z;qK>5er>trb{wEX8cw}URFoKCcl4|*36xq{*Hi?#o9hLS*O-?Xh{w7X++e?SChPS# zY7l4t_8Yf?A*&2_=F~eFIpp6ZRHPhYVsYVk0~$(}u(Ae@lj$v)4z-YAq9tKvaqA;5p(k;et+fj|MpLT!(EP}3t%#>o!Bk5z{LW(bbQ?0$b~Y_lDMcs zu>T+Ff|m~j4WQM#wu%`ndaas<(f;k+B%h@eFomV@gYk;f-s<}acZh1VDH01hR=}?H z6Y;opPzf`q@BJmlzj~Af+uJg0HFaqo_u=` zfT_viX}1o{yqwYI^MX09CaBBDH%3WdY<4}k{3 z*T>iRCyyU1Xp#H73XtbZ3>{!93MQN*n!f*H1qF>9=;*KUBREGo;8#|7SPz|M0CP>%{aO+&{9)& z(`SH49=iAM-^~d_OTr@z=~nbM5Q{~PRyrn4YB+^mA<(W-*Q#+r`LN^|Eb$V#oj}@+ z*_Xxlps*a@TCD)WDb|!xAV=0@6YDu+pE`ar(7ABESg+MW-%YQUA}uDb<}XJp%heH$5Asw^4!?j`BM*ScHYK6)P0HPpvR}cppOa>6%=TY)Kp({G)?2)b7~w{;sbO2 zcmSA_!VJG%dU^Yj3?^$$$jr5DUy2ha+`!WGAjo->J?HzRF*eB zHdaA_2O-nBfC5sDAKfLkKRx8n#Obc0J?mW=I&_rEssQ09?O@=vgpGDC zF$iJia=PQhx8GaGraPevGP)0fn6ZFwL)(@JL}l7S1Tn|+=mZ?sz|52su}@^uUzu1G zA*w=Xv+sZOl@mxLIibf*I2Z2C8V~+t&?>-63;*xW&qRm99@F{p2>z2WHoxjIA?Cbo z(YtaCan}g(1{7f14LhH@n&_Y&$wc+}x;L9NV>e5(qlZ{Y>oF*o-+>U!J4J^y87_(@ zA{xJ#c>y~^$}%;U-h7bYm=Jdd>66A(da{E+K+{T^2Ruq7_Rg~U`HW46Gsq#J zP@ARrHJEf((%gd+_L<#IJ&(wKF0=N&<^)KKCNBE6M8WwPVvw7g3rju6nn0a&vB=6v$M4g5YMg1b zz71SYBhX=ruQ_pKFOHd_&9i9qEM{1$OZN2GSo|UlsAqU;`pbEqh8SVz#?&|&7lz;6 z*yD|DIvX<~S&#g}c$sCZR_lV;UAnX05^Pr7l23<+rkSRWeYAlcE?9V<81hZ`$ofJw zn*R|@2T;hvoXEMWPT#0SVGiAu4Xq2rAS*MP+)36~#69R8Fjw(36;1P_L*VE{_xSZ^ zjlGy+6{FDmmoK7-BPDxtcRCBudbLQCA4tvfbR@gP|X%fw- zPzldN=%ZENzKVA!b+bvvb#cbx50}jHJLqdjBn0 zOqM*p(p`}&pEo;rfy z$7=cMgp9;%B(68+#FTVH4SwDnOdj6BNrj*yoJ z{wwsvFTlOv`PM7Cd033*BJ?t_j_mGw@lhnst4uPnrSTv|)zUrkrB?o8ujH{ieRD&n z7?eWvu>n7$yS4G=o9tggGd;>Uhu^bs)SyNV@hR31=`q>)ZxI7(v|IF5(5ii^? zFSao@HumSwA9*n{a#`Bsvxh;QHwgkwpzAOT9q1~zprDlKgqGwh>sw#kubSupl5m95 z5A#e;6*OwSOVX)1vlhQO-=&pEqNTw@KBw;Rxc>R4;+s?5%sVw@!G9G5g4GUTFIt!E zmxfDm+T*v_V#pP7r6RbxyZHkqj@`JA8KLs;1Rjq_`LkS0$yI*TR!@!!k6KpExOL2o z5|06EHv;j(f>5M@xo)4#Dt_CNCP3dO$rPz5uSnt{7nJTdEwU9G-DcN5oqJ7obK-@k zA=9AIeo+i+dh>5$c^uD3O+d0DYuK37y)9}NZ^*dB<(2g;j5yMSQ@<@uj{c)o zVnuEwV3hA$7 z4&``Ww048-+VtNMftL-!PwhDp1fc=PoU!(Q@WuJFO80l)Q|ad?I1FDs(o5{K+;eqb z$?o|@s@!By-kZ(>&>7qjL77$dGs%e%$Ja#l^X%r?bJdTms{y{%!tTH=5u(m}j>NSm zE5#p6$-j&^R?(Tv7=&c;Lj60cjsvywKe$y<r^l5$c zY;|(r9BD;XRt$YJE#UqNECDlUouqGLYIc?*(&X&j;uPt-Uq1>!Aj~y+ zDG5z>oIdXOHE|hSDeAglEOL+>=ifvj4hPhK?B}2V>2`@VzsVRY(~QTkowKaR5rR?z zt)xy@e};a7B-D@&yw$h~*}38$IsS_K*2k@nskxS9tc73D;h;qBYffrF2Q~K^gcgXpMa%qntGs&(>8A-_kE!Btub4 zqN5D{!ZFZ#A`|Mfz({B#KVoMJ6Ls$ea4%a$ko>~C>$fSwEXM)8L3a>2%c#sOu@CN7 zEMx%d*Rv*kBSl+Y99!W;`v`ddD_#%N77l^Bm~8+Pnc~6}x~ps-a#4HZH7f+X=)TRE zkf3H|HFaF7oK`GZO&#v&p=kCtRHb34iQs~~IlszALasj|*#?V7Yl8b4*gxSS1zSz4 zUXip;&Ocwx?)}v|fkC-HRKTi0nwskvUVUt*$W*h=wQ|vdT;N$+yiJXulgMjf`H8>t+$+xcxCm^Tp!E#8!|MFXApk>n?( zE5}S!M#=+kb+WVnP_+9WcInnjG+W2cO_O$%`6VMGG^dS}YI8PcOrjMrM;B3Jgfa(S zS$nd)%;6KS3@A@OkRCz zUBFp2{F2N|tlMI-MS<1@?PZRVikGa8ybsSQv$tHkjXoz8SW*tS)cX}gk~QkXR9W-9MM1KgBl^rF z`Eicy-&+W`3U{QuEd=mJ%VJ$Ajc4t=U_9O`u)Qc@8YqbjR1ESClBiT%(J6`s@aAd-2jJ`!dC9$i}OZ0B^Qz z+?34aZzncmN(JXDSAm9mXDfsyV zH!OSO_UGP^K3zVY%_4_>TKkX8=r<&*Yv534Xp(;^`DEEm<4_nR)lMLDaOEj1SIia_ zF&5yBkbWOm@5;sc9;=Fc)MOY35SXv}AkCJRmY-l~x=37SN5i*HZ;0~!xea#TYG?mj z`t}b-f|GF<3z#T2aoC;3TBh{3+LqUh{X1UY#I3>W(k$7w6kgY#I_{NxQ$y`S?*WoA z6+K0#kv}^Y25=XU==)~B*eB7>hE58lfjs}DSGNi7o6w!C*4;q9=C}D{R;mQk%=}FQ z!%g`|l-x&GA6A%SX<;J;+-mq+?e3LHA1sAZs0}Z$@;!Z76rSEULQM8QAy}*KCj$o@ zprNMl{}3goxn@bFWG}v~!xh)3k%)=>a@^|qWZ->}`vY_;@G6`Zc_EqJW@?|QtDg{B zUrB~yVZ{%UbFATFA81L_iQ~!S^o{gg;zsC@1~SG1iHQC}h%u!YuZLvBe+a=n1|V%( z2&iYzWoPLulc_)k|Il| zfU7CZ91AC6io6|mPR6TCwP}jSVvWuda0EN}n`E+f3RdM-cz(+w@Y4bhX47dfr3JpU zAO-^w-I=*Tl@t1~o~pPy)8y1OGgnyp`pRvjTUu=!B~W~jb3l^KPb5n8z?SvpI6X_~ zl=>{B+^S;c-Hbb9{y1R+t%Np~<$yf{koJ7bmOj~+js{ZI9G5`r6tb1aB{qGG7~IgOQa;nwj1^QM0(BRIo!VL-_I>Bj|5&t zv!h9%g=g+!lqx9UdLIw|tNvwe`c*1)g-E&=M&gWIh8B7oYqgIFb18=+cxuq30Ndv{^=hxgOqpCa^}=N^kW@MH!G23()kLOm9LUMH^I zHcGU ze{i2go}w!z^jTw9u%Jekp#FgZ`ZaCmk#|!gP8=Ylw_79D@fSxR(2|djUjCveX{6rn ze9G}FbB;UN=!2eOD_$XGdWg`4Pgdw-ES(tt;k9J%Wo|*hA39%S8G5`9^-h^zD~eyVtr=%?V`( zwu4oO#4mg` zM2_0e&E;Hsynf1*kJ>xjR#1|al@$|%4pdD@)bK6%bY%SthKkdx245H<+kFfW9>^Hx&GEdudQ!logSCWGT!?|*=$STCvy=5zRJ{%sUm3G zJU{hqg5HPh>Y~m(543BIr;*s;CcR_-+y;B&72p=LgAvPNJ5TmVvGQ&ON$yAAo_x8= zI-hwkqpDltn7jpQWtUonw9XrY%cAdFyuzE`FR7>HG~wVmJgu7c%eYMb{_>wk9aDi^ zrLvQ+oB8Gvks*#FYC@Atx5MIOY3uK&Mca2$q0BLT#ZS!jRMlyUKU{72DTPn3;@xo$ z`E~!un1AMSp{iZhi+0)>Sw27gvV?8b_NZFEcd@T%DP}3(H_Y}~QBmZm`^9PyvDQ^T z<$&>tSKBx^H6>267)V@t_+Go)_H3OSwmGvTM^jy{5)HqY?Q#oBUK3*f=6ZPZ{eoJM zgb1|#PAx66%sNH1guK7#SFTH2ZBAYt8OIj1yi>#%)=u^0eLnHmsauQimMEv(SD?j5 zpylAr((~qW#_`;nsD-k5>z_U}`I4nqy^G5VoCcMaXgdnNUJTG|{9D&{_E=ii56+vR zKd^h7^c^Kh+jCB7G40+80vUr7e8HxA)C-v8?Kust`y* Ul$|rSK)_F4T1Bcx(m3@00cZnT(EtDd literal 0 HcmV?d00001 diff --git a/my_dual_robot_cell/doc/index.rst b/my_dual_robot_cell/doc/index.rst new file mode 100644 index 0000000..0580c5b --- /dev/null +++ b/my_dual_robot_cell/doc/index.rst @@ -0,0 +1,22 @@ +:github_url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Tutorials/blob/main/my_dual_robot_cell/doc/index.rst + +.. _dual_arm_tutorial: + +================ +Dual robot arm cell +================ + +Example about integrating two UR arms into a custom workspace. We will build a custom workcell +description containing two robot arms, start the driver and create a MoveIt config to enable trajectory planning with MoveIt. + +Please see the `package source code +`_ for +all files relevant for this example. + +.. toctree:: + :maxdepth: 4 + :caption: Contents: + + assemble_urdf + start_ur_driver + build_moveit_config \ No newline at end of file diff --git a/my_dual_robot_cell/doc/start_ur_driver.rst b/my_dual_robot_cell/doc/start_ur_driver.rst new file mode 100644 index 0000000..d81d4e5 --- /dev/null +++ b/my_dual_robot_cell/doc/start_ur_driver.rst @@ -0,0 +1,135 @@ +:github_url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Tutorials/blob/main/my_dual_robot_cell/doc/start_ur_driver.rst + +========================= +Start the ur_robot_driver +========================= + +In the last chapter we created a custom scene description containing our two robots. In order to make +that description usable to ``ros2_control`` and hence the ``ur_robot_driver``, we need to add +control information. We will also add a custom launchfile to start up our demonstrator. + +We will generate a new package called `my_dual_robot_cell_control `_ for that purpose. + +Create a description with ros2_control tag +------------------------------------------ + +The first step is to create a description containing the control instructions: + +.. literalinclude:: ../my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro + :language: xml + :linenos: + :caption: my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro + +This URDF is very similar to the one we have already assembled. We simply need to include the ros2_control macro, + +.. literalinclude:: ../my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro + :language: xml + :start-at: + :end-at: + :caption: my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro + +define the necessary arguments that need to be passed to the macro, + +.. literalinclude:: ../my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro + :language: xml + :start-at: + :end-at: + :caption: my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro + +and then call the macro by providing all the specified arguments. + +.. literalinclude:: ../my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro + :language: xml + :start-at: + :caption: my_robot_cell_control/urdf/my_robot_cell_controlled.urdf.xacro + +Extract the calibration +----------------------- + +One very important step is to extract each robot's specific calibration and save it to our +workcell's startup package. For details, please refer to `our documentation on extracting the calibration information `_. +For now, we just copy the default ones for the UR3e and UR5e. + +.. code-block:: + + cp $(ros2 pkg prefix ur_description)/share/ur_description/config/ur3e/default_kinematics.yaml \ + my_dual_robot_cell_control/config/alice_calibration.yaml + + cp $(ros2 pkg prefix ur_description)/share/ur_description/config/ur5e/default_kinematics.yaml \ + my_dual_robot_cell_control/config/bob_calibration.yaml + + +Create robot_state_publisher launchfile +--------------------------------------- + +To use the custom controlled description, we need to generate a launchfile loading that description +(Since it contains less / potentially different) arguments than the "default" one. In that +launchfile we need to start a ``robot_state_publisher`` (RSP) node that will get the description as a +parameter and redistribute it via the ``robot_description`` topic: + +.. literalinclude:: ../my_dual_robot_cell_control/launch/rsp.launch.py + :language: py + :start-at: from launch import LaunchDescription + :linenos: + :caption: my_dual_robot_cell_control/launch/rsp.launch.py + +Before we can start our workcell we need to create a launchfile that will launch the two robot descriptions correctly. + +Create start_robot launchfile +----------------------------- + +Here we create a launch file which will launch the driver with the correct description and robot state publisher, as well as start all of the controllers necessary to use the two robots. + +.. literalinclude:: ../my_dual_robot_cell_control/launch/start_robots.launch.py + :language: py + :linenos: + :caption: my_dual_robot_cell_control/launch/start_robots.launch.py + +With that we can start the robot using + +.. code-block:: bash + + ros2 launch my_dual_robot_cell_control start_robots.launch.py alice_use_mock_hardware:=true bob_use_mock_hardware:=true + +Testing everything +------------------ + +Before we can test our code, it's essential to build and source our Colcon workspace: + +.. code-block:: bash + + #cd to your colcon workspace root, e.g. + cd ~/colcon_ws + + #source and build your workspace + colcon build + source install/setup.bash + +We can start the system in a mocked simulation + +.. code-block:: bash + + #start the driver with mocked hardware + ros2 launch my_dual_robot_cell_control start_robots.launch.py alice_use_mock_hardware:=true bob_use_mock_hardware:=true + +Or to use it with a real robot: + +.. code-block:: bash + + #start the driver with real hardware (or the docker simulator included in this example) + ros2 launch my_dual_robot_cell_control start_robots.launch.py + +.. note:: + We extracted the calibration information from the robot and saved it in the + ``my_robot_cell_control`` package. If you have a different robot, you need to extract the + calibration information from that, and pass that to the launch file. Changing the ``ur_type`` + parameter only will lead to a wrong model, as it will still be using the example kinematics from + a UR3e and UR5e. To use a UR10e and UR20, for example, you can do + + .. code-block:: bash + + ros2 launch my_dual_robot_cell_control start_robots.launch.py bob_ur_type:=ur10e bob_use_mock_hardware:=true \ + bob_kinematics_parameters_file:=$(ros2 pkg prefix ur_description)/share/ur_description/config/ur10e/default_kinematics.yaml \ + alice_ur_type:=ur20 alice_use_mock_hardware:=true \ + alice_kinematics_parameters_file:=$(ros2 pkg prefix ur_description)/share/ur_description/config/ur20/default_kinematics.yaml \ No newline at end of file diff --git a/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_alice/programs/default.installation b/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_alice/programs/default.installation index 45a1d9b1e4f655740612e954c819c205565cd74a..c793559796c45c29758ee5b777959b34dcd83106 100644 GIT binary patch literal 2483 zcmV;k2~74MiwFP!000000PR|9bD~HW{_d}!_#BmsfL7^N8Fe!3Cec!psoJU3R11yv zF3?s3CfQ%Vr<;qQm^hbr-^p%9hse40b55T=eSy9mMltez6cZXs_U&RhyuKbT?dfgv zellOc-+`>jRmSyjv1~4e_mgo&#w83pF=fvKxt*|x1nn)OYlebImOSF)TNL1d>|zfk zek@DThCVK~7`qFfxR_1Dc@i$sY9M>akFfkpLz4RTG~$2Z*O;sc;IzYS5_3b5v_pOZ z_AaFIM{ZZ;r%8OK!je+|g+}V+YK>O}havLm`bB$Zi@e<0h=v|nCk(B8e0Gq^O6Nz4 z3dsdo1FY$m=S`uZTu9&eEv%z`Jmx4|WY28e`Z9EYhOOb(q2-rMQz zd@ z@C>7Hj@KlLF?(&4{MSD6Sy6knO#IhAC&Ffj@&7B)UPttgcj5_1AAE{_wlGyN{Vaj1 zD_!4JHQ%rA*MHOXYbLMvf%ATSzrH+hjus2=gXa5#TC=ox59_yt6(fd7)@ng9F{XyA4He@LvA^)Z6vb0Lp9(fwb z*+EDD8b$E}?XYWyU!}J|9*&o5z}qD z5S0d!W*9Y`%Z$UYn>g5op28K4LwYVB0fKdcn9D8AafIVSO*zHnx@sfdFpOt3A{_H1 zL@OVhs8tSuyd7*z4A+0XbJTx9frXE+acU z4d--4tA=Wsx#p?NNCyg}M)VAYEtr(kAR9z^zn&5(5`{Nxke2O+lfnewi*7W0Cg-T?4vaL+=3H zsG*xcxAyeL=NY3O;f+5uw)syn60j>I3gUt$%)vv~WjKnetTB$DUWf#!-RC@tbJSS*8l6aF3=W7y>m;?D7 zvjksAr>;Wtp)f6tHrV+yN&;bCRL+59v{Z;8b2uc`vP{kBsrxaIwRA}nz|Ed#J_@n& z&1p6!c2qQdZ#EC^nxO)xH=jZ0f^p~)!_1M+7fL*J{uDu29dOddiEnx4| zWAD5L>_$Cy<1Jt}>#>_}0lQU?-TFzf^M_$z4lw1jm9s6~-;3wnRWK?C6QCy&B*C&G zJ;pndu9yar-cpU8(lL4+Q&oDFZXS7ifF$$#o^L}U(Eu11kI(r8)iOBc1BKa|-x?x( z=xM^8KM)eMBguS$G|r+ZqGyyjOA@5i4yVrOBj%3lN@n1O@}5fqv509YC*c1|Nf@W_ z#m^kuXT7C&AR?M+=tj3^_4EtrJd)Y!ban0UFSI~H(L%m7;Ek9qO;@^_(b0OU)ib&# z7yof2CF}X4c7b7Ny3y-eR!{uPr2iMhz2|ehqkfX^UI9cCf^+;|?N|^mv(w!pKhQha zCKnpk!(kt1tKSnjs9Qs(jjb>B?RBMA@HPf*pLgeS#TkvE5)M5PYuAirGbbxR7cY%4tT~a{Bxe ztcQv3Uldc+{#RMp9t%;$=&q25%%-=}P_v_BtJ(9qUQ;u>UJtK2UF5mYj^V5{A=Ud% zsT9Ikyn+USu|vntwx`)bpu!&h1=Dl9$ykkk`|uDHl;?fQgpPS^o>{!{S0B&`PhP8#?SZ zn{H~HL$;@8eUshs{s~YNiQbW=>;=e-Igt6fQq8Qkz+N9cd*)emC5B%*cxJhUd%@PpJ zoaLuFFcgk*V0JySrvur(x}DA^;&wi{QV$7QK}gMwvk0W4Xg^$%m|lyJlu_md^*9gH zz-_Zqn#BX^rC}*n&(t;3>UFw3)6AlBnp2F8{s)ZWgyloBKY~~@bWiYOF-9LL^W7yw zVdTM*R&spNv7ahbIhO``!HMY&WadNXGhHf>nr9eS;G_#4I z2sb;XqT!ydYL;*YYO||%I#4}5Rd+RPb`)ce zrrdnLUGDJy4dscHCtCH8JD}-?PaF>py?HFDJl*Sv80;CKccC$I@BVuldd6q7wAC{RO?0m)9 zE+6g;rtVCwUDNcu?%K>op_eRwE%KgKm2Y>{IL#V&PE!E zX@jSfWQV*6q&c_5&L*TV|32q|$k9m|ymR6JaoJ-Hdv$P1cVO4bwwku15Mk0&U=J=wu7 zihU+a(S|%Nwir7L-*YgXhVwXFqE%0Jkso3CmzpGX$J2=ag}b4*_5kNN+{TPMiliO# zWAJw&6@TPr*?t#bvoRz7}nkcx%g z9w{O$7v36RO}Cskc?so0`pQr49qr>WN8uW0uGI@E{T!Gkz=tG2URcC&NCn}tZovIh2nbxzrrD=$e+b@OCo#;&A=#}N{Yu9`3 z$!VgadyOKtKs)S=!!Ihw5BviX1PjcV7p@}-hx};nWQjP5l@nQ7PrjR8FZ)-cBb8oI ztx)XD5rZ&Z_HT!es%mJ8B1>CDJ@%5sR+b`0wwKWEo-7{e^Vsq6V1p<~)CS;YMTssX zP-V^q@IJj=&Tf~9yp*?4dh%jC`F%XOs!*y2%0zlce1_KG^v}_JnuceXs1?vd?9eJDB6h;P;Qsx z!Q#O@G(*5L43^QEKuC5BqbC?A#YW{Zo6aK@E$EKe2Iz{}cy=_<({z0@3qsraw~J90 z3rbu-$d1a)t_S03Paa=Qrt^__oR6;5LxGkH5_ixQfG8$$G>gGaBK(9Ai)qHB?f~LI z(Vd5%a%w#h>N|qVE}?;B`y%Lnl%#TI4faCA$PLUM8{~^O4*h2w<>0;O4yGgCpj@;< z5$=a;E)h{?p3e%;%^XX!3?`%HA?ofWI4m_H6BOVi4Ec+!*9n&7xdI&@SL(`Y8-{Mx zv8AAT%ht>~Y9qJaG8GMXbXBt~ydNgz>cwPVLX!!;7LATNSZl4!y5e#SxUJUPdaG48 zk*n&ChRv2@?9mjf?>37a-ksx!#MH)vWERahyPq=I%bv&giQw7`VDXSHNgO(ezRY|S zV&$R6ho;n%5*umDrIJ!}ya;Y>9Kb*XE%atBfE5I8hvP;6@_IC^3DXJmCXl5k-IoU3 z19!ksXyYZBQdmpE)Cu-ie&oCAmst8xjuh;aV&ogyIPH1eGk~RYV6v3z^+$g z*WUy7RyFq4d%$i~V>jLdcC#A0`5v%a)!40{6gyuvz#U)`TepWAY%vSZcj8+IWiToS z6QE}=h=XOxdWd&kvIFc%dP6ljO3Uc9OjYSvx_Q*v3<)ef@%Ev%!xWC6d!SDq+sxAK zdI}a`aMgwM+VvrKEDbi;{v5@Da2_SNjE1V#Y-+=;+Oaxq!_w6@6j^R4##w!0%LmKh zLoJT*a;DElJlHkl`{d~cg)#Df_0}8l4GZokt&tx*9%@l~mu?$H!AzF<=PiK~Msm(L zd3`wStdtse{0JS1K7jb=C>jQrd?K*W^G8E43_XuHKMst9?8tHfC&n$bdYBST5X>lQ zmR^uZTUqTN~ z6~tDRV`675_+a)2vjs2sLTGa?hjFmtnTd2UNabQpsNKU6`t#Pq;#{`Rp1=|eYw}{d z!Bkk@m-hkbMSHlADiz9UMbUHeDjvLtvF~5xi}L=iXgnSYQ^jbnkc-T^yVBrvtYfR* zaocWPGuv(luUc?YcAy@^UTMOr^Nm&sgrWHABLrp~+OQ^P`wKn{OX~jLupwcaRF(C_ zcv?R6RVuTRr<~g)?Qw_zwsjba4yHl-aKwG91z8^PpzeI z#Y`(LB+|b;h7YxEc3V6<;q@H{)`h678p1Izof<3k)AD#vYVI}>E$paDlFDSd$V+;wWMxhBnYZ%++V0m)Ilm;?xlq<MrLlLK~{6t#!r8aB|h6CYHy^0c(1~{8rDsoiBGt&#P%j6K3TtH5jgT!cv0XW zhNREJ-Hdv$P1cVO4bwwku15Mk0&U=J=wu7 zihU+a(S|%Nwir7L-*YgXhVwXFqE%0Jkso3CmzpGX$J2=ag}b4*_5kNN+{TPMiliO# zWAJw&6@TPr*?t#bvoRz7}nkcx%g z9w{O$7v36RO}Cskc?so0`pQr49qr>WN8uW0uGI@E{T!Gkz=tG2URcC&NCn}tZovIh2nbxzrrD=$e+b@OCo#;&A=#}N{Yu9`3 z$!VgadyOKtKs)S=!!Ihw5BviX1PjcV7p@}-hx};nWQjP5l@nQ7PrjR8FZ)-cBb8oI ztx)XD5rZ&Z_HT!es%mJ8B1>CDJ@%5sR+b`0wwKWEo-7{e^Vsq6V1p<~)CS;YMTssX zP-V^q@IJj=&Tf~9yp*?4dh%jC`F%XOs!*y2%0zlce1_KG^v}_JnuceXs1?vd?9eJDB6h;P;Qsx z!Q#O@G(*5L43^QEKuC5BqbC?A#YW{Zo6aK@E$EKe2Iz{}cy=_<({z0@3qsraw~J90 z3rbu-$d1a)t_S03Paa=Qrt^__oR6;5LxGkH5_ixQfG8$$G>gGaBK(9Ai)qHB?f~LI z(Vd5%a%w#h>N|qVE}?;B`y%Lnl%#TI4faCA$PLUM8{~^O4*h2w<>0;O4yGgCpj@;< z5$=a;E)h{?p3e%;%^XX!3?`%HA?ofWI4m_H6BOVi4Ec+!*9n&7xdI&@SL(`Y8-{Mx zv8AAT%ht>~Y9qJaG8GMXbXBt~ydNgz>cwPVLX!!;7LATNSZl4!y5e#SxUJUPdaG48 zk*n&ChRv2@?9mjf?>37a-ksx!#MH)vWERahyPq=I%bv&giQw7`VDXSHNgO(ezRY|S zV&$R6ho;n%5*umDrIJ!}ya;Y>9Kb*XE%atBfE5I8hvP;6@_IC^3DXJmCXl5k-IoU3 z19!ksXyYZBQdmpE)Cu-ie&oCAmst8xjuh;aV&ogyIPH1eGk~RYV6v3z^+$g z*WUy7RyFq4d%$i~V>jLdcC#A0`5v%a)!40{6gyuvz#U)`TepWAY%vSZcj8+IWiToS z6QE}=h=XOxdWd&kvIFc%dP6ljO3Uc9OjYSvx_Q*v3<)ef@%Ev%!xWC6d!SDq+sxAK zdI}a`aMgwM+VvrKEDbi;{v5@Da2_SNjE1V#Y-+=;+Oaxq!_w6@6j^R4##w!0%LmKh zLoJT*a;DElJlHkl`{d~cg)#Df_0}8l4GZokt&tx*9%@l~mu?$H!AzF<=PiK~Msm(L zd3`wStdtse{0JS1K7jb=C>jQrd?K*W^G8E43_XuHKMst9?8tHfC&n$bdYBST5X>lQ zmR^uZTUqTN~ z6~tDRV`675_+a)2vjs2sLTGa?hjFmtnTd2UNabQpsNKU6`t#Pq;#{`Rp1=|eYw}{d z!Bkk@m-hkbMSHlADiz9UMbUHeDjvLtvF~5xi}L=iXgnSYQ^jbnkc-T^yVBrvtYfR* zaocWPGuv(luUc?YcAy@^UTMOr^Nm&sgrWHABLrp~+OQ^P`wKn{OX~jLupwcaRF(C_ zcv?R6RVuTRr<~g)?Qw_zwsjba4yHl-aKwG91z8^PpzeI z#Y`(LB+|b;h7YxEc3V6<;q@H{)`h678p1Izof<3k)AD#vYVI}>E$paDlFDSd$V+;wWMxhBnYZ%++V0m)Ilm;?xlq<MrLlLK~{6t#!r8aB|h6CYHy^0c(1~{8rDsoiBGt&#P%j6K3TtH5jgT!cv0XW zhNRE*Z}mhKaIHM;sX#7yxNL B4x|78 delta 45 zcmWFunV_SQGDYjh)9IQLQrZ#`Q8OhXXG&>W>~7PLkd&CI_3}0&!&v^6z>8W$_%z18aol`zOr#yATG)|uJW$k({c0;Q*Ws261r_(hh lq_ia>qGn1&&Xm%$*xjZfAt^Ca>*Z}mhP7-Dy&Qpt0RR&?9wz_* literal 0 HcmV?d00001 diff --git a/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.installation b/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.installation index 7535e418bad715d83d6faa98038c6f4aa3a44f3a..0c76ca1cce307646ebfa0ba1876cb74d2d401065 100644 GIT binary patch literal 2469 zcmV;W30n3aiwFP!000000PR|7bK*D?{?4y(`7?(PY(o`n6$#7?yGfvcWU4lmni94Q z+O;i8mUHZ{e_Qf_4JOGPJMW}6lZ<0`w_1-{kFK@{(fcs*yWTx4b@J+-viSW_?U)>L}eU@RFE!5ZUyhv z>}t|fUVA;sm6Kjich8RjQX%3GZ`%uQYx((gq4<%&al(KDyVT_+^@vYgIjfy-DRFCf z^qSv#@81RZYp(@_k2t~%1@naMXpGOGpD>CRctc{2*-K;ozxMOGsJ%Gp{nvg@gl!t} z{}<6-M)cD=@dTs~0Y$%Bm@1fll|a=^T|ae7eZRh6f931fEMD&e=l%MAeSY8^Z5G}K z&G!ejW^3^t)^7s)UOVOZ{rM(6>n8hM37oxu?8>*J7gd`GohN&v+WaE>^ zp_(N+1{WyiOLULDY4la)7C5E}b1|IDIitZ6b55d724#tS{E3D*mnt|C=XP(Xa+Y9K z0U{95=isibHI5C3+ zLUAnXRh2BMm??8`E{+5>{f`XY6aJK8EGkt9(3ul7M+{tpWqe?9Z~=!&%xO4Hi%s%K zr1{FM>uTCCSca7H?TVo&4OS6MUWh&+=0#YvXF2<@%AAd}R;5|gq7+Ivy^zf;*StEP z?=4^)-s3q8(xD1+2v(jkyGJAtu!SxQFo?OkQwaET`-Zl59k1m$TCdgBUA?t7U8iOB z)_u$NjGl@5YSs~{UxoU9jQIuqSA93hQ~b5T=Hr**BGidvy0W}uwME z9@JyGYeQP~ztbv(FqW@TATZO&4M>!de<<2iRgeB5VZyhWs&QNNQL?*h++#+3f<4em z0yiEA-_EniS`Gu*LNQM^mFKQ^g=gh_i`~EDB$VFc6qVK1wT8=FxHZgP*Y4Rp$1I9u z6`j!pNWq@w0gAA8*ANp36v*7}gcSJUkr-}WECy=Us1V2vw|N&er0Er9Aqr&wlso)R zIN&I9@ruqE&^!+s4%YMm7CFv{%Vk7FyBdBV-Yy)=pTn-#W7ppTcB3A<@fNU~_1Mj~ zfW2Ffz55ohTlLtjw}9QQ$8Ns`>`py)=NH8;Hc#LVFy#xnyDL54$gcvbU~~Z{M31n9 zg{zA77~hk8%`@A&)z`XKziaDS-!bi@*5*j2v+8D1?!@A|21JT&U@!T!giThOXckMA zWz}fTG7ZCC;$lzitSTiA<+*(f2sR09;Dsj$7Uo4U?UeFNZjktvVVtkZa$gGDt4f`x zE%Msw4ySEK!4cv*U0zO{B0^BQLbEKRthji=>}7A&fV|c=_v=IRJqCxFS+t;QT6I*b z%uAkPM!LxbYQ#@5$Kj+*gDi`Y_v>E)Nf2SnkDSUaGW4krmW*4SB!?sMT*LV7+*;M|0 z82}-X1d`7*0*l=?Os!{FU8Ao%eXD0Tm48*V4@VgV#MLrPtKV~+zWmoq^F}{IxR1*M z-_syTlbZmlWi*xJ|N90Um>+&ra(76JY$Tqbwbpj3yf*51om*9jZ9GS8vzFLqnb<}R zv32d3*m(=ynf=b}Y@N6(R*Wp;R_up_tQ?7!o@IznUWMN|qdpPE?;5-Ow(PkOE@e7< zjt!$Q3snyS_8>Y$%BsQk57@biPu0>iot2~ouwyU}g+g&4x@oH|)C(;T9 z0e!ecQG$X`WV0<+rbc7XIn1=BAI!l+LX&u&1TjuCa+kE6Nv>{jLYi*7Ws+v7{ytg! z@#SKAIbBW0d8S=7IKuoW%{jj~pU#Hr^yAfRF_Djp$w&QAU=)JX-Gpy319#K;k;Cj0 z;PlPVP@RvimwBlV81aPVY3RW@oOl?zA^4%lOFvK+crtJ9!@{Y!fz0@Su1M9~8tkQp z(@VtSEiAL*3**rvjtej(zCnx#fQ4v{VmyjALLyWAoCLh|+$pehs$lYr_95!Q891yo zA{Uh4q^~FbqMJ>MC4H_zCzA5|+UZ%A>9nw;p;p&5>=x=Fzty!h1NTkca2&kPuve>> zdF=|CT=1=EOw`9lcWt*cUtqvJz11_j-Ik4f-SiA>cQtE|rd<7?Q|@rdYDU)ST$0&e zFV4|!|5~Cjf#E?PBFv`Z9R&^B34>o3?b@(wyvI+JafaN#VIZU!&ok+2FD-rKUaojW zxM<%CKJRhliMMCh5fPbBV3s^?#QCd`ygsFo{C`LrKXMp1C~(tPZz=i{$~Fmi zL3@%3vzK+{kN2;{X$mtj8NI5(wE*&_e)w~$h|?Hi?p8UM@6p8j7C2W6@~6|x3cK5g z26Xe32O>wOWbj@S2Z;NQ22ZgIht+oMGW;NpbP&Y7xK$RnL>%^!I$gXRg7&hc`JSMC jBiff3^jzU$FzrVNOgq)lGw75X_1pgdNb9S-WP~k) zuD0c|<-FWqe=GSNOh{j@PxCZQ>f+ti>ZjF8+FjAX%#RpyUBn3WrP=jrJ-WOct!MM= z=IwO3f`5myCRZ7kqt&{(8r@DO6&ag^*kUw%9?I=FjEL6`Lb?r+7s--CTzri@Jd|zh zpx9-y6z%BaD!|xYxx~id++W828f}KMgWL$qzcnOjFq=pGU-&d3TLL&|eh@RRD3TtK z8-uU>f~ybR|H2sa_RO(eXkaIxwkR(9kPu>v~lsPjZ|** zdP`9uxguMDH4nJoMKXJ9-p4?1Ek`J-+gQ+)Ykgvmzm;w0>7g6CXQ}=!lI0HfqfhzcM*pH zjqo{)3?qMuw06I#5R^=r(E;}FvQATc52 zeZ(P_C}53ulvp(-gV+4lYyY7Wlt37?)3Vp#7Kafp%X#Q;8V+ScmOSF~Pg+NoHu2UW zPeVB^bPO(0#8&75+cW=*+AVQJ;q`;suL8L+o3-ys{u_nGS_PT@sJ5p=?4QCBk%1y9XomSt_fv^a^E9xaf3D zJ@3#isY+I@{%J$`c7C}YT}%&HdWp3`vAskL9PNB`Gr3n)LsI~GfI`Ba6YrCyh|%Dj zuxKcY*YIg(yLh}qAyB}|&_S7^3kr0ZuNKfgzgaJC)(O2*>`{jDYIgm{?E0dHsqQfo z>MeB{+Je%*rptM1o-4|yATv&NUOd4|U34h_K3)ECe>uCFt*4W;^#_bt9OA6>JBIWt zM7IP#CIlco($KZnA@U=bR8O*86v0sctWf1l8sr6s(JQdX4!NTAJbJ=WK3gQZ1rzfb z%t;#*;gP@P6z-uCBQ7hww{tA*Dwq^>dmr`S928atkr7I8l1245-EI>s$$Jet0-mOB zx;?|tyG`6xP_tucW)t<0)9jdvhWomzb-Os<)Y{eVg#%a6WQ4CpqoY37Ivca8I2;4+ zsm-3==`>B`sJg9Tv!fUVnsWDpc6q`F>+vFARS4Gm175({Ih27eXNBJfL|l%5bE13* z%nAe)$Lv|Ax#>1Hc7Maoft$UqhMS6_SSspo?9K+sk}s|!xK@cePJ~&yhaGto*bjS$ z@f4twebb|q?Sxa1@=}mkPWp&K+sE8*SMv|+)b;r$O#GO}(IN)ZCd5f{WwJ>2z+6>v zr-Gj#pnx6a-b(iH`wiW+Am)%I6f=5BQMO+v`WEOJA`!a`xS*zXN#9^66iZ7if%NJo zWo7PA}Abf|e7ClaDr~Gb@77AITlH(L&aX46s$**} zIksNw*m~KqwHn7(l|#qQM)2<0zr1Hd{P{T`SR`3RD16u8QS>T+tOtvxpX$y;?e0vf zWhloPWzEU$1!(tU*FBRav(@PQayltKm4#;$A*vX?4RVm#bT%4`%cekYG%*r z<4p&`OdI+!tc@n5`rjy(K$wUxkbq%kzU2}hrC!08R)szKhj=mDrL1h#P4ENc{;I+xC6XY*=KA`&rZiXmp-LMr*pcYx%UMVwkj4d*=Ngvm1JiB+Y=K0T9< z0Kqnf;E!v9`|3Ik4t2|(*P%9M(zRPI$qX}2a+Bz zEzVh$QC3u(5Ie1{YLM5;W_leMz8yl!F!z^qL#v8vnOVzYo{{9Z;2P0$#IQFlyFpqZ z%I5W$K<+5K(<}M_Q&Metz^JsirYt*;YMLEzYus|L**+s{;ZwFe)~JqGc4%HB+A~Lm zdj67wRvW$`QbM{ut>|T`OqV658)yphZS{V>T1~`C%;_4?^%{By=td3Q1bVli?*#?t zH1=&2J}+G4V+A%VBtncd2M9P78rdX*j~3?fMY_#-V0ZYKZQ2bXn#RtsA>D-bcw zn$APACD}HLc_0MKhK0mpMfT#j{F_#X^p~)!_1M+7fL*J{uDu29dOddiEnx4|WAD5L z>_$Cy<1Jt}>#>_}0eiO|d-o^B&I_BM4lrdQz7>?-Z^bvHt6)?P29gN~YQ1$unuo4g z6s)%(jZ->CzhkOOzpI-EqiuY;B9XP9VPItK?gI=46=qT!>GhV`O^>JAGxDwxM|i!^ z7gHgHT$esxAwNd$N3z}Jb)$6j{G7kbPy96Q&f{55D<^qPHN6lz`s68-DChC!ca0$X zSk{~qSK{_+WZRHLMOD@WW-HAjYWeeOz?&Fk(B3corFGemY?3T5EtuXc$0#VO&$$Qy zq>nxhXZBFGsMm@^__a{bf)L>WKhuzf$odSblfwBprLGHV=_~o=j@N|oqI=drDq1|i z{PO#~8=vsvA-KDUaHFiseb}UZ8n^QgX=Rn=w6L5YKEiAfFK}Dal$c&8mj8RfH4or% z$kVZtgUr-OIK|a=stPnr) ztOX{mAUDh8CbxSrGsl~kP2O6SIA1$SWgVxT@Fn#5)o2-Jo5@`P;vAU9!r$ GG5`R*JpS$g diff --git a/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.installation.problem b/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.installation.problem new file mode 100644 index 0000000000000000000000000000000000000000..7535e418bad715d83d6faa98038c6f4aa3a44f3a GIT binary patch literal 2544 zcmVS-WP~k) zuD0c|<-FWqe=GSNOh{j@PxCZQ>f+ti>ZjF8+FjAX%#RpyUBn3WrP=jrJ-WOct!MM= z=IwO3f`5myCRZ7kqt&{(8r@DO6&ag^*kUw%9?I=FjEL6`Lb?r+7s--CTzri@Jd|zh zpx9-y6z%BaD!|xYxx~id++W828f}KMgWL$qzcnOjFq=pGU-&d3TLL&|eh@RRD3TtK z8-uU>f~ybR|H2sa_RO(eXkaIxwkR(9kPu>v~lsPjZ|** zdP`9uxguMDH4nJoMKXJ9-p4?1Ek`J-+gQ+)Ykgvmzm;w0>7g6CXQ}=!lI0HfqfhzcM*pH zjqo{)3?qMuw06I#5R^=r(E;}FvQATc52 zeZ(P_C}53ulvp(-gV+4lYyY7Wlt37?)3Vp#7Kafp%X#Q;8V+ScmOSF~Pg+NoHu2UW zPeVB^bPO(0#8&75+cW=*+AVQJ;q`;suL8L+o3-ys{u_nGS_PT@sJ5p=?4QCBk%1y9XomSt_fv^a^E9xaf3D zJ@3#isY+I@{%J$`c7C}YT}%&HdWp3`vAskL9PNB`Gr3n)LsI~GfI`Ba6YrCyh|%Dj zuxKcY*YIg(yLh}qAyB}|&_S7^3kr0ZuNKfgzgaJC)(O2*>`{jDYIgm{?E0dHsqQfo z>MeB{+Je%*rptM1o-4|yATv&NUOd4|U34h_K3)ECe>uCFt*4W;^#_bt9OA6>JBIWt zM7IP#CIlco($KZnA@U=bR8O*86v0sctWf1l8sr6s(JQdX4!NTAJbJ=WK3gQZ1rzfb z%t;#*;gP@P6z-uCBQ7hww{tA*Dwq^>dmr`S928atkr7I8l1245-EI>s$$Jet0-mOB zx;?|tyG`6xP_tucW)t<0)9jdvhWomzb-Os<)Y{eVg#%a6WQ4CpqoY37Ivca8I2;4+ zsm-3==`>B`sJg9Tv!fUVnsWDpc6q`F>+vFARS4Gm175({Ih27eXNBJfL|l%5bE13* z%nAe)$Lv|Ax#>1Hc7Maoft$UqhMS6_SSspo?9K+sk}s|!xK@cePJ~&yhaGto*bjS$ z@f4twebb|q?Sxa1@=}mkPWp&K+sE8*SMv|+)b;r$O#GO}(IN)ZCd5f{WwJ>2z+6>v zr-Gj#pnx6a-b(iH`wiW+Am)%I6f=5BQMO+v`WEOJA`!a`xS*zXN#9^66iZ7if%NJo zWo7PA}Abf|e7ClaDr~Gb@77AITlH(L&aX46s$**} zIksNw*m~KqwHn7(l|#qQM)2<0zr1Hd{P{T`SR`3RD16u8QS>T+tOtvxpX$y;?e0vf zWhloPWzEU$1!(tU*FBRav(@PQayltKm4#;$A*vX?4RVm#bT%4`%cekYG%*r z<4p&`OdI+!tc@n5`rjy(K$wUxkbq%kzU2}hrC!08R)szKhj=mDrL1h#P4ENc{;I+xC6XY*=KA`&rZiXmp-LMr*pcYx%UMVwkj4d*=Ngvm1JiB+Y=K0T9< z0Kqnf;E!v9`|3Ik4t2|(*P%9M(zRPI$qX}2a+Bz zEzVh$QC3u(5Ie1{YLM5;W_leMz8yl!F!z^qL#v8vnOVzYo{{9Z;2P0$#IQFlyFpqZ z%I5W$K<+5K(<}M_Q&Metz^JsirYt*;YMLEzYus|L**+s{;ZwFe)~JqGc4%HB+A~Lm zdj67wRvW$`QbM{ut>|T`OqV658)yphZS{V>T1~`C%;_4?^%{By=td3Q1bVli?*#?t zH1=&2J}+G4V+A%VBtncd2M9P78rdX*j~3?fMY_#-V0ZYKZQ2bXn#RtsA>D-bcw zn$APACD}HLc_0MKhK0mpMfT#j{F_#X^p~)!_1M+7fL*J{uDu29dOddiEnx4|WAD5L z>_$Cy<1Jt}>#>_}0eiO|d-o^B&I_BM4lrdQz7>?-Z^bvHt6)?P29gN~YQ1$unuo4g z6s)%(jZ->CzhkOOzpI-EqiuY;B9XP9VPItK?gI=46=qT!>GhV`O^>JAGxDwxM|i!^ z7gHgHT$esxAwNd$N3z}Jb)$6j{G7kbPy96Q&f{55D<^qPHN6lz`s68-DChC!ca0$X zSk{~qSK{_+WZRHLMOD@WW-HAjYWeeOz?&Fk(B3corFGemY?3T5EtuXc$0#VO&$$Qy zq>nxhXZBFGsMm@^__a{bf)L>WKhuzf$odSblfwBprLGHV=_~o=j@N|oqI=drDq1|i z{PO#~8=vsvA-KDUaHFiseb}UZ8n^QgX=Rn=w6L5YKEiAfFK}Dal$c&8mj8RfH4or% z$kVZtgUr-OIK|a=stPnr) ztOX{mAUDh8CbxSrGsl~kP2O6SIA1$SWgVxT@Fn#5)o2-Jo5@`P;vAU9!r$ GG5`R*JpS$g literal 0 HcmV?d00001 diff --git a/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.variables b/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.variables index c444be6180074e45a4dfeaf289e10f87ab33d802..c5cba975e172dead9e6631c4cbd703ecb8977be2 100644 GIT binary patch delta 45 zcmWFunV_Swe3{0MC2HCdv$Q3oB4$QK%#_f!*xjZfAt^Ca>*Z}mhKaIHM;sX#7yxNL B4x|78 delta 45 zcmWFunV_SQGDYjh)9IQLQrZ$y5t5QoGbOYvcDHFrNJ`AqdU>0Xp+xUbydwhx0{~mw B4oUz3 diff --git a/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.variables.problem b/my_dual_robot_cell/my_dual_robot_cell_control/dual-arm-simulator/persistent_storage_bob/programs/default.variables.problem new file mode 100644 index 0000000000000000000000000000000000000000..c444be6180074e45a4dfeaf289e10f87ab33d802 GIT binary patch literal 84 zcmb2|=3sz;%^%Nb>v^6z>8W$_%z18aol`zOr#yATG)|uJW$k({c0;Q*Ws261r_(hh kq_icZA|xfFW=d#T>~7PLkd&CI_3}0&Ly6v>ct@aN0RG_}hX4Qo literal 0 HcmV?d00001 diff --git a/my_dual_robot_cell/my_dual_robot_cell_control/launch/rsp.launch.py b/my_dual_robot_cell/my_dual_robot_cell_control/launch/rsp.launch.py index bc0d8d5..d665ab7 100644 --- a/my_dual_robot_cell/my_dual_robot_cell_control/launch/rsp.launch.py +++ b/my_dual_robot_cell/my_dual_robot_cell_control/launch/rsp.launch.py @@ -104,7 +104,7 @@ def generate_launch_description(): "ur20", "ur30", ], - default_value="ur3e", + default_value="ur5e", ) ) declared_arguments.append( diff --git a/my_dual_robot_cell/my_dual_robot_cell_description/launch/view_robot.launch.py b/my_dual_robot_cell/my_dual_robot_cell_description/launch/view_robot.launch.py index 4a8c477..3506ecd 100644 --- a/my_dual_robot_cell/my_dual_robot_cell_description/launch/view_robot.launch.py +++ b/my_dual_robot_cell/my_dual_robot_cell_description/launch/view_robot.launch.py @@ -19,10 +19,10 @@ def generate_launch_description(): description_file, " ", "alice_ur_type:=", - "ur3", + "ur3e", " ", "bob_ur_type:=", - "ur3", + "ur5e", ] ), value_type=str, diff --git a/my_dual_robot_cell/my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro b/my_dual_robot_cell/my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro index 899c25e..9a54ac5 100644 --- a/my_dual_robot_cell/my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro +++ b/my_dual_robot_cell/my_dual_robot_cell_description/urdf/my_dual_robot_cell_macro.xacro @@ -86,7 +86,7 @@ - + diff --git a/my_robot_cell/doc/assemble_urdf.rst b/my_robot_cell/doc/assemble_urdf.rst index fbf675f..1c5831f 100644 --- a/my_robot_cell/doc/assemble_urdf.rst +++ b/my_robot_cell/doc/assemble_urdf.rst @@ -27,7 +27,7 @@ First, we'll have to **include** the macro to generate our custom workcell: :end-at: :caption: my_robot_cell_description/urdf/my_robot_cell.urdf.xacro -This line only loadeded the macro for generating the robot workcell. +This line only loads the macro for generating the robot workcell. We will need to provide some parameters to our workcell in order to parametrize the arm. Therefore, we need to declare certain arguments that must be passed to the macro. From 7ac29778ba0f0cd24f8908cbba821d3fd4026db1 Mon Sep 17 00:00:00 2001 From: Jacob Larsen Date: Mon, 12 Jan 2026 08:20:50 +0000 Subject: [PATCH 2/8] sphinx configuration for robot cell tutorial --- my_robot_cell/doc/conf.py | 82 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 82 insertions(+) create mode 100644 my_robot_cell/doc/conf.py diff --git a/my_robot_cell/doc/conf.py b/my_robot_cell/doc/conf.py new file mode 100644 index 0000000..80d8726 --- /dev/null +++ b/my_robot_cell/doc/conf.py @@ -0,0 +1,82 @@ +project = "ur_custom_workcell_tutorial" +copyright = "2025, Universal Robots A/S" +author = "Felix Exner" + +# The short X.Y version +version = "" +# The full version, including alpha/beta/rc tags +release = "" + +# -- General configuration --------------------------------------------------- + +# If your documentation needs a minimal Sphinx version, state it here. +# +# needs_sphinx = '1.0' + +# Add any Sphinx extension module names here, as strings. They can be +# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom +# ones. +extensions = [] + +# Add any paths that contain templates here, relative to this directory. +templates_path = ["_templates"] + +# The suffix(es) of source filenames. +# You can specify multiple suffix as a list of string: +# +source_suffix = [".rst"] + +# The master toctree document. +master_doc = "index" + +numfig = True + +# The language for content autogenerated by Sphinx. Refer to documentation +# for a list of supported languages. +# +# This is also used if you do content translation via gettext catalogs. +# Usually you set "language" from the command line for these cases. +language = "en" + +# List of patterns, relative to source directory, that match files and +# directories to ignore when looking for source files. +# This pattern also affects html_static_path and html_extra_path. +exclude_patterns = ["_build", "Thumbs.db", ".DS_Store", "migration/*.rst"] + +# The name of the Pygments (syntax highlighting) style to use. +pygments_style = None + + +# -- Options for HTML output ------------------------------------------------- + +# The theme to use for HTML and HTML Help pages. See the documentation for +# a list of builtin themes. +# +html_theme = "alabaster" + +# Theme options are theme-specific and customize the look and feel of a theme +# further. For a list of options available for each theme, see the +# documentation. +# +# html_theme_options = {} + +# Add any paths that contain custom static files (such as style sheets) here, +# relative to this directory. They are copied after the builtin static files, +# so a file named "default.css" will overwrite the builtin "default.css". +# html_static_path = ["_static"] + +# Custom sidebar templates, must be a dictionary that maps document names +# to template names. +# +# The default sidebars (for documents that don't match any pattern) are +# defined by theme itself. Builtin themes are using these templates by +# default: ``['localtoc.html', 'relations.html', 'sourcelink.html', +# 'searchbox.html']``. +# +# html_sidebars = {} + + +# -- Options for HTMLHelp output --------------------------------------------- + +# Output file base name for HTML help builder. +htmlhelp_basename = "ur_custom_workcell_tutorial_doc" From 54920bd123ba515c42739b54768593382a5976cd Mon Sep 17 00:00:00 2001 From: Jacob Larsen Date: Mon, 12 Jan 2026 09:12:07 +0000 Subject: [PATCH 3/8] pre-commit changes --- my_dual_robot_cell/doc/index.rst | 2 +- my_dual_robot_cell/doc/start_ur_driver.rst | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/my_dual_robot_cell/doc/index.rst b/my_dual_robot_cell/doc/index.rst index 0580c5b..24a2c6d 100644 --- a/my_dual_robot_cell/doc/index.rst +++ b/my_dual_robot_cell/doc/index.rst @@ -19,4 +19,4 @@ all files relevant for this example. assemble_urdf start_ur_driver - build_moveit_config \ No newline at end of file + build_moveit_config diff --git a/my_dual_robot_cell/doc/start_ur_driver.rst b/my_dual_robot_cell/doc/start_ur_driver.rst index d81d4e5..6c99a4e 100644 --- a/my_dual_robot_cell/doc/start_ur_driver.rst +++ b/my_dual_robot_cell/doc/start_ur_driver.rst @@ -132,4 +132,4 @@ Or to use it with a real robot: ros2 launch my_dual_robot_cell_control start_robots.launch.py bob_ur_type:=ur10e bob_use_mock_hardware:=true \ bob_kinematics_parameters_file:=$(ros2 pkg prefix ur_description)/share/ur_description/config/ur10e/default_kinematics.yaml \ alice_ur_type:=ur20 alice_use_mock_hardware:=true \ - alice_kinematics_parameters_file:=$(ros2 pkg prefix ur_description)/share/ur_description/config/ur20/default_kinematics.yaml \ No newline at end of file + alice_kinematics_parameters_file:=$(ros2 pkg prefix ur_description)/share/ur_description/config/ur20/default_kinematics.yaml From 23a68a83449dfb55d1bf3e26f9fae229e7c64891 Mon Sep 17 00:00:00 2001 From: Jacob Larsen Date: Mon, 12 Jan 2026 09:20:45 +0000 Subject: [PATCH 4/8] Get images from figures folder --- my_dual_robot_cell/doc/assemble_urdf.rst | 2 +- my_dual_robot_cell/doc/build_moveit_config.rst | 16 ++++++++-------- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/my_dual_robot_cell/doc/assemble_urdf.rst b/my_dual_robot_cell/doc/assemble_urdf.rst index 47223f7..527bb18 100644 --- a/my_dual_robot_cell/doc/assemble_urdf.rst +++ b/my_dual_robot_cell/doc/assemble_urdf.rst @@ -109,5 +109,5 @@ We can view our custom workspace by running: Use the sliders of the ``joint_state_puplisher_gui`` to move the virtual robots around. It should look something like this: -.. image:: rviz.png +.. image:: figures/rviz.png :alt: RViz window showing the custom workspace diff --git a/my_dual_robot_cell/doc/build_moveit_config.rst b/my_dual_robot_cell/doc/build_moveit_config.rst index cd242d2..3510784 100644 --- a/my_dual_robot_cell/doc/build_moveit_config.rst +++ b/my_dual_robot_cell/doc/build_moveit_config.rst @@ -25,7 +25,7 @@ Although the Setup Assistant is very straightforward, there are some tips and tr The first task the MoveIt! Setup Assistant asks us to do is to load the URDF with the optional xacro arguments. If you would like to change the ``ur_type`` for example, you could also specify that here. For this demonstration we'll go with our description's default values. -.. image:: load_urdf.png +.. image:: figures/load_urdf.png :alt: Load a URDF Next, make sure that the generated **self-collisions** are detected correctly. In our example the robot @@ -33,7 +33,7 @@ is positioned on the table in such a way, that it collides with the monitor on t joints are in the 0 position. Hence, the collision is allowed as "Collision by default". We remove that tick, since we don't want that collision to be ignored. -.. image:: self_collisions.png +.. image:: figures/self_collisions.png :alt: Adjust self-collisions - Remove the tick for the collision between monitor and ur20_upper_arm_link. @@ -41,15 +41,15 @@ We skip adding virtual joints for now and continue with our **planning group(s)* We add a planning group called **ur_arm**. A reasonable and error-resistant approach is to define it as a kinematic chain in the following manner: -.. image:: planning_group_kinematics.png +.. image:: figures/planning_group_kinematics.png :alt: Kinematic setup for our planning group -.. image:: planning_group_chain.png +.. image:: figures/planning_group_chain.png :alt: Kinematic Chain Your planning groups should look something like this: -.. image:: planning_groups.png +.. image:: figures/planning_groups.png :alt: Planning Groups We'll skip setting up ros2_control related points, since we've already configured that in our @@ -58,7 +58,7 @@ control package. In the **MoveIt Controllers** step we setup our desired controller to match the name "scaled_joint_trajectory_controller": -.. image:: moveit_controllers.png +.. image:: figures/moveit_controllers.png :alt: MoveIt! coontrollers configuration We skip **perception** as we don't have any cameras setup in our scenario. @@ -69,13 +69,13 @@ are for starting a demo using mock hardware, which would basically be a duplicat already did in our control package. Since we also do not use the Warehouse feature for now, we also skip that file. -.. image:: launch_files.png +.. image:: figures/launch_files.png :alt: Select the launch files to be generated After the **Author information** we select which configuration files to generate. Again, we strip down all the files needed for mock hardware startup. -.. image:: config_files.png +.. image:: figures/config_files.png :alt: Select the config files to be generated With all the information entered, you can **generate** the package and close the setup assistant. From addf7198069d23a4b25c56372d40c392c8136f42 Mon Sep 17 00:00:00 2001 From: Jacob Larsen Date: Mon, 12 Jan 2026 09:21:05 +0000 Subject: [PATCH 5/8] Fix title lining --- my_dual_robot_cell/doc/index.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/my_dual_robot_cell/doc/index.rst b/my_dual_robot_cell/doc/index.rst index 24a2c6d..d26d624 100644 --- a/my_dual_robot_cell/doc/index.rst +++ b/my_dual_robot_cell/doc/index.rst @@ -2,9 +2,9 @@ .. _dual_arm_tutorial: -================ +=================== Dual robot arm cell -================ +=================== Example about integrating two UR arms into a custom workspace. We will build a custom workcell description containing two robot arms, start the driver and create a MoveIt config to enable trajectory planning with MoveIt. From 204f2d4bf4a6e66216ae32bef6829fa6961e49a2 Mon Sep 17 00:00:00 2001 From: Jacob Larsen Date: Mon, 12 Jan 2026 09:35:21 +0000 Subject: [PATCH 6/8] Fix xacro reference --- my_dual_robot_cell/doc/start_ur_driver.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/my_dual_robot_cell/doc/start_ur_driver.rst b/my_dual_robot_cell/doc/start_ur_driver.rst index 6c99a4e..6196c5e 100644 --- a/my_dual_robot_cell/doc/start_ur_driver.rst +++ b/my_dual_robot_cell/doc/start_ur_driver.rst @@ -25,7 +25,7 @@ This URDF is very similar to the one we have already assembled. We simply need t .. literalinclude:: ../my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro :language: xml :start-at: - :end-at: + :end-at: :caption: my_dual_robot_cell_control/urdf/my_dual_robot_cell_controlled.urdf.xacro define the necessary arguments that need to be passed to the macro, From 8b091a964e0cca6db4af8c01d59f8167fec02da3 Mon Sep 17 00:00:00 2001 From: Jacob Larsen Date: Wed, 21 Jan 2026 09:32:09 +0000 Subject: [PATCH 7/8] Remove MoveIt! guide from dual arm docs --- .../doc/build_moveit_config.rst | 154 ------ my_dual_robot_cell/doc/index.rst | 6 +- .../.setup_assistant | 10 - .../CMakeLists.txt | 11 - .../config/initial_positions.yaml | 15 - .../config/joint_limits.yaml | 70 --- .../config/kinematics.yaml | 8 - .../config/moveit.rviz | 484 ------------------ .../config/moveit_controllers.yaml | 32 -- .../config/my_dual_robot_cell.srdf | 91 ---- .../config/pilz_cartesian_limits.yaml | 6 - .../launch/dual_ur_moveit.launch.py | 78 --- .../package.xml | 41 -- tutorial_index.rst | 1 + 14 files changed, 6 insertions(+), 1001 deletions(-) delete mode 100644 my_dual_robot_cell/doc/build_moveit_config.rst delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/.setup_assistant delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/CMakeLists.txt delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/initial_positions.yaml delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/joint_limits.yaml delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/kinematics.yaml delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/moveit.rviz delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/moveit_controllers.yaml delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/my_dual_robot_cell.srdf delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/pilz_cartesian_limits.yaml delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/launch/dual_ur_moveit.launch.py delete mode 100644 my_dual_robot_cell/my_dual_robot_cell_moveit_config/package.xml diff --git a/my_dual_robot_cell/doc/build_moveit_config.rst b/my_dual_robot_cell/doc/build_moveit_config.rst deleted file mode 100644 index 3510784..0000000 --- a/my_dual_robot_cell/doc/build_moveit_config.rst +++ /dev/null @@ -1,154 +0,0 @@ -:github_url: https://github.com/UniversalRobots/Universal_Robots_ROS2_Tutorials/blob/main/my_dual_robot_cell/doc/build_moveit_config.rst - - -======================== -Build the MoveIt! config -======================== - -At this point, you should be able to run the ``ur_robot_driver`` for your custom UR setup. -Now, we are only one last step away from actually planning and executing trajectories. - -To utilize MoveIt! 2 for this purpose, which will handle trajectory planning for us, we need to set up a MoveIt! configuration package. -To create such a MoveIt! `configuration package `_, MoveIt! provides a very useful Setup Assistant. - -Setup Assistant ---------------- - -We can start the MoveIt! Setup Assistant by running: - -.. code-block:: bash - - ros2 launch moveit_setup_assistant setup_assistant.launch.py - -Please note that MoveIt! itself provides a detailed `tutorial `_ on how to use the Setup Assistant, so you may want to go through that. -Although the Setup Assistant is very straightforward, there are some tips and tricks we want to discuss in the following sections. - -The first task the MoveIt! Setup Assistant asks us to do is to load the URDF with the optional xacro arguments. If you would like to change the ``ur_type`` for example, you could also specify that here. For this demonstration we'll go with our description's default values. - -.. image:: figures/load_urdf.png - :alt: Load a URDF - -Next, make sure that the generated **self-collisions** are detected correctly. In our example the robot -is positioned on the table in such a way, that it collides with the monitor on the table when all -joints are in the 0 position. Hence, the collision is allowed as "Collision by default". We remove -that tick, since we don't want that collision to be ignored. - -.. image:: figures/self_collisions.png - :alt: Adjust self-collisions - Remove the tick for the collision between monitor and ur20_upper_arm_link. - - -We skip adding virtual joints for now and continue with our **planning group(s)**. -We add a planning group called **ur_arm**. A reasonable and error-resistant approach is to define -it as a kinematic chain in the following manner: - -.. image:: figures/planning_group_kinematics.png - :alt: Kinematic setup for our planning group - -.. image:: figures/planning_group_chain.png - :alt: Kinematic Chain - -Your planning groups should look something like this: - -.. image:: figures/planning_groups.png - :alt: Planning Groups - -We'll skip setting up ros2_control related points, since we've already configured that in our -control package. - -In the **MoveIt Controllers** step we setup our desired controller to match the name -"scaled_joint_trajectory_controller": - -.. image:: figures/moveit_controllers.png - :alt: MoveIt! coontrollers configuration - -We skip **perception** as we don't have any cameras setup in our scenario. - -In the next step we modify the **launch files** being generated by the assistant. We only generate -"RViz Launch and Config", "MoveGroup Launch" and "Setup Assistant Launch". The other launch files -are for starting a demo using mock hardware, which would basically be a duplication of what we -already did in our control package. Since we also do not use the Warehouse feature for now, we also -skip that file. - -.. image:: figures/launch_files.png - :alt: Select the launch files to be generated - -After the **Author information** we select which configuration files to generate. Again, we strip -down all the files needed for mock hardware startup. - -.. image:: figures/config_files.png - :alt: Select the config files to be generated - -With all the information entered, you can **generate** the package and close the setup assistant. - -Manual adaptions ----------------- - -Before we can actually use our package we have to adapt the joint limits. Since MoveIt! requires -joint acceleration limits to be specified but the description doesn't contain those, we need to -specify these inside the generated ``config/joint_limits.yaml`` file. - -They are not part of the arm's description since there are no physical acceleration limits, as -those are highly dependent on the robot's current pose and TCP force (e.g. induced by the weight -carried at the TCP). Setting the acceleration limits to ``5.0`` for all joints should be a -conservative value. Higher values might lead to unwanted slowdowns during execution or even -protective stops, while lower values will result in slower motions due to slow ramp-up and -ramp-down parts of the trajectory. - -.. literalinclude:: ../my_dual_robot_cell_moveit_config/config/joint_limits.yaml - :language: yaml - :linenos: - :caption: my_dual_robot_cell_moveit_config/config/joint_limits.yaml - -Please note that you could also change the default velocity and acceleration scaling in this file. -Also, if you want to specify any limits (position or velocity) that differ from your description, you -can set them here. Remember that these will only be used for planning trajectories, not necessarily -for execution. If you send trajectories from another source than MoveIt!, those limits will not -apply! - - -Usage ------ - -Before we can test our code, it's essential to build and source our Colcon workspace: - -.. code-block:: bash - - #cd to your colcon workspace root - cd ~/colcon_ws - - #source and build your workspace - colcon build - source install/setup.bash - - -Now you are ready to use MoveIt! with two actual robot arms, MoveIt! itself also provides you with the opportunity to start a robot with mock hardware. - -To startup the complete system, you'll have to start three launch files in three individual -terminals. - -First, we need to start a robot, simulated or real. If you start a real robot, make sure that the -*external_control* program is active on the robot. - -.. code-block:: bash - - # You can switch to real hardware if you prefer - ros2 launch my_dual_robot_cell_control start_robots.launch.py bob_use_mock_hardware:=true alice_use_mock_hardware:=true - - - -Second, we can start the move_group node by running the launch file the setup assistant created for us: - -.. code-block:: bash - - ros2 launch my_dual_robot_cell_moveit_config move_group.launch.py - -If everything went well you should see the output: **"You can start planning now!"**. - -To interact with the MoveIt! setup, you can start RViz with the correct setup file: - -.. code-block:: bash - - ros2 launch my_dual_robot_cell_moveit_config moveit_rviz.launch.py - -From that setup you can start developing your application involving a custom move_group interface -or similar. Please refer to the MoveIt! documentation for further reading. diff --git a/my_dual_robot_cell/doc/index.rst b/my_dual_robot_cell/doc/index.rst index d26d624..a834a74 100644 --- a/my_dual_robot_cell/doc/index.rst +++ b/my_dual_robot_cell/doc/index.rst @@ -19,4 +19,8 @@ all files relevant for this example. assemble_urdf start_ur_driver - build_moveit_config + +MoveIt! Configuration +--------------------- +For inspiration on how to configure MoveIt! 2 using the setup assistant, please see the `single arm robot cell tutorial +`_ diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/.setup_assistant b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/.setup_assistant deleted file mode 100644 index 44d47a0..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/.setup_assistant +++ /dev/null @@ -1,10 +0,0 @@ -moveit_setup_assistant_config: - urdf: - package: my_dual_robot_cell_description - relative_path: urdf/my_dual_robot_cell.urdf.xacro - srdf: - relative_path: config/my_dual_robot_cell.srdf - package_settings: - author_name: Vihaan Shah - author_email: vihaan.shah@uconn.edu - generated_timestamp: 1719324402 diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/CMakeLists.txt b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/CMakeLists.txt deleted file mode 100644 index 0cb4e73..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/CMakeLists.txt +++ /dev/null @@ -1,11 +0,0 @@ -cmake_minimum_required(VERSION 3.22) -project(my_dual_robot_cell_moveit_config) - -find_package(ament_cmake REQUIRED) - -ament_package() - -install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} - PATTERN "setup_assistant.launch" EXCLUDE) -install(DIRECTORY config DESTINATION share/${PROJECT_NAME}) -install(FILES .setup_assistant DESTINATION share/${PROJECT_NAME}) diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/initial_positions.yaml b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/initial_positions.yaml deleted file mode 100644 index 27a6a59..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/initial_positions.yaml +++ /dev/null @@ -1,15 +0,0 @@ -# Default initial positions for my_dual_robot_cell's ros2_control fake system - -initial_positions: - alice_elbow_joint: 0 - alice_shoulder_lift_joint: 0 - alice_shoulder_pan_joint: 0 - alice_wrist_1_joint: 0 - alice_wrist_2_joint: 0 - alice_wrist_3_joint: 0 - bob_elbow_joint: 0 - bob_shoulder_lift_joint: 0 - bob_shoulder_pan_joint: 0 - bob_wrist_1_joint: 0 - bob_wrist_2_joint: 0 - bob_wrist_3_joint: 0 diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/joint_limits.yaml b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/joint_limits.yaml deleted file mode 100644 index bdb5311..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/joint_limits.yaml +++ /dev/null @@ -1,70 +0,0 @@ -# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed - -# For beginners, we downscale velocity and acceleration limits. -# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. -default_velocity_scaling_factor: 0.1 -default_acceleration_scaling_factor: 0.1 - -# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration] -# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits] -joint_limits: - alice_elbow_joint: - has_velocity_limits: true - max_velocity: 3.1415926535897931 - has_acceleration_limits: true - max_acceleration: 5.0 - alice_shoulder_lift_joint: - has_velocity_limits: true - max_velocity: 3.1415926535897931 - has_acceleration_limits: true - max_acceleration: 5.0 - alice_shoulder_pan_joint: - has_velocity_limits: true - max_velocity: 3.1415926535897931 - has_acceleration_limits: true - max_acceleration: 5.0 - alice_wrist_1_joint: - has_velocity_limits: true - max_velocity: 6.2831853071795862 - has_acceleration_limits: true - max_acceleration: 5.0 - alice_wrist_2_joint: - has_velocity_limits: true - max_velocity: 6.2831853071795862 - has_acceleration_limits: true - max_acceleration: 5.0 - alice_wrist_3_joint: - has_velocity_limits: true - max_velocity: 6.2831853071795862 - has_acceleration_limits: true - max_acceleration: 5.0 - bob_elbow_joint: - has_velocity_limits: true - max_velocity: 3.1415926535897931 - has_acceleration_limits: true - max_acceleration: 5.0 - bob_shoulder_lift_joint: - has_velocity_limits: true - max_velocity: 3.1415926535897931 - has_acceleration_limits: true - max_acceleration: 5.0 - bob_shoulder_pan_joint: - has_velocity_limits: true - max_velocity: 3.1415926535897931 - has_acceleration_limits: true - max_acceleration: 5.0 - bob_wrist_1_joint: - has_velocity_limits: true - max_velocity: 6.2831853071795862 - has_acceleration_limits: true - max_acceleration: 5.0 - bob_wrist_2_joint: - has_velocity_limits: true - max_velocity: 6.2831853071795862 - has_acceleration_limits: true - max_acceleration: 5.0 - bob_wrist_3_joint: - has_velocity_limits: true - max_velocity: 6.2831853071795862 - has_acceleration_limits: true - max_acceleration: 5.0 diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/kinematics.yaml b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/kinematics.yaml deleted file mode 100644 index 195e5a9..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/kinematics.yaml +++ /dev/null @@ -1,8 +0,0 @@ -alice_manipulator: - kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.0050000000000000001 - kinematics_solver_timeout: 0.0050000000000000001 -bob_manipulator: - kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin - kinematics_solver_search_resolution: 0.0050000000000000001 - kinematics_solver_timeout: 0.0050000000000000001 diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/moveit.rviz b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/moveit.rviz deleted file mode 100644 index 2cbcdc6..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/moveit.rviz +++ /dev/null @@ -1,484 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 87 - Name: Displays - Property Tree Widget: - Expanded: ~ - Splitter Ratio: 0.4957627058029175 - Tree Height: 380 - - Class: rviz_common/Selection - Name: Selection - - Class: rviz_common/Tool Properties - Expanded: - - /2D Goal Pose1 - - /Publish Point1 - Name: Tool Properties - Splitter Ratio: 0.5886790156364441 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Acceleration_Scaling_Factor: 0.1 - Class: moveit_rviz_plugin/MotionPlanning - Enabled: true - Move Group Namespace: "" - MoveIt_Allow_Approximate_IK: false - MoveIt_Allow_External_Program: false - MoveIt_Allow_Replanning: false - MoveIt_Allow_Sensor_Positioning: false - MoveIt_Planning_Attempts: 10 - MoveIt_Planning_Time: 5 - MoveIt_Use_Cartesian_Path: false - MoveIt_Use_Constraint_Aware_IK: false - MoveIt_Workspace: - Center: - X: 0 - Y: 0 - Z: 0 - Size: - X: 2 - Y: 2 - Z: 2 - Name: MotionPlanning - Planned Path: - Color Enabled: true - Interrupt Display: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - alice_base: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_base_link_inertia: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_flange: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_ft_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_robot_mount: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_shoulder_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_tool0: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_wrist_1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_wrist_2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_wrist_3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_base: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_base_link_inertia: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_flange: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_ft_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_robot_mount: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_shoulder_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_tool0: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_wrist_1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_wrist_2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_wrist_3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - monitor: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - table: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wall: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - world: - Alpha: 1 - Show Axes: false - Show Trail: false - Loop Animation: false - Robot Alpha: 0.5 - Robot Color: 150; 50; 150 - Show Robot Collision: false - Show Robot Visual: true - Show Trail: false - State Display Time: 0.05 s - Trail Step Size: 1 - Trajectory Topic: /display_planned_path - Use Sim Time: false - Planning Metrics: - Payload: 1 - Show Joint Torques: false - Show Manipulability: false - Show Manipulability Index: false - Show Weight Limit: false - TextHeight: 0.07999999821186066 - Planning Request: - Colliding Link Color: 255; 0; 0 - Goal State Alpha: 1 - Goal State Color: 250; 128; 0 - Interactive Marker Size: 0 - Joint Violation Color: 255; 0; 255 - Planning Group: alice_manipulator - Query Goal State: true - Query Start State: false - Show Workspace: false - Start State Alpha: 1 - Start State Color: 0; 255; 0 - Planning Scene Topic: monitored_planning_scene - Robot Description: robot_description - Scene Geometry: - Scene Alpha: 0.8999999761581421 - Scene Color: 50; 230; 50 - Scene Display Time: 0.009999999776482582 - Show Scene Geometry: true - Voxel Coloring: Z-Axis - Voxel Rendering: Occupied Voxels - Scene Robot: - Attached Body Color: 150; 50; 150 - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - alice_base: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_base_link_inertia: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_flange: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_ft_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_robot_mount: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_shoulder_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_tool0: - Alpha: 1 - Show Axes: false - Show Trail: false - alice_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_wrist_1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_wrist_2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - alice_wrist_3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_base: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_base_link_inertia: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_flange: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_forearm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_ft_frame: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_robot_mount: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_shoulder_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_tool0: - Alpha: 1 - Show Axes: false - Show Trail: false - bob_upper_arm_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_wrist_1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_wrist_2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - bob_wrist_3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - monitor: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - table: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - wall: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - world: - Alpha: 1 - Show Axes: false - Show Trail: false - Robot Alpha: 1 - Show Robot Collision: false - Show Robot Visual: true - Value: true - Velocity_Scaling_Factor: 0.1 - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: world - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/Interact - Hide Inactive Objects: true - - Class: rviz_default_plugins/MoveCamera - - Class: rviz_default_plugins/Select - - Class: rviz_default_plugins/FocusCamera - - Class: rviz_default_plugins/Measure - Line color: 128; 128; 0 - - Class: rviz_default_plugins/SetInitialPose - Covariance x: 0.25 - Covariance y: 0.25 - Covariance yaw: 0.06853891909122467 - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /initialpose - - Class: rviz_default_plugins/SetGoal - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /goal_pose - - Class: rviz_default_plugins/PublishPoint - Single click: true - Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /clicked_point - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 4.587055683135986 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0.4825928509235382 - Y: 0.6104342937469482 - Z: 1.4097795486450195 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.41039803624153137 - Target Frame: - Value: Orbit (rviz) - Yaw: 4.133575916290283 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 1016 - Hide Left Dock: false - Hide Right Dock: false - MotionPlanning: - collapsed: false - MotionPlanning - Trajectory Slider: - collapsed: false - QMainWindow State: 000000ff00000000fd0000000400000000000001f30000039efc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000210000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000253000001880000017d00ffffff00000001000001100000039efc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d0000039e000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004710000039e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Selection: - collapsed: false - Tool Properties: - collapsed: false - Views: - collapsed: false - Width: 1920 - X: 0 - Y: 27 diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/moveit_controllers.yaml b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/moveit_controllers.yaml deleted file mode 100644 index 01b20bc..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/moveit_controllers.yaml +++ /dev/null @@ -1,32 +0,0 @@ -# MoveIt uses this configuration for controller management - -moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager - -moveit_simple_controller_manager: - controller_names: - - alice_scaled_joint_trajectory_controller - - bob_scaled_joint_trajectory_controller - - alice_scaled_joint_trajectory_controller: - type: FollowJointTrajectory - action_ns: follow_joint_trajectory - default: true - joints: - - alice_shoulder_pan_joint - - alice_shoulder_lift_joint - - alice_elbow_joint - - alice_wrist_1_joint - - alice_wrist_2_joint - - alice_wrist_3_joint - - bob_scaled_joint_trajectory_controller: - type: FollowJointTrajectory - action_ns: follow_joint_trajectory - default: true - joints: - - bob_shoulder_pan_joint - - bob_shoulder_lift_joint - - bob_elbow_joint - - bob_wrist_1_joint - - bob_wrist_2_joint - - bob_wrist_3_joint diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/my_dual_robot_cell.srdf b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/my_dual_robot_cell.srdf deleted file mode 100644 index 70480a0..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/my_dual_robot_cell.srdf +++ /dev/null @@ -1,91 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/pilz_cartesian_limits.yaml b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/pilz_cartesian_limits.yaml deleted file mode 100644 index b2997ca..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/config/pilz_cartesian_limits.yaml +++ /dev/null @@ -1,6 +0,0 @@ -# Limits for the Pilz planner -cartesian_limits: - max_trans_vel: 1.0 - max_trans_acc: 2.25 - max_trans_dec: -5.0 - max_rot_vel: 1.57 diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/launch/dual_ur_moveit.launch.py b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/launch/dual_ur_moveit.launch.py deleted file mode 100644 index 875ab92..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/launch/dual_ur_moveit.launch.py +++ /dev/null @@ -1,78 +0,0 @@ -import os -from pathlib import Path - -import yaml -from ament_index_python.packages import get_package_share_directory -from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, ExecuteProcess, RegisterEventHandler -from launch.conditions import IfCondition -from launch.event_handlers import OnProcessExit -from launch.substitutions import LaunchConfiguration, PathJoinSubstitution -from launch_ros.actions import Node -from launch_ros.substitutions import FindPackageShare -from moveit_configs_utils import MoveItConfigsBuilder - - -def load_yaml(package_name, file_path): - package_path = get_package_share_directory(package_name) - absolute_file_path = os.path.join(package_path, file_path) - - try: - with open(absolute_file_path) as file: - return yaml.safe_load(file) - except OSError: # parent of IOError, OSError *and* WindowsError where available - return None - - -def generate_launch_description(): - moveit_config = MoveItConfigsBuilder( - "my_dual_robot_cell", package_name="my_dual_robot_cell_moveit_config" - ).to_moveit_configs() - - move_group_configuration = { - "publish_robot_description_semantic": True, - "allow_trajectory_execution": True, - "publish_planning_scene": True, - "publish_geometry_updates": True, - "publish_state_updates": True, - "publish_transforms_updates": True, - } - - move_group_params = [ - moveit_config.to_dict(), - move_group_configuration, - ] - - move_group_node = Node( - package="moveit_ros_move_group", - executable="move_group", - output="screen", - parameters=move_group_params, - additional_env={"DISPLAY": ":0"}, - ) - - rviz_config_file = PathJoinSubstitution( - [FindPackageShare("my_dual_robot_cell_moveit_config"), "config", "moveit.rviz"] - ) - - rviz_node = Node( - package="rviz2", - executable="rviz2", - name="rviz2_moveit", - output="log", - arguments=["-d", rviz_config_file], - parameters=[ - moveit_config.robot_description, - moveit_config.robot_description_semantic, - moveit_config.robot_description_kinematics, - moveit_config.planning_pipelines, - moveit_config.joint_limits, - ], - ) - - return LaunchDescription( - [ - move_group_node, - rviz_node, - ] - ) diff --git a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/package.xml b/my_dual_robot_cell/my_dual_robot_cell_moveit_config/package.xml deleted file mode 100644 index ae4308f..0000000 --- a/my_dual_robot_cell/my_dual_robot_cell_moveit_config/package.xml +++ /dev/null @@ -1,41 +0,0 @@ - - - - my_dual_robot_cell_moveit_config - 0.3.0 - - An automatically generated package with all the configuration and launch files for using the my_dual_robot_cell with the MoveIt Motion Planning Framework - - Vihaan Shah - - BSD-3-Clause - - http://moveit.ros.org/ - https://github.com/ros-planning/moveit2/issues - https://github.com/ros-planning/moveit2 - - Vihaan Shah - - ament_cmake - - moveit_ros_move_group - moveit_kinematics - moveit_planners - moveit_simple_controller_manager - joint_state_publisher - joint_state_publisher_gui - tf2_ros - xacro - moveit_configs_utils - moveit_ros_move_group - moveit_ros_visualization - my_dual_robot_cell_description - rviz2 - rviz_common - rviz_default_plugins - - - - ament_cmake - - diff --git a/tutorial_index.rst b/tutorial_index.rst index 22fcaae..506f065 100644 --- a/tutorial_index.rst +++ b/tutorial_index.rst @@ -14,3 +14,4 @@ Example tutorials :titlesonly: my_robot_cell/doc/index.rst + my_dual_robot_cell/doc/index.rst From 97a32ad6bd4708cfd25d86354ade6d3b0a8cec29 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Fri, 30 Jan 2026 14:28:06 +0100 Subject: [PATCH 8/8] Apply suggestions from code review --- my_dual_robot_cell/doc/assemble_urdf.rst | 2 +- my_dual_robot_cell/doc/start_ur_driver.rst | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/my_dual_robot_cell/doc/assemble_urdf.rst b/my_dual_robot_cell/doc/assemble_urdf.rst index 527bb18..faccb71 100644 --- a/my_dual_robot_cell/doc/assemble_urdf.rst +++ b/my_dual_robot_cell/doc/assemble_urdf.rst @@ -7,7 +7,7 @@ The `ur_description `_ for all other files assembling the description package. +`_ for all other files assembling the description package. Workcell description -------------------- diff --git a/my_dual_robot_cell/doc/start_ur_driver.rst b/my_dual_robot_cell/doc/start_ur_driver.rst index 6196c5e..19db314 100644 --- a/my_dual_robot_cell/doc/start_ur_driver.rst +++ b/my_dual_robot_cell/doc/start_ur_driver.rst @@ -56,7 +56,7 @@ For now, we just copy the default ones for the UR3e and UR5e. cp $(ros2 pkg prefix ur_description)/share/ur_description/config/ur3e/default_kinematics.yaml \ my_dual_robot_cell_control/config/alice_calibration.yaml - cp $(ros2 pkg prefix ur_description)/share/ur_description/config/ur5e/default_kinematics.yaml \ + cp $(ros2 pkg prefix ur_description)/share/ur_description/config/ur5e/default_kinematics.yaml \ my_dual_robot_cell_control/config/bob_calibration.yaml