From fdaa4869d81957e51a8e549413fb465ede4f14ad Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Wed, 8 Oct 2025 22:29:41 +0800 Subject: [PATCH 01/11] Beginning experimental feature for ros2 support Signed-off-by: Michael X. Grey --- Cargo.toml | 10 + README.md | 54 +++ examples/ros2/Cargo.toml | 33 ++ examples/ros2/README.md | 48 +++ examples/ros2/assets/figures/nav-example.png | Bin 0 -> 41822 bytes examples/ros2/package.xml | 22 ++ examples/ros2/src/fake_plan_generator.rs | 121 +++++++ examples/ros2/src/goal_requester.rs | 124 +++++++ examples/ros2/src/nav_example.rs | 332 +++++++++++++++++++ package.xml | 22 ++ ros2-feature.repos | 37 +++ src/lib.rs | 5 + src/ros2.rs | 19 ++ 13 files changed, 827 insertions(+) create mode 100644 examples/ros2/Cargo.toml create mode 100644 examples/ros2/README.md create mode 100644 examples/ros2/assets/figures/nav-example.png create mode 100644 examples/ros2/package.xml create mode 100644 examples/ros2/src/fake_plan_generator.rs create mode 100644 examples/ros2/src/goal_requester.rs create mode 100644 examples/ros2/src/nav_example.rs create mode 100644 package.xml create mode 100644 ros2-feature.repos create mode 100644 src/ros2.rs diff --git a/Cargo.toml b/Cargo.toml index df663f88..38ccf547 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -71,6 +71,10 @@ zenoh = { version = "1.3.2", features = ["unstable"], optional = true } zenoh-ext = { version = "*", features = ["unstable"], optional = true } # --- end zenoh +# --- Dependencies for ros2 feature +rclrs = { git = "https://github.com/ros2-rust/ros2_rust", branch = "main", optional = true } +# --- end ros2 + tracing = "0.1.41" strum = { version = "0.26.3", optional = true, features = ["derive"] } semver = { version = "1.0.24", optional = true } @@ -110,6 +114,10 @@ zenoh = [ "dep:futures-lite", ] +ros2 = [ + "dep:rclrs", +] + # Turn on all capability related features. This differs from --all-features # because it would not include single_threaded_async which has a diminishing # effect on capabilities. @@ -118,6 +126,7 @@ maximal = [ "trace", "grpc", "zenoh", + "ros2", ] [dev-dependencies] @@ -130,6 +139,7 @@ test-log = { version = "0.2.16", features = [ members = [ "examples/diagram/calculator", "examples/zenoh-examples", + "examples/ros2", "diagram-editor", "diagram-editor/wasm", "examples/diagram/calculator_wasm", diff --git a/README.md b/README.md index 288a36d3..0be364de 100644 --- a/README.md +++ b/README.md @@ -5,6 +5,60 @@ [![Crates.io Version](https://img.shields.io/crates/v/bevy_impulse)](https://crates.io/crates/bevy_impulse) +> [!IMPORTANT] +> You are on a branch with experimental support for ROS 2 via [`rclrs`](https://github.com/ros2-rust/ros2_rust). +> This will require more steps to set up than usual, so installation instructions for the necessary packages are below: + +1. Install ROS Jazzy according to the [normal installation instructions](https://docs.ros.org/en/jazzy/Installation.html). + +2. Install Rust according to the [normal installation instructions](https://www.rust-lang.org/tools/install). + +3. Run these commands to set up the workspace with the message bindings: + +```bash +sudo apt install -y git libclang-dev python3-pip python3-vcstool # libclang-dev is required by bindgen +``` + +```bash +pip install git+https://github.com/colcon/colcon-cargo.git --break-system-packages +``` + +```bash +pip install git+https://github.com/colcon/colcon-ros-cargo.git --break-system-packages +``` + +Create a workspace with the necessary repos: + +```bash +mkdir -p workspace/src && cd workspace +``` + +```bash +git clone https://github.com/open-rmf/bevy_impulse src/bevy_impulse -b ros2 +``` + +```bash +vcs import src < src/bevy_impulse/ros2-feature.repos +``` + +Source the ROS distro and build the workspace: + +```bash +source /opt/ros/jazzy/setup.bash +``` + +```bash +colcon build +``` + +4. After `colcon build` has finished, you should see a `.cargo/config.toml` file inside your workspace, with `[patch.crates-io.___]` sections pointing to the generated message bindings. Now you should source the workspace using + +```bash +source install/setup.bash +``` + +Now you can run the [ROS 2 example](examples/ros2/README.md). You can also create your own crate in this colcon workspace and link as shown in the example. + # Reactive Programming for Bevy This library provides sophisticated [reactive programming](https://en.wikipedia.org/wiki/Reactive_programming) for the [bevy](https://bevyengine.org/) ECS. In addition to supporting one-shot chains of async operations, it can support reusable workflows with parallel branches, synchronization, races, and cycles. These workflows can be hierarchical, so a workflow can be used as a building block by other workflows. diff --git a/examples/ros2/Cargo.toml b/examples/ros2/Cargo.toml new file mode 100644 index 00000000..555bf4ef --- /dev/null +++ b/examples/ros2/Cargo.toml @@ -0,0 +1,33 @@ +[package] +name = "ros2-workflow-examples" +edition = "2021" +version = "0.0.1" + +[[bin]] +name = "nav-example" +path = "src/nav_example.rs" + +[[bin]] +name = "fake-plan-generator" +path = "src/fake_plan_generator.rs" + +[[bin]] +name = "goal-requester" +path = "src/goal_requester.rs" + +[dependencies] +bevy_app = "0.12" +bevy_core = "0.12" +bevy_impulse = { path = "../..", features = ["diagram", "ros2"] } +serde = "*" +schemars = "*" +serde_json = "*" +tokio = { version = "1.39", features = ["sync"] } +clap = { version = "*", features = ["derive"] } +rand = "*" + +rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "worker", features = ["serde"] } +nav_msgs = { version = "*", features = ["serde"] } +geometry_msgs = { version = "*", features = ["serde"] } +std_msgs = { version = "*", features = ["serde"] } +builtin_interfaces = { version = "*", features = ["serde"] } diff --git a/examples/ros2/README.md b/examples/ros2/README.md new file mode 100644 index 00000000..5177b3e3 --- /dev/null +++ b/examples/ros2/README.md @@ -0,0 +1,48 @@ +## Building workflows with ROS nodes + +The examples in this directory showcase how to incorporate ROS primitives into a workflow. We model a small portion of a navigation workflow that involves receiving goals, fetching paths to connect those goals from a planning service, and then queuing up the paths for execution. + +This diagram represents the workflow implemented by `src/nav_example.rs`: + +![nav-example-workflow](assets/figures/nav-example.png) + +After following the build instructions in the [root README](../../README.md), run this example with the following steps: + +1. Source the workspace with + +```bash +source install/setup.bash # run in the root of your colcon workspace +``` + +2. Then you can go into this `examples/ros2` directory and run the example with + +```bash +cargo run --bin nav-example # run in this directory +``` + +3. The `nav-example` workflow will wait until it receives some goals to process. You can send it some randomized goals by **opening a new terminal** in the same directory and running + +```bash +source install/setup.bash # run in the root of your colcon workspace +``` + +```bash +cargo run --bin goal-requester # run in this directory +``` + +Now the workflow will print out all the plans that it has received from the `fake-plan-generator` and stored in its buffer. If the workflow were connected to a real navigation system, it could pull these plans from the buffer one at a time and execute them. + +4. Our workflow also allows the paths to be cleared out of the buffer, i.e. "cancelled". To cancel the current set of goals, run: + +```bash +cargo run --bin goal-requester -- --cancel +``` + +After that you should see a printout of + +``` +Paths currently waiting to run: +[] +``` + +which indicates that the buffer has been successfully cleared out. diff --git a/examples/ros2/assets/figures/nav-example.png b/examples/ros2/assets/figures/nav-example.png new file mode 100644 index 0000000000000000000000000000000000000000..1e41af96613b6e5532295cb2c9c741351e5712bb GIT binary patch literal 41822 zcmZ_0by(DG7d6TZB_JU!2#g?z(k;>mh|)+69Ro-VA<|MRU4uxcNT&?lC^ZO((%qnR zgY>z1-sgSKIp1}Cf8piuo8O&#uf5jVgsQ7PB_^aJ#KOWNex@j=iG>A4V_`v9Z{UId zq1}V5U}5=VJ(H8s@-W^=BWP4!zUoqIL2p}f7*sRg`?w+YpfZf}f&BL}?HuiASp!)T zniERlC4cYk>MF8QK2WMI4i&D<{C(A!u^Zu%k>uSsB_?qEBW=5D{fz&2>hDxhm#tox zncrt`GPXze<(Oj>?~#Z8-+r)fJ$^pvSIO|1E4sQ-(jw{5J}>RRzyGlW`aJpw`b9r~ z{vZgM{ALE>v~StRggi0oaj#UdDbMQQ=t~gxtL=Wvc3~$4Zzy!oZ6)$AkuLf73)ttO z(z{=%^N&@VI=SL&JaP_$MkXg5Y>J{x@eN9CPP8j{Ql<^+OqTh*uHK|${qHdusQ7-` z-q?dG!B*9m4RxDed0V~Y?3&6Cf3OiHPw5oH%gK#fpK$PU{5!3%lp8GULw^<(E+)^% ztTKr5lFD`L418Yf2P9WDNqf9)E&lI-a?zh~5ch-*pNL-D#(`sjeL#6C|szE3vI8hF01fMEBPtn_vUk{vA57CXcFGU$hv`Jk#M#?7Y~`h ze@9Plsqdk%Kk8Yn+E6W3eIZ8NemSP#3Lor{E;eDhIEY!RE=;k#c(SexLH2Cx`z}-M zCt?NB=v|LBYb;+n0BUgP_gq#5r3X}@iq&%zO!B`uD~iKm1WB_q|R<)(daySyPN>gzMczD|y! z3T2K>5R;Dobg`)aW^#duM(`c%%(W9{SLM+E*ma*&q)5k3U;ZW-gw&$d#pTI#>_7X+ z{^Ea+3Y*kzEw9=B5ucN_sszuyJZ2uYcFhP`uukE!5!TIk;;i5&Ddejq8~lHzB){PCgm@}wT}=33D-x#{4N9@!_M#7 zO^VK*dR#r8&?osCB2Wb0WPQbWc)s#myFq)CJ%o(<<$6Tf;2_ab9MwOQv-@|1=P)J4 zQFLF6!(|-NmvSh)216&?_)4g) zHVRsmwGr!ItVo&EI0Zp#>zCM8jpL4a1Z)(mRA}wz^bNkJNtHZ2;7j)}W-mwY5PIA) zZ~KE|Gspf@V+VC>i-@ct!FGp$~3F3+eMpzlB8Wh0;USLuJ#7unlWp%zS9gxYh;9JOsr zX(4BkMRY%2<|lI@bM?#Y(%2NLNB-zzA9_;mE-Bm(Yxx@m(ZSN0AIMQkSe3Z2+GB#>@Z!mkemx&kpCfkdRSiK8LIkUGy z7w$vG+a?;^%gpmv^D=y2iR66zgQ_KY{Wq)apB=7SBq$j_Pg$`u3hBFv;U2G-b4?r3 zPCNOPR5-q1Rk(c2)yH>ktk*K^lfzw5^W95xT#3?T*9bq$zd%zZMHu;dIZl^xs@B=! z#+%TN5xkqUJ9a(sTs%8aipRS_N+AL4&EzNv&I>_;;(Q{W#-Gz4HNEBoX?k60MPFq% zJjhvQmBKKKe_FPaGVp#+l=RD=Gqx_sM_5@XbwpjrXh^HdaD30nW`eh?L%#%h=soWh zXyEnXi4LX7$rHjvExp}z@2#Z6jf(yt=>)xv%{2EJ(Vw56M!Pq*V%wRiHKMaTl%$Wo z;2^NcQN%nv?*7FDJU?sV@xY~S{t>8xjh;o^L=TRrzSz7PH5N*r)vMC;WhaS0&{w4m zu*++HwWfD5qb>eGjU%jV1Ba)vJf|w{&3Z}A<=(h;M&R`uk>hB~LX#HXltWjkUql|3 zCrw0{uz!{uyiieExbgZ%PA%DEfz}R5=^5TqXtlrh`#%tDZ)SP;mL8MHj4)v>S z`&Yj+{L-z&1g37&Hn2^{{BCZ=*`)ZkW^@@;L_?@DM>#C~kff$$gjH*(@~uZPD9 z{_jjeQl9f6UDsNSt~Lc>4F!>Fm07U`7|RYssdGr(A zLodj7#MDo@UCJ3L*_Sss^0PN1W}3Ws#EuX1%&s%R_@|Qk%j;$^4dKk5{u}-y)UbISbOg)*iSXPrDaUsEPC8h+l1A zU8<#dt|Wau(ks#_8PYZJiOXf^*^qME&=a!irFA{u?aC9)5Sj5{QSq*{=pso^)t+he zRA~_R+{^FbX)%zbR~oh9YA+q@wc;w)%=axZGC^7p&s8!S1jw#kskCS)A!;u z*DpiD+s#RW;^lVTZ^prvC`O5i;vOU{{P52&Y*a~JNh-}w#D9-k7&T%yN~g?tdSkH8 z#TpwGEqR*%c=_Xt-g*OvI#!i4_ZiQp&Q0OeT!mYW`>KZv;XH-luq0LIJdfkQDuY+B zjrk5_KU+(*h|-V`qtpNz8-lWZ4jhecSSKo(!?KiF?tt^N{tX{ABcg|OR17NQ z-fg(_OIV-&Jf8KFLeP&?+PoMph70UJmO$mG-Cvp;)-};KsJ15%#jA62j`(Q>0@2!} zV~a|~#bUISj@0?iyA!|jzq@A9w|K;G(8P_>FY#l=a1rvmvHlxo@y0#AlM8u2Xoh*a`#rYMP(O#Bb5d>lP+GS>w+TmCK( zEy|Z@7sV6Ym8M3NgWrLvc&|fh*9wc?t}}Z5xm!UJU2FnQ7XMtYFl4-P?-dP(*@3gY zO#A1^M&+nlim8RwZhi7jfJ#g-+24}kHJui%TJ$$AV=VLT2i=j%_nyDUf-kh5%xI5} zi2s6lkHD>yVtCz~gi>KgRYd3p_iY^-qt`Lcim7fBHiggQ9u|7+F65fjoc)~5aQa5j z36aIft`6i3|9Z;AaIk0IDAhI3*uU$HuKoSbQsj9DG~=QyaTKL>D47T_j5>m_vr!Yj z0w^wFJ~``iT1D56SpKflZNDqKc7hyy+7feN=+IaA({> zX8f&v+GE$$c*u?=y|G165HWqSs{=cB{d^ET4x$ay;{yxdP|47%7Eo@`3+<5zg`)2)msla54ppE%NG%epZPJty#Rcd7}4F7HaW!1FD zfp_Tbeq{xYt3JX;!+I!cIU0-Y+m!rw7RX7%gCC{d2*_;mx7YWqqd?pep=IlGTC~n} zPO*JbBr$+6i`^DVWOOnUO0Ci#T#FXSP2($Dg0q&5oQdo~W9>sCW1XNH^e*Ur5~9nSaS!jGCx*NO%!A*Q$ISt9(G1BqyY-jmPyV;OGp!zQcj zMp4H~?*W7)e+cq=7#^Y|_)t;jvjXv8I<0QJiQk3mZ$${7S;Qta!uxQI>Q%9mmD%81 z&I%W!662-``wCdkd+c~M$rD7LrL@aR?=u&B4Qb;oTzI=m=gQ2z7*8%F7oj%CP*G=_ zP`V>;`PZ%{skJ6sOzPc+pkAiE;LEGuGgs>u$m!8F)e^xk1H6$%X|87iP0}ZDa|%}X z>^~uNElypi1RDF^;sip(v65KGcmp?QAkGUp2lAmoD79pponPd<#Edu0VXIWp+RPZ@Wz)M2_-K` z|3h`}`pd1T#Rjv@B9I-?W$hBrL5jB007 za%;|GYpU++7va=9m%=`$2e(jEIk`9pQVu$l{E|zKgixbVOmrOb^}Ux@mlswZA@SwJkTeBhzdZMXx%Y_1KdoPYrp8LKKGh^TEr!~*L#Ja@t)h=g+zudhh~F535Y z{xGS<@n4zvwFs1Zpg1R=TBON&pk ze`P(%+J{+lRw#$^unIuBz8WZf#o=(c%+{JO@SJN6SPQ^sR0q(hdG(|H_abnk@FoWd z#`ir}a}pwGj;7sbg=}i{`~a-Qn^Yh|w_F^h6dKl{;r(@Q_PX!q##*v*W`rI>(KgFD z+!(sPL_UiUCIsAVGDPkdyCy1<+|~sLLw@Ai#o&%}=4Q9Fee^rRRfd|(@?MlyWVXrD zWox^kpQ`>I%HSz}l1oTz)n|{X`!88w9M5lqFdUCN&XRQamf0$L;v3ZWGu+7kf-C5?>2g4?w>K@;95+_GJ9Q0w1mU#PN_#9OVJ+B}%O;{tBw z-AVK$4nm$F4kXCU=>`!5zxJauuv$|_D!-ruI!%Wo2DZ!JI`EuHM|TBl@qg}RvAR;OE)zLD~VTNKu~mLLSKAifdSM2KM<`OnhWOTWkEea)oCk|gx?%$Qd19?#t0-Nh$I-2`le7zz{>N`>4~ z=twZB&wnG8*zT#S-lJmY;8GQF0xrece`9z1T7ro$U#r*IW=)FIJB`l@@{}()zWe@X zX_#pcCj903pZE&Lk>wFF!_{g`+f{rOB9%w4ej>{LyC59o@@#6-I?}?=mfmvqIHaUz zqV{_~ZvM4Be~ZNK>c0s5{)+vnC6}T+7!j-1E)-s<&DW4Ie$e~&w_iNzokykv&qL+9 z|NRO|XhSuY2XUzQxY$Q~E|ZHV1!F8Q)4QJL4_OtCk2mf3>1iy1e2lI?!d zbz}<@!a%?Huj`7nXnq!n(y1wHFfyu|e<<|w0w(loQSos1D0;Ze@7#7koZx5Jhi8C* z@VEcKjzi``gyEi&JkG%t^NP-BU{qI88z)3(Yi9o;j=NJb&MaWhQuV1p%}XKY>8lSf z;^Qr!55KzeJ);5X^5J^*3iSdw)x$ffdo?MjwCSCkQ z75YKue{YMWN7O`RwD>I521;qW9IHJYCqY|h__$%b2xryDV+N|Wst<1RluG(t^F=Hj zP{i)H4|7+mu4+YYDU$`lQq>wr;cC9C2D0^aB_7T-i9qk1v)9FyKst%3|?# zOCK%cP9C>Znx1`3`0XeqlEz`J6auxxQv(Wp_0+t!4Q=_7rOjxf!V z<(>r6-14m0+LM)(Hl3ENpu@f8p6Oxu2uL8-kC`;K;;-XG$~{6z`#lJp_={b>!qLQi zv1s>6g->^g&|C)9T0*u%yk&JyL7}Nn#jf7^kR+$XWU^#e6i@oYoT>KTuWtA8@@ zzBL7(2GzmZR>QUq!{gVyQm=g*C##V})w5{J@Q1pksa^-ap87oPuD`L-pCVFrIv>n5 zrIKa%-#Y^}C&7ou3frCMP3qT83KZPIM`N+iXm8cjOuY(+9}m4yE4Z%pSe4>&CN&le zGs+&w|9Iu~3Ac5pGm^fqUb{%A;9DROJw8cKTQI5abuo3U82{`F+|g)nsb`_Ph0+b~N`0OeycHGcLlVMH~W$jNj8h`)`Er*Q9PJrBHEL ziebEh6>b={t(rqz26I)`D*7drDtL@vOpMcx9Z1LX;#~QvBnxUJ7`_ViRH<{lBVGw_ za6@8FSifDzG;JN}_}BV_BWg<6IsO}MCXyS%Li#6X&s{G%*V}^Vr&`v0DYD24bmQ+E zLw^sZa0WfC)+y0n5t^Av60lAt!NRf{$@gpVIXfyi+5erQ$1GmlOX(^fajW2k{l+c% zn{FFpX6bK5x4<39s&<%O+hY4JzlVdsMa0T=L($Hf0H~~}HFe09IX$RgQ%f)QI$X<9 zmAZJX-RR*QyD6Pf<^}R`?-7`Xcih#Z_nd~Wf61>19kcr&82zZ0RB zzJvBsY=_w$cJpN9&(M425s3UbdLnYT-!GL%lv`Tbd}_PT!us<sleM2c0Q`xUco+rP>8^Sr z61WVk{6E&}Kfckf{Og)dtMs|LIDXfKh3Lk`#B!(g0&e3j<2YsPe=ajQs_z6AP7~j) zf9ZN&dT>IAPtyp}g z!RC^N&wQItU1Gz9H6hvJeJcR#{-Ij#t^ga&mJ@0+Z;rS<@`=k?&X)_|*~;ZEM_dfQ zz>tJgXp9QOzo`r|o=S>-q)t0;fu`;Oj8k19ydt+Q1M72fo6NVpkXtMfi>%}*R^fPW z=DSXu6yZJIe4@#{5?h|_ZU644+u6}(Vb>aC65e>htg3d&N|k2GXpQh0_la+40U>qC zPOb0X`Cu#Im(%sG@6?r|B#NA1>ogR7f7El8ld?+dR_F%f^Yl5S<9~F=`P;Ako1h6W zxwvqvjr)WP%((E@D$ShdE0;3%_JGhEu6172I$RrmCr@#shGh{8S^s*K{1)azPNrIh znGTllwjmsQlRe|?J3ZTK;2EPvEk79jXPtYNVPZA|*$Z^C$D&`7Z=bDR)3Xy2 z&Fs#A9DQrAjZ^`Vu6{Ga_tfUb>(Gvw+8<3`hx!F&-ag3XN~&G3`@32oEb;o|a?s?v zNmVP+AV@Fi6Hi(ej~Q&|h5`z|w&N9cTdQalX_pKjxI9*htcM(1E~qsEd3-r)nE)JehbymAkWml&iz?%IX;FP)+-yn2BMV6VYHrF+Y0ZV`+i5zjLi5m% zn=EpzD>)tEO5O`EOX!5{Uw$J!r)o`XRhW^OnDIT^{Cc<=P+StI!l(}tbOID625Pi; zvsS@}DSQ?RV#l>v?a!r0+7bNOeLvkU-kj{Y)-8l_9PxU7$K@#>8=tCkAwAd_cS&fT z*#!KwJpEk-+$ug~0r{Yuh=!)?hy= z#6FR~ib2>_-O=x|dZNkOy}g5s%vg(``cJfJv0k}3+mwI(Fee4?cE5tOcM4B6qWc5e zkUu<)lL@FVYk)Tvsk0Cz=~{jSxMkw43`Wd^xL@{4mO?fA@pmN%YM5!Cow%aN=uzai zd&Mw(_6`|p({I=z_rDa=U=`|sOtEJ=-G9ZxOV5-dVErS&xXEjCaP&mMr-|M(;4gx0 zif=b6m?(x_@;f1hSr(GWDr)(Qa@a=Y{vr}tQ<+wOyzV^=5AP>j52zZs>^fQt#Z^n3 z+fg*PXtSCB7HA79?X~m$evt|M+q^uLXBan)nPP= zGJe-Z*w&xHy#DQasaZ8n>#V)P6`jRXXNK+C#V84&jExzA^KNkH>QJ<)g&K5PHI}tUDS}DAnDn?RLhbLqjM}){K&AUiG#52 zO>}O=8@Moo9fknqK=jE267&rxXlCL|xl}7+q)Mgh_t^XWIiP0rSsqa0na=#=mVw8+ zmmX&M?LcU1w8{IpDw0mf>j99dBn}RN){Umx*-;-L5?5AyQ_S8RhKpe~1u29>w^Zx% z?wew9=106h&fM(Gwxp6+>GEs8GSnVt+ujKBR) zj-D^VvCWARCNB&uc(4p;USc<%zFaTbBt+`2+*|huJKl-hY0PH*p!sZrpFBAZjPqlwJw>EV0`ewosz?wwTJf;_7@q zx}Y{NA)Z!0rT6wvT+fzkf(5yjzXu{gPY?CjSFWUS0SdgjcCxXuvpg zf|9Dm)<&$4Xh{q?huaw1J`iSUZ+O3yW;Bx0KsmQ)4cFW}X-d1DNV@nvWeE9a51{CN zq+iYf|nRgSXcA4nTJKUDr`niga5k{ zA1Vz*6d~gLtDt}pr}&3vxW0d(s9Lk%kG#!hqK}*Zu2Ne@TGptL@RwRNeu`h*Gxo5C z=$l)2J3bHN77w9qn>UY1YO*qvDrFg^@Lvx2dMP2F)y^IdBg%vpwzmM1X>iEX_={;k zvV?c_1KJ(H+b3xmyr;bZ%0d<6umH{h|HmRXD}(e1-&6hl8kZs@f+Ujj_{8h*NAz2I z^5q4nzRPq+^xP&971vtz;$vuHs6Xt?{osnL#F+%V`>K9CIL6~@Q!Z;Kj0!_eL)2Po z(vrT$xCT;;W?t&6um_s{+NFkYpdJh^*e$hcS}>HIRG3 zrSh@7aR_I8hPyJTe2P(L?sx@a94O|x_FAXLVVceGRW~dB^hY`KTa&YZvb+J!i#BNLVhMpj|Bu`-jmf}}|%fF6--YdG_X&;(FPscW+>ExYHr zg$j{$RK-p@RkqshF7*rZZ-Ys~WDwc&ZNd0V>H`(Ki(M(zYT~=^;WJ;%o=m*EBlG?f zke=M9<{iGPQ+AoQ^!n!Ue@J)>D}q${;|))n%?&%&iGoulNM^Ud(ev@a3w`V{1Hj33 zlsN*XXT^1WguyAcJzU;uN+6!g;HXRDc&efbpdbT-YleyFrom#t@~6AEcvCELIz7Cr zE{cqWoST3fLc)>?vD-dyw=Y$6(8KKF3!(bKnzrV}(WJ)OfRYlvM8(K;wtHv;srcn( z1=h6?s4ZoCD}8p)yEHx5FVD7hLFO%geER2eobNZ0%oJPb+)2tF?{2R^e`29U%=1~T zo9B|?)2&>=dQj1-Gyn}VWuSR}<8!nmKXSWaTXN71$N@hz_^Hc>H=cG>zP#3{lP@sI zx9mJ0+(0Y7TN^Z+6M9+qsJNB1T%M5Xp_T&nM%FDBg>(6g<+n+CE0H?_KFF)JiK=y0 z<4ii5nemT-aG{~IXs?;|Pcm*_8dUC)i-OF<|3>8zgmn$b&~<{SFzrIEXFfYJzQpJ& zjf^)RcyJKq0{!AIe0Do%*m_~fiEwep(}Q8K%u_0OGh+&M6IvAIm^Vj2m!Ft^EeF`s z^XXT~I0%cf)xo?`m-%7qI-z11al0*t%VyPR^BVwJ7%K~KI?U}%d{0<;&(wgtgxRz; z)6skcY(fzLhjfI8;a^`a?Ywj^+Z);GzFwkLPG-i_cExmu79jmHY|Kuk3yqSXpTchQ z>KsFg2A8zS=J-2DSz_`WJT4&%~6(WBO&6d17zcj?6 z2v6%v5s9ANDFbX~(FX1SVm$lw+WusmgbQ!XYb7u}0=J*ek%LjMMdCo6PsmOO3sHkS ziv}F-SmJZpn_0WxjoqhR@$?uymtsPWZu28TY_>aX^|!gy5%P!S6IFI8haKTGB3Iab zzOC4q_3qma)qq}6qvF*2*(kZ)xIcikcwIpNl+joHfmJE_>ZB3j^d;*8Zk1U_$x;m32+wEqObfHNq^u;t_TQajrS_)hGjG2HRq>TC59)UuJ^>?pI|p#A zedDNrh2Q^3X#hTHd<+~tLk-*1TC;u`PqFo9GP(3nx|?HPcO@*85^|?i&q67P=rRGA z_7>W3P#SGpBV-2#$Kn9Wqbr~u7WK~?UHFPk?oX5Z{bhUVd=mRLU$*wds% z+*e7~GJLl#iH~q`(Stmhkf!XOQDYSM*eQ$nQ2P_Cp~b+LO9sEPGH=%HFS^347MAkN z8aUrMF;I$|MJ)#dN_ce1f)7fB9VPX#jj;4t%E85oetfp^q0qb|46hRl=KfcV1=8#v zC1nR0$=6^Z#!w7aMp7aI9>?!C|LyQqR`mvslL(RcVk~91SFV6{D5Q66{ME=-34!Ih z9Ib=h6WI<3zGdWhacGr9hSh>4zm81hvk0}-D3e6!!6>@~BDu*Cj00O0(5KY7kh zc7_1Iyvtc}{&z9@%>Bh+o|;HT20j5oCVufm==C4<3SS@`+l)MA;Rytlk&};5$2Y=6 z88zI`^{3t*D1uz>*YbAamAh%g*5XU`n-pemxM!H|`!{fjMeKvP)i3EYtu~zQVuY#`y+XQu6f zucltgi!TBAZ!VtI%F?!d`ndoE*ZX5^nkd$3iXLvQ)4;rFVemu#^u8<>)@%A>+sL~P zKX%^|aq}YULY*1`m6Q0|ycK;oqJL|hkW!#B3O_Xh$HT^ml^n4v-jG4u_QE!f5u=(e zE;@!cZ)A0GO~b|;p;$L?wgpB@KtYS=G5r?~mScUHh7`BBYcdw@2{84k_XI!gH$t+X za*{6^1Mb_3eRkiTSrPjqt6SO09w}*DuW&_0WE$0p;r-@K@o>qZhh*{b@y7VRiH~Yk zRovmVY31s{E#u7e;~yFpP5o7e?lmB4^Ma$oFW0lg?EhVL!aSr!<1@PcN$=;Cekp}I ztZ?MS0TVG-7wsQh-;1Q1`8e@$pG-KS+MEL<#d;YYU_Pw+TRt8-5VRS%H@LD{GwUXT zD{s$%`a}CgqU!=WHAAO)V=d3B@ZS zoBJLCM=gu2o2dP{MIp2rjZboi7HuLP8SKV*U_acEY6^-REQH#i+glp;cgg(YL_@UO z1jzcqy`b7jIc5!7KtMng%tg6E%(3qAHh4HQF3WNPcJNoB^CJ3dsIglMpw1IXgve1H z6w3DZoRZV+rwRfEiO{8a!*9WL73+=GZI4U4>lpm?WTVucUJ`$|dzCK~*QZ(y(rg9yia(A8pO8Vvj)RUbB#rk82$7=tqOoLfwWF@I837Pc@ zwh;K9tp>8A_PHob{kkb}vEW;rjQRvzdtDXeYjRA_t0_+DPubA*W1Cv)*=2}(@6@?Z z&+SUpH^K9{f+{bmx40?y!yMODjIM*U7W~?5}rPiLHzV{MFZ`tIf|m>4Q~=Qpj@7wLPdy=7Jl!4SBXPXjIX9x4G)#`>Q2wmg#P$9+NBIolI|wpjXMJz zinTkQXsR_psN&M=&fI;Acz_qYD z*>t&+(t%scx*kT%klC{IDfP84=a~$38E5&QnrSzKojZ^49^kCf=;e}TZD+PvBn8`v zcLN+2`Rop#+YN-;sLod+<@#7kLx9;E`H9fN(VWulWL3DDScic$gzKB>0iz0$Q37h4 zT}&qW?unkmvwq%d4cmJ!F`V1`b0fkO2|HwRA1J6H?l();qsatQ{HWTz=XlKh^F})} z7t-=gTAFtq#@~R*KBLo&4 zQDzC)+P>d483Z0x&%!qAcassdN{^*%8YfI?v0HPu0sqP6o#;)6N086- zK=KhPo9;F~AUf!&=IUzYllFT)t1yd^)4$rK<(sFKM*I0#sQ^nexqNZ&TTUojXh9YQ z%WbJNrt-4cH?dvq-}pZfIYM?67}flbwi<|vn!Ka=J8l*0#+y}N`w;d&E3k-Dw)QV4 zm^efX>3XP4&%cqQg~krPe9FnmAi`*v*L&)z)-hlJ9-|Sn{!pKfmU` zL>du7X}Lec&l!jfepb*dBD#^k)3#({>e-4hQiPQ3KQR)DjjlHk7j;Mr$o1$&6h>A= z8HH@MoETyy;a%?@lh&2;dB*;AhmH9#*@-`*pq|^Z39x6z8w1?u&8f$ms*=iDj`C$`$0n7?d{O!GR|`3D zg_*Q4wR(yZinTZlm@02>$Z?1nZU<5S>?eOL-Esna<0-<~EBiH~fYVaZBaMQJmpQOu zqkXZ`8%gldcUqK__}QZ3dGDWkj8Mde<0sx3xLo9e9{hYl+F}1qw=kgCYsSu*eR)Jd zNGnV#L{8&D5iHzaJ$++UIaKCe%fkx&X?r}{yEi=OcIF102W|%wVUvZvN^Yctj052` zdTXd)kcs-?jc0d#1yXN3HKUd|i41^?SDcbjO%%=MTYu^%od|LqL zyn?jQCLS@}#})AhBwzUm&didYl{ZSIn>4m>{r(=2a|aW3XloOaRv2*P;GUv*@9|r6 z2-t*;bO~?er%D^tnctON9=~9_huX=2pS)i3piF$z`l8vxT)vx`M@YI_7MPBYWAsTg zGvCtfPP8jp-IESFs^9#YB_GaxK#s$p;cqXfp27tSAAjwiy<~Cwck6?^RP#*or&tvF zNnZ#KCVUk8y3VoL@&Qq7O3jLE_&VBH%7FG1xd@IKZU6YBzxPJ0#%_JFghD9f616&b=_29@f@n_#!QnPZmarI6>+bYT49CYT+M`?W(iM94V^Pi=e7H@M*K$ zYs@0-%cs3e`56B`@k>2hqVS@Spp=fD4*b z9IiQd1E57nCDvL5FblwxsAB>AKc~Z^jQw^aAQ^=I{<6ls?{>i2dSMBaX-6(tir#;Q zrX(%wEkC2nrpWu?$;XQ294yRAckJ)XG{N_lc!=ADk}HW8B(?sDoOl?`tmMC!&WoK4 zfVUURB>*lUO$cIGuPlM?x3XZ;BTw}I87CY0|-SRzceKFuRMQ7rSm_7Zq6HIMNdH601`h6$KS6E}=49DEe@P5%-E^mQ?`n~Pd%+zwU;?10n|BWZha{L0*}f9ONt#Mu=WY~p7K4rnnaa?bGBXix%pR9n z3a`wFytnd(#I`BcxQj=UV)L74DcrG*O7U~9Sw|!3oHA>c7V7%QWl9Hx0S-vYbRVMt zMc-So{upqykr!RwMTDg|1;FX>*+tfspVjHX>fw}y*EkOPfHZroe*cGb+iCuONze}$ZP)zAoCO={y z3LD;+jvK9HNgpPSkMZZUWExK}jJ{3qD2IWd`&PO^Jjh+^m0E0YV9d{OFrIarM1JiL za4rqukL7&fe(~pXv<|?2IjQ*t%yMx;MV3ABNp7H7;H47-G#lF?1!AW%jv<6F<>?Wy%JL02us>TDnbt9K`ih&2MYwtBZjpgE-Zcdxb`sWj z-GtXVe#QA#`J3nLm=E{kFC%7I0&(-R6sou{nhUSZ5__o)YHsxN`r;oO)-8Z30sv2Q z%lnv9F8%x}7*WVP*Xuqei)2O&)T>ujL0R8+FgFsew#@fFFI2dd+1QZdga05&e}VQr zn3B!YBbIIt1?ZiEIg4nT2be6UPq@?wrMQQdY;W&M8i2JR9)o@Xo=kaieN<6g8E}eE zIy9fGm|B)OEr{W?>;L^p`W!!uilaL9Vj8DJo~9VCnEq@s1meM$tu@|-(nn-sQd^yrv-fbGgC>(^C+s4Z%HL7$LK>Ix(DiJBOz(s2v?uMhVFE2-p z+|%IHs6IX8HUDDW3ah?FKx)-9^mEQ;0NXKLf5YtG%f--T_g6EXzb{;-oV$GT+_{z+ zInuvlA&%`*vNosc=6ilxWxo&L94`M$Jma-qa(D6zXdp@%sCW+$q%;cMx zTSy%@Y#+ycIte;l+LW7#eh*tp$>t{7)0MuZA>H0?xoY;hI2={++n8m8(Wec0l-1I$ z_i0)*3QQxxmW6|Id6lefik-eQDfL@l0KiYyUl<>kD6ec&lE_NLz z*+254SQ&MgOn?RAF@he?UZ00cVM_e7-07#U=We&_?%w$t>hmt=`T4zWViSt~^$dFhd*WlY=$3Gd z;zxOTC|Y!!<(f#D>EdDIDxV=mD{nBXP_LH*A}i^xrvvoY+YPRoDf1|q>4S*(B7rSL zNkrDPs=WXCl^|Jan|E zH0J)j70b>51!grR0}gj@wm4qY^1P18AZQqf@C^u_1kyO}JoO_kV0o(t#d{wb7d{uu z%RF-3pku{|C0YpYv`7KIYJmwvw19d0jaaV0%cP4j)gY<{aJGEN{d>^<_OCS;o6hOX zgA1&iV*j_t77t8Ea7PvAhs)&rIT`gz)qrAs6SfeD{uXzB}`gs?uF&mt~l`5c|-uuq?T@@8cZG7<@2Qvc5$RC5S$^_zh10l~8v0*D%S*$KmFsgc;y*vJowW5dCx*WC`0zwX2TP+wyuQH4;v z@eK@13LI5+cJe|C5^bI48V}#b$0$lu$GnRh6L26@R$TP>Q`U0Hzw4;H2mLTjX_Vc| zT>RCFp;hU7->?L!X`JhO{4v8CYJ}ZL@$L5(4%BZ*92Bk_6xJW%&%En5s}LmnJX&cp zNQSEFYTsX98R{$f$Jl0JuRJ!;B|;j$C2SA+Wv!NigKb~{`ODr4QR#g5-1z0Ii+b4E zN{VByXcQBoJ6%@s!pXVnv)nuT;*U2_9b(VVlS(Q(h;gx4 zGpxX&ju3hOq2f9ew{n_(_cjx@z854iLM^)!KHf3)h<7HK)<_omh(-#d*$Xl&bVctR zdAvDE^Zp0$W~AJe54uYb*_xsRb!(yhkX@p3)sZdy3J(41i?V!0FdA5`{P-E}KV~yN zVFmfWCA;)4HD==Wdj@$t3pIuP9q-vsCa;^MR?K2Y!M?}V|6w^FCkY8$7P$mO*TaF* z-7hNa@2+V5IVo&BxnMy5cop%13X$|tI`6w&B@2Oc6$3AGV}PZfgI;^NUO(an$HMd7 zH>jQ%djCE?yJ(w5)w=Rv?4Jj6iC+PDF9vQ@NmtN5mr^UZFuN0$dtZE9`T<$Lw}2;6 z=DnsUlT<0`=fxZ+>|B^qy>i(mpo!Xo<`^pmktU~aJpu>}nSdyAZ>igg;mQU3Fr3zW zVG|>iO!&_(Et(!3dv>!XB+fFnz!}}(Ru}mipOwYF;p+JUji8tRv#6U1qZOQn05cGc z)t`NYcK)J_!;l|=3Kx{-yt=vZ>8c`{506vpl@;8v=Zs@6SNOj-L|=l6G{N*q_FbG zr}`6tgWzlZsBt^RJRHT`SnhWAo`6C*2uC54meu?q@YZdj=3N~4wOvlp0mZOBZ9agE zJhZC2W`QGs+wBav`{}_J7C_NgzZ3{27b`*6Tch9AB|fHYLsplQSl#lyB>+>o1E0hy z9f`}hkUQyUWibPsuheoo!NjJ(B`JhjH+eb&CFIztLA?I%!_=C%Ki9Zd@E(P|ks?pI4N~C2a)dAGG=O5^#^`G{29K;JirL&3q zdqCBG>KGWL462H4mU5KVF8H_Fzfpd&(E?mPGwz^&Wj4Re-GYZ~M8*T(j8WVW{OJOX z{QnJu4l~h2|6DJt^Fp2x@D4j zCcoW`Va5KT#t6<_w4O5sACc4^1)wJXCllemQ8KZ$d_~-45dOPQr%-CzL3_II%8#IGj_VS(H>!M*p z61r!Q;dPDY8IrtJax!TJptg@4th}!|w*n>ul#zD~>vBKFjTgiL(3>+G( zc8A^bs{JMoB9+i4*VoA%UOrlTz44T9E}Yo%oloGHAqz6$BU9wiZ!@cNDfD zQ;eE^9Px|_gISIunHxlUscHrcOSGz+rU2I5SjmS>@4>ZEDIhg8yY0rMWBOaw@nMySrswMV~$iuBi5AMa`CSM;9x0nPj#49yKBwnGE znFXf5+{~h|{u#Z>(5%8e5{Ko7k_MArW_aywNTCt~dcN)3crCvIU2?fS_Y2gl5$gqD~=a~{1>C?GxUde zGP?IYT6L>L+I^HN{9I+ui z0fFFMAaE*eGgNv(FgyJ9_08TB-667q=F^jVni&$qm7lK8sxSnbdp`H#lX{coyO;XN z0|?bjEy_=0YG(Z;Yh{zXV%S&T{7yCV-PQBBd;5hCkvsRz&SiO=uy=XBiNvDEyXX(% z*}*@ac2n^wupWC4K(sZh@ip6I3CJH-U&hVuHV4>^JoY`BpD6Q#v}6^^>NiTon~ke% zQ%B*VRvnZn08+B1QXFw^fKhhD_;0izVkoa$p@00`AF7A1Gg3Ou6s~%6?eCvzMcQU-OEvye-1%?C`9S85G|Ufs>MjQjnhIr zy1<{|IUjyz9w#guF@4-C{N2A8YMnN$oSG1b^n1E9?zLaf$U?;On$}=?X%1nAW-G8Ficnpt7;(_h3_yvWw%rIIw#Ecs+Mg zvhC-}E4LUQQt)!&o469NAjs*B@vs9Wz@m~5`+o2%?l$nBETkOS5q2D}iN(!v?9EyN z3~GqLG~m6kRQNw~o6F_8OoB2vM7$yIID5)BjCYCRRrynouv;Tl2C|b>I?Ozoh7BQ5 zHOJty*#*$^|JYBrA;NgN9ecwn=s9o}Iw3QF)aYU_gGT1O>*b zJxX=31n{l=4F42=h*0x40HfKkOVxiR>LlWTi&Z`DhRK}#u^QY1$XK+y9B&-B3&gFH z5!9LMPOO|n0PPT=2TA9sBQrRvhJMeu*+zLJdAED6z=ucDl3@w5dF?s7@Fr9g&WCyU z0ud|fCFO;;Cl5g@UqbHKM~V&)-t9jBSr)`mt@flNU&NQ0D>fiYRjIguka+Ngc^8Pf zufiXCq8~l5^5nsONE{@!Zb@9B7s#vJ7%eqV+x4RwRcB%%kB^r*+P*oMTy_Sib{xv% zv{})|ICgmj3h~M$P5iOVxpRg4HWrVM5Izsb9jxs4*2k@<79thv^e$O?q%dRpQasJ! z6jXt49KMHbs_-m0usq&cEtnmQJto>q!CusoTY6iNX)BfCK7U&oVP|#gJ!GubBQ%6+ zSLMViu8?@LGTnG+F<}LwZT=FR+UhRuRr64s{{$wCB1lkHtv zCleTJ^|alRLZmyO25+GfIumjQgab0Q(J2NoRN8T$7c}ZaSI~FM2r5%Gl*9-yh&2*b z^i4`6{y0dLbB&%~6=^+TW;KelR(NTS(~n~hDX`zq{%_tqgc2g%1S!!j^xf&>UIZff z(uc1_B;`dedG1nty$)GEzRDft(8OM$ddtt`6+NdY*+1n#xQB|eHTixE|su&PlP^wEYE zzJRJk88A}W$Tb;_9Ln$E$SrwJguvZ1}A0QxMeLs(TKiX zmiOcsP}1Kui(7vn6CoO1X2-qoffWm|H>xNKbW%cS!xVGUkrZWKyT^HBq4Z{A*?`Ga zc<=o9$>#O_b58X!$iq4#pr#)4b$^|vL5^IZC7Fci;CMZ798x=!l05#em)_5_`<;ND zrAG6LtQJII!nMAT@2&))EG0ip+jHsDm9m$1zF+O*cLu|!)ZG9lfLeO(Paq`a`9W1( zM#mSYq~ZGM=BgRtI^+?7Q|ery4T~C=GDg785i0?}MDJ?Ea@Ah%Obb zg;Oc>`yMW(7YET8Yc9}5;_mG}Ed7wY?yH{L? zlm2TJZQBtstLIi{BG;?klT}-BRkMhI^(aQ6m{GY8vS)Ky`q_)YDAp?Z$}>gN9dyEGbm+Ul$PPda z+?MzpIz+1RkzA3ROSs)Gf5U7yXcXe=E;=B-ypFjnnK=nEM{~F^d|HSF%8QxUMl~c@ zMeN6p&9c#=dWY0oskCvlO4sqnr*M2$4>H1{TY_ZQDf7~Aw9Qz%Vq<F@@v)9rYF(mR3vPGJeqn zgPY%U^bL@hg2)s!S_q2e142ZoGRW`Gq2c zo<09|(0`2K{>x|=fbY)%q?3Ll@<3FXBCF!k+k^?N5yWAsk2JM41i(fr4T8!|d%zz{ zb=};Q@nh5D(370rWn_FSqxyWML_61|cXzq?_4^^*@aEBpwCGNGwNPHyY8&jHCtKdlgTZt66`VQLaEtsv5zCLXb=XRBa0RSGvhe6vkJX|vtF(6|H$w3~ z;@)S$^!PVP30s>7QBm_Z;TTfI9w?^y`8PQgFdr~&*HFgws%%VD37Nlu6!62VfgdrF zoBSJoM?Y_Q+@^UGkg3VI2ij67GQ{XB3q8~2@b{(UD(G=*2-#oJYn39wC&%v_m- z>c)d=>7(sWS0)QTu9Q5E{-|}4)^&6l5y$Zu-=7eFoQ?ZV+*0>Pny&!5PiZn1K}=c% z80)634tck_PF#kJueUV4nJ>(#bJpq?3;I8zL1`pqTo7 zX~yC>TRwOQR07!$hBHr*sQ50%-_lU^ITjV(fDC|kXVo2aqAyzt7gbw zx#VVi|HvsajQ{3==5hJ%gWbLv*=bE37+7yH!s#uTjB(Xw>`4u8FMZpE`byB`$;qM9@1+I^=ZAJj%}a4S z@hU)f=G-eSS_y<*<`vz*u0{C%MN44{~x5jcCZMTb9fBJP!#)ZN%-JdeK5a_TeJ32~RBv-tB+y4>^ss!G76on|ny z*-N^rqW~vF&(qXD$g*j_D=AXSR~3M368+N~6!w)B8m|}kSzMj=T1l&079j@i9JNBra~MeI1ZZ53 z+;MqitO5Ja2*2Mor@*uw#<^DvaP~tv#aom5{y&KJk;TX*mLc#W7|~FualkiHICFIP zoY08*!HLMI$>ZoExB#5NdyU}ucZUq&YojXjQAe^s!%<}5L{HHAXL|Eu*aTu#pgXc) zl1mcNhH*Qa)_x_Jw@Gyf>llvUL#=&*;BihuE_tB}j#GwL>H#9=wgXN_kfyd)=Pbs* z{0MaV+9uHZ6nXe-3Xt}WjuX&w0Kc0*g2MTFKyoVVC z5~E&!j#9M8a6}owfa&@~)%Dsh#N$v-eYJ3wQINg%3r?KJi8skI7_<(k*+3uzk@2SH_hGe_*1kby%V0|8`@?MoPs`z)+2UZRF=qm%j6^&e~i%oa?Cw9sNVVl zSkUX5Ddp8eA9nt^Gob-5RtBz78`=3g&(2>?YX`F?f(i$S(evLEkK;r{wX(F-X)H?J7^tbBN|~wfFEcU2FjjK zNL|4@+krzUhgOH*-TZRpU9vsm-PS2d)#b6jyA!cHr!S9pHfjPMv8#E3&sWM;p3jk@ zaSX}0Az6whVOjTu<`b_a?<$WDM>qbUd1BB;w3QWV8nlX>eRvFm2y!rq%d^UvCgV!C zn78@Fc=<9oVYTr$heh9)Hh0ze)fp*`H4a$n&@#1EJJ2~7dLHl1-7h+OP$8K4q}WbI z!`T1?XndPergk@?%HN*PUyGbvF1lKxb`eWWuAJp4ZL%{R!bB-c5dgr-u#K!A1}odLB$)M_+vp(8|QI5`MW&(wLm*7bizG8LJ9SF z1md0PgHx}A@6J{LgT1Z)LKs9m@yDYmrjSIs2VNl&V)0*TC5NoV=(0DwGKA?Ek-8S3Tye9g>F9Ca4j_Ih1H-N{u^*`d|L`yl1++TWUSdvU~QKvx*?^xHV_GP~Y<{mJ0@( zhwLBkP^0}#n|ni0XysIVBSGq~soOU;B2YxuT`$OZ3CmlGhang3bpfkRN|Ohl={q>N zfWlCB*KA#G#QQ#eagGCQP+uSeIIs$$v87M+pBhY`S3tQ=Hh5K}K?pe;Omg9*{6Sx) z?CRR&6vfn>=R?XAO-oP~9w#=E61IHmY9RHW1fBt-GoBck09!2AZ?-YI^JqZK(rivo z!H(uvBraE*D@TL?MI4@njs9Vf+6!r z2ae|&G{}vd<8h8w+zrXWZ}4==0^>+MT-{TCBxBtTN9~oTBYdISF_tY)Sh1zbm2vU0 zwlVJ+qh_9&a{J+IKF+>(b7WYXcX?;A?P_%B!HTt#`Y$*`s~!RzK4S!wD{h+KU3R~) zj^h{(&m$5RPsF0(*+a_Py%Mhd)C+BP5(t7_uqlG&SR9O!eTX2}wl4?qmBH#{%@(g? zzTuehmgl`IM2x0!BEaZG zH26LtT48Mc67~&|49R%uTvP638i-56y>b>1URC!pDEd3UP3K9Zn0q>R%JJI{U8R|v zFC~A5mB#uQm%gXX?(v?_QS9X6TSHJt0bZtSbk5*HG=so=z$9bX=Na&${E{W%vHA3Q z)24`xh`{CItNC5Lam0cUm$c6b3RJA$A|+T$v1=7{i4>EH!2w#_CBH$hLDUyKFCM~B zyOl+&&Jj2L0i9%gIxcGaw}WDM%0u=j($j0-JM8l)E_!C><+DSq?Y9%$O)3Su0Zm7| zX2Yi%!ClP+VM9^c==37KuMxWHLPQQX9AL~i66?Zx5t+z@XF zi$#=#roJGIadlb^r2A+JNA!cMEa4-uX!h`BX6)OQ|B<95Y9$+e$*ZE>K@S)Va05ic z$U`5rj_;6lveOGz!G0Chflj0Ly~bre`;Ncm<}dvXo32h3V97+PE+tKaQ3&;tvzHNx z5%muJsJ_u;Dj1ha1oe!8cCCk!BfRPu(fyU9+*d;v5>7v?-_IMCt>Rp-o(pj?h>G}X z6?g|ST^4O3gUx=?3*raD7AnGXGmivTU^Fp=Ap%wzZQ{JMmz+58m*)uHgHiPcHLpXah? z1JbrHo?0Xe3paKrU4LL>eJ{nDPSp1nocz54g*357h`r}@V=+^jJc_(O9)A(5NYY5B2bY3yFkx-vA^*TvuO6Rg z)F2&dc_64)#`1=IswY*b*PWTfU0MXZ1|U(H&AcrzLeG7NU32FCceSzkOOXD29s&&# zD>y^lz#m72J$(;m-lC!o@mI}$Va{MQP&sMzLU!5%BghfNBt-fajeo%7_VbfuIeQ2x zHPfz42yzD^5%v`{y;wVqANYEahMfC?Z=W5l1TfH9P2apAjsC@+_}lfz*VnBZJs+>om>v60*r>8e3;?>dr%|N73Y;nHZtt7qG zK;|3;EU6}w)oDcKd%~p6u?=E#Py{!LaoV<46FQr0P}j3odwJs2lm`C4$EIMG*`Sw zJl4kqeuyFZ%0i9paAuAy#`Vm+l>rNs`PQR4h2d^dW#v6#jBF-5Z&APffZ(Y$_BGTq zHNc)uQNt9-Q@zozQl#Urvix!t!yeqENai)Ql`8dA2$!x}>WAMy=PY;T_{r3m7_DU5%nV!z6SF>gUwm5S}vTZqG62|8K3l`ARUl z-88^Q6X6C>C}T%!06t+1DaLVxfF3QN#txk1-TWfv$pGU`!cFnE?gSDv{e^QW!~1;P zRhx~Uy2ZaAcbl1hC&W5wVO)BR{73}bGV z5QtJPXcw7mrDkby%G`R@JdG3oh49M_vpB5|y=~oiT9X?0wbWcz*y|U%!gr$b(W4j_ zDDS67c$$lT~86` z6K}r(udI_5vri^Pxp+q3S@FunW{%eGQ_Y)hxK<(}Z^oXCWz9#5O@Pk15DE_=>9-nC zUUDPDPId$~RX_CeMEsw4ihn_}lz}$k%=!JzX}e50z=Y>TgyuPmWifSE5);D0`JcYU z$s#P6IJ2B9c+47VAKiS=BJ<>|egN;!tLy3-NE*FuatOmZJ>M7q3F?2g|7p07KG8}i z>u|0$IKLNX@8-4b=lOzc%m&2eZ|^*c;Q(hwRZ>g<_pJKrr^);IfS54Eu7b_D!?RjX zgw>hi(A&k}3&a`Rg3Hpl&ON2R)MD528|(^hq@Lx}NU>lU@!Vdh*V5p{<@e7%V>RR? z>2t&DKT~M1D1Sr-nE8o%(%JVI=xhFGz0U*~ZU!HjF$8{ltvh>bZ%ut9=&yILb8ef09J968qz$QT>A+<;2yHD1#5B7<{ zzD7i6&*ZSVuXSu(njHDKtmBl}u_tgvJ|OY740a`Ug2)<1Ye9$h%m?^?=uz7^WxE)%te(F3Fvj{7J!dH*os_f2=FzA3c&~1; z`s!|3DUx}z4Zpu+|lJ2P7UTlx9Vhh{Cf$@n+bcW-E*5UyUn= z5)3pqEDLnZvD+|h%7-g{i5~N&e;fYf>*!8hq8|G1Oyto6dqt&@?{l#wK2lON}VvM@Jp8h*LBErT-PnhGZJ;zqh-8`GRJa%>DM}tf#Bf ze5{#G>xa*6N;F>GkQBDERQSBQ<052WW0JDF!N?khJrfJO=QUzwYF$fwqj@1ZucDls z@`R$sT>J@N4yx4bQt-#Fy0v>uTyS!sEB!#0+Y(vt7_sIjJvx)d2h3?69)EG-nrr8x z+7o`K(Ok4&7EAP|JS$||{eA>|$BE9BsdFYme_A!piKT4!m@G?;#6 zq_l9hosS8#Hz7evx_oa2{#nW6g5w9TBp2SWP8+=&m>Pe(63%dILB~c3mKV1xm`tK? zpr|}2(Q{ZHPW1|zRwM9dpgwkm@m zx71orz7w3F*Vxcn$n_>0Y@T*&9?X-!vmA@N({h#fP1(gK2BtaB*BuN)gBxTbDhAsn zI1(|;xKPog6nZ4+<8}}wI^+D8i9V-;RriIij*ika;2t$=KwdlOO1gew zGK-k{TQnfT=o!~;o<~J}e0sj-x0FKfp3)y>DP|Ui7x%u-D5>9Ton_rJTlnBq^XIsn zB+)0r(}tvG|B+Rf&6Sr}zNPn+_vKvcGPK?BuTk*hM|K+73lV7CyGtFJYbz%sE=o&! z^)GR*1pnX%fN~}L>En!TeElJQJP>&EPC1=RE4{EL{zb1<7kz4jp>isB9+f?jQ5Xwu z;oQnu#(q)LH0MMz`I(uO*H5Gm?O0XFe5vi4;ktM&>L|(iDUEoa&g-V2SJ8C`pzpOto1IQ++I15#lJ+gxX-K;FP)zfTeH7EIoa8!_53HO`i zI{9((iA(XsYKn+Fu&eL4u3p!x4sdw!Dd(I6_e-j?iivt{4+~CIg1%P>N_2;z97rQr zNrFe!RL@V`rull$M?dUbx){CD%wdE1TT_(@idH4s$V+1mpQw(`l^efo9CD~sP}Elx znJSD8WgmWdPkVQTSCubJg0nHZVS$O!J}2iU0Q@Ysv)t;Txlif|R5v!r^gE1^mDyV_ z=#Ql=+rpk4Kmj;^U$W`QzRR(HdB^u#9<5wMcrikef-6QT*|_~h0NZFi5Usq4d4fzF zc8#BCRr_klTLH`ZU}`aM@-T-Ai9uq%*^I1K?#;*~?F1ECDO>+7exI9Dy-+_r-30oF zX((wNKZRVcS(l*td7o5x1Bve~)`6Er+VyXn8cme$(k@Fh9ib1Jww0~q74<0E|JCS?}#EloioVfOY{U`^Q+)1mTZ!#@BF!Yh2CL@+c&b!^_yJQ;C`s+B?=@a zi1LzFdIXANnjze}|GZBY*{@0?s`mP5jz@2uG`w2~FG$Tn+EHV)mnhiMC5WMN0kv_i`RWnW> zk$9zlBRy;&>Qg0ED4uJ3i%q-63Z$mI$=Aj96YjH6LGNq|{sw&$4cLXZya@3DI1%Era zvWD~|)*mav)uV*|^m%HyK5ddvjF~Wud{QC~n?Ah-`XuVMU#- ztpAw#94AJFji8eN|0#Z6ZtjoCNEEL{p9O_S*;os>eyqW5t^2Yl=SvZ`n36)woNA7p&FaLWzErup!?=Dt-_PlLH(EFpbu+j z|I}{+8HsXLXARHuyGA1e7H&&^z-o}-`*PwMrh9wx7wGEx-zY?pGNlUh+tveU%S^8{ zSG}AjY`5M^9OPXNZMHC?6lDKC@2~FFzdMW9e6qs9BK)rs-B0Vv5l11b_Ore$y!_F* zGhm2);PerDt;3oN!wJoxHgVh!M>11$iCGbbiM0*lK0`Eu)WvSMR@5 zV2yz+5o_K?*Q%JztapdZFf%Ef5wMpFf9`}m*|y#X$T!9(6nzQvSM6V$QkByxLcNWN>Gtw_ynD3kEm=!;a#$u*0-o6J~Q8lIz)l7k* z@{cTtz4Evmz4nDVBNu9YK3SFG#1J1Hz)&1~1dRQCWULIOW0%r4MlXg_#?!{1BdNF} zLXS_{ILix(diZ_#ZJ!fM}7^+6& zC9i4Pk_Uenmi${A?o4E~NxrSj>{R>h%s!Z!jnwRNhq^(Xb9KKeHTUzZ8GPs|sHW8e zq%(5;iHpu#vx?-q6Sun}JIxk*T|E}Tn8CeIa!V?MP2HBjp#iDBDY-&^B#rDUcJ~06 zz8|9%zy}N%W%{2%8x-(eK$hTNSs@O(t>URPl1uAc4>S>qBK~Ikjk&tc4l7-{RGZwf zTzZE1rN{~(GjBqdoulUGaEg<1X~A5iBNG-=f2#gX=&rrJ;A_{s#YStAekbA`B%2bY zNq3B}xSnTk2dx_%1_uUqrelCnuo6M?Vgg6|JUUEGQ57cQj4wY0-%mGs9^=Ish}SkD z0C0N+b~xIxJIHdW?@p=ICQ)ah{J-*nfS_ZnRESz$_FW$h?l2}0u-Yy0F51$X7`TLD zZ+tz29mn zho`p(#uHjZ2d+Fa%zIt{d!DOi*bP68k=acmv)ltPJu>nZY{wvyy7iNY2pt%9P~q8-nj)8`D&mQh-c7Wy?8l2DAHcFqlTc%>)J#Nlr9RA zt{a?b*y8xey6W^Z_h521`=GHdVl@VL&a$LdPVwX)Y!o0qraAl@Bf)t1ICYt)vaW6aslz)+|3qElc|m_mt=OA4ueWo6=;G0w0~2;8n+r~GEsLuA{d z7%Og>Zp-8yG=@hM#W;y8Q5ju9+mvc-*+$wr{#%ZuV@SJebO=n3LJWMxqDP9!st@yB z0}arD0}4`{PJI@U_HZ6nns~os#jCPqly{hIYV?kAu&8q6s(h3oDv23bq(eCZGgO%CXzhsXZsz>l zve@9Qlsp?<8Gy4u+wV5!=gtEr^1*{UWMZOy5AFgNu^B5!t}Yqz@o|)B3gZ_U8xQzO z1#`%5QUqII6lrGZ{4dZmM{PnO&1u!wZ@}+V{i0MtVxs@b@Vn8{b4(&f6{}mxF-{q7 z1Ck7vV`mZ~bmSC8P8%95J*vdtu5<*2*_PlwALads2rR+UM->5!eBtI`1GFktw)FB@ zWdPN7H5})rcGSy~+OThhk=;>tU&g`Ktp+qL^1-SW3jHnIwOB#HPa&n`F?@{y;kPp2 zz!BAN>&|Hx3eLkS%k zm(nQVo6b}C`dKbLsX_?18j^zZa{!0q#t?!2Wd+{g{#;cWo)!yRn>#^RT*TrRZ@t7n zp_wZ9*_Pv?QhHE03ZX?hv~sOTtjQbmUf1Mqj$-%>TyUAgP)Xuh^*w#p_@qMd$LoWw zmT1wL+P9Ec3h6e_6d&x9)As77ul-TBs!LHRtR$d}?`2)pmQ~#y)xUT9H)Vnuf;2w2 zFdWq!tSVqZoos+M($1VneL?pddjP-;~)YTi3leHB%Dq;Hr38_@glA9eLZk*oaBp9ZA|_t1AHE=GPdm^by5w zi0GUhG}yVvM=P!SM8~CWA<^&-xnWe$P)rC@G%?lqk$|0>@gc%BtsriPKt2qiq=|0L zWhk4yjtRT!g~9bhsK5W|Ok=b}6|O0e*7fYGQrpbT&vWlQPWHS1s2A4D!*9F#Jbxx< zPx7;#k47K{{loY>(m13-a{})=#}g-B?=D0LsyCsQYSSc|`iGO4!8bE z6Ec9-Jsi{!fs#7j8N^3YgmJr>jX%f%A{xH1IW)g`YryiWn$7ezXjF|9la~w9>EATZ zRAYbopB|d`F@}0}ki}vNkk;trr<&}M$YVFX8&96rrN0PQaO8XPlr2Ih7TjWGJ50%G zq^c(s1%7ZHMEcz{V_Z?TVBCfFF7bx!)hY!S8+KHclORr@3I1F>WZI4CqKze-{A;!Q zMS1TpP4sy8e#YB_YlC!yPeX94Fqf1QGb4e4lY6-P(?kN}%AB~Dqtjm=r^`lk$m|(A z_wD*J)+<%tq>3kSZVW%D#w`**oJEn#bMpupcazIY)ttK?3o%?Ru)GG3lLy5^|Fn^1 zVS`kKkyi>`|Sn0#tB`_`ERg=Jd3$33vT!zQeRsRVxM|t?5kVrO*p2P$_woFfSeO`cMtPoQLyNrp_F}m;QT&{{r$*bm(xwAZh{)&4 zff9TFAnN3%*@`w%GQ~3_U-=nFD-xjY8q2Cy zmW;IA4YtdCjXMcu;gJm^KuTGo(pGyIjwSE^NY;$K6!n!_-I^u{&GeKlpdtRY(ifH01XW%BuGrYheRj95VztCBH2*PNggPdDR z4&TmtY%@DG{mqvIeQ8EtS0VqS^SPJe_7KSHkfypK*N9glI#sl^GP8q}&S+?qO|}`b zv)@^DCxXg1g%;I;nn=p1F&m=u#pg>uR zOVVj6aAvT-O;kNBDh*w=Lmz&-7=vv`adUGo;J9R?xGk$-e>;08Xn18|{Wn=FRXlA7 zL(6qcOBh$pHX}YqBVN2om2J|=Jd$q{_=2NvDu@#EKGLRdRgIbrzA2xo2JYqsH(NrQ z>IPa0MKnAh3>$%MC;O|(XThkSY*p3AMRe=GL)P@hpT|1*ar%~9;MM#|UFo~Jg6n(( z{GL!@F|J=-i@aTa@gv)?QCG?FbD8-sU4KNZa04(fCG2Fep@;qtpxI!r1M0gkP;Q@%1IEuDMRtLsGz93Nz0?!$@|;k z_2Q%1ekGZe31$p0g;4(Ib?J<@yHFgZah(vci>kMt!ouq)9DL6fk`u#*i{@`FvNg^XsCJtc$&y|{BCnGQ z$nnP$vsI|DE2vA>f0SbnUS6p4I#=EHQP04X7SYUUcxewZqlyb;jMs#5(&&@lE+vr1 zNp(MlHNj5zFO*@9AKeKOe>ccl-FIa%Dy$gR@HpHVahy3s?inW{|QsE z#_eMoHz;r>B>D8%Q5| zUU~3u-C|YIjfywXk3WW?yc$GMwB1eM_}MW-OAS4p^H_#=;r61f0hXgtHCcG*zc+pm zl5SQe;alfh94Gm2Viq~0o_SImt$xA8hBBXhah{3aB7jA6S0R+B`tE9EDE*&0h>SPE z7Nx{rLoUH>hyfT@svN^RsJE;8~hK5N4OA?}RwE-{}|p|*E5pK+y% zfpvd<(k(nZHbzxNd0jabT)W55Nm-gNuIhYzulqLPB$dpZ-~Z%kM$qkd`aC%62?>rs zoO|`4o98)b+2aD}&-*?jXq+v|&8_Nczd#8ORunnkDcy*$+G2X=k8)t;T7)@+8LA_D zb46b%xnEPrwyO_pkVjp`UFO?R8#k$pZbFOJX)rJLF|L!?!U?(dW%H#B!Rd9no3|bn zsZl|FNf4Y%oKHpIGQmmv{4^X)uADgk+X-n@_pD?4!8UIIeMn|+~F3Ji@=X4Zxm?Km{wGGcxHbpmM@wB(B) z?*KhPPYtigxJ1-qPY!2K9dn7?EYFwsT*nl^{r&`H`k^wy*YAoqI?F6hS(WC z<_D23{EFzvGg?&i}%e9L}gFk$$ptpp5P7H%9KDePc58xfE9e)&F_a0vbS?@&P) zBM)JXul5@x`*Qq3md7Pxas8V&p+;UXNYQf#gL9sD#4%}64&d36!58oQyH|AA<%0B1 zTtSi(RXCJ%4P|A!4}-$&AyA!1Qm82`6H^T~v_Cm)P}m{U;8S_^poZ$#f7SrJ7-%p) zfE1|fWm^!{IOGJg88;p!$Zj?rI+|`J`GO2`ujW?zxbh>^H46KghH*G_e2!__eqF=B zVtmZ^;Rmt?y4HHn8yFj>neBEjeu-fc{W7bsSp9I0Jpjwe#Z_|wneP<=DZ{(<-{k!r zT6`&067L(Qm9b3!nOJo+l{6g+8;g6qML(E?c|gT_6FjRh%r{kel^88P*kUMe-jLt-F(!dKKkPE%F0shMz1dmdLA#PC^-Z>;OI>VH1~2Nsy- zUz4S#$UR#oku18dS07Xk#3&D7fO>}{-w1%WT(uGs5;}GetEqWH&+kIvat>6lk~`vm zrS~=_A8d^XKQMC82y;p&qBOcKD8U<+{p?bL{+t-8rAB*Cl4L=jankoM##O&d_nH`@ zQMFPI zXz~yxl4_7Vss(Azq5I;Fj`HV~Yh4);LY5r1!?t(6t@t~n+d0L?^B*hC_CMd@@Ku{_ z&;1Iin!;JiBKSLJfjtg4O&;fvMRiI!d9(;UWs7cI;OD!-pG{~oHAWwN=G;MO#8qmq zSWx~ROE}N9obLVTUuXih$L-kK;)sNTg9%ax4G2X@1p;8WALo2E%jz~b`}oF zQKMZq;*OWDl>hG!Sp1s@ZL-x)1OOt`9PjbG6vpa?O`8Bjl!i9au1|oTjZe)@?yMF;6g*xG=(Q#qL1knKp6^}Cb3n&vuyaozer>?&OzIq|-D-VHFD4-|AL z=U8TOOIA)&f!IU~*nziSlEjY$sAN|XC=;aKH!s1-mCjsXX)sW>WMhS6P^Q1syg9FE z_TAuq3?HBP>KnMHAXEuaM_*u-S&v~9YRBC&lJ;Z#9-!0n&buxXa-LaiuH;^gR_S-Q z-C=`zaHw<^b)0&bh13RizUHW7FL&YWCEmia7F!GAP~hhqlnlKKET!`@?!*3+?qUa)I_iYxNek%9t{PZ2_e+-Le{ zbl07n$Wsa!pvn{SYnZ4uWI65}^PelTq<>Q;5_TylvZo0I6u{DVn}&M9WUs=f=@IbVjt3(C2nF?S4SaC3+XoiAcYT=s`ZxA$Y!LPEgJA4C zS!&e#fGI=H%fpZWZ1ENUc|h?}5p4;DF)pXNrR0sGtvdS`Po&Hil=Ie8_zKx_8o z3zr-das3YqE}%&WM#1WO+7I4l)BNGmZyr_tVhztN{Zz|F|$RK(1 z?ZcilVRc!$_-N^LBHHoA#l`Q{4c^H30rEf6b$PzY5zkhC&$aP2A5kMr;v;avltz%# z2DLACCK668Uqt2gX58@cDVq~|wfqNYvV?oIHvB*OffoM;26|Vg|EH-gV66%{cPZoZ z^pWD_HtoELb$I2yWE1@?Z{I;1-FmxG-g?!NMLl$UC(sy%8bO}x7QvjSVC*MNvOpd}KvxeEn$b7)Q6aN%-ybOC znAEv?6QttTOd^phpwXoVkleON@y zEaiFobd7dg_IO46!!)kF1?#dhVDL|T9G62Qcra5lY{G$^mNN~OT^ZoL+zZ`j9#7-0 zTZf|)=I)2@8C_&t=0hfdkcx|pV}}UL(UtWemN;G}JkcIM0b&VyJoASb845!|&ntB| z+%BI31G^v3EZ!QUQ(;JF^qtiCepf~+L?wOA8IrQ#+tGY-$Rg^PUjJm}&Z$fhhF`2z z02h6hTx@YK#THS}H)hrAXpB^4i4M4^q5BM6sv#XAC4hZ~^RO5s?7@8mcYr0l7x_yU z^{Xr(9671hD6>=?dA9suF)7`Y9|^|Ax8E&oA-jJggBRb0s=;30_4+ON@loVDRP1-G z2CmqjfJ$P`_bGQEm67Dq9IjF^sR@liTZ4DEs8Ll5&~s>L0Cg0T*aFvs$uh@7V|<4A zVOk2^8?k!vOF|KSZWFE~MWAwU#KGP~Qy@|Oq06>=u=^mV^ZnA}JfO54h!1V$@qMp* z^+~Ce%4mS9_My#oK)nKJMEa8q*Oz0_hRE(~=5Ue3{eYK)>~3XqyrSduN+N6gQc>20 zuMO0;w)kwRl}ykbrBOY&Oh+0&3Y(yA7mWQC+Tv#k%rT=qe`pPZ|K_8zduPW|N`tOW znbJs9&QrK>^wrIki1u)^c~DMebT2*Lry4Ya%LfA77mv)Mh9=}U1u2X?ABWLg=4w?E z5f`uX4a%pL(+EQaljL3-4|E=Q_S9o{VhU7Waq=u}G5V{<5rYH@C|R44(;U!)3n01G-tVO^yR_PscC<2BXQ2RCYa zS%9e*uT8Fu#(74(OVUP@Exwri0}F4M+7TS&M2`~eg8C`v^qFIU^kV9NXd$)TLUoBSOAuMC6@|-rZVY0^)r-7-)k-5z-CYXWea>1_r{dWuChM|ooq(6qNAvRh zGN3C^hTxGSF;4^NZrs{~1OFv1U7FN%h4)ZuV-RoJ{IIre>RtI0Omap9DeA)4dqro9 z{l7=1yF=eD%LMujM)A(`j(_{VPuP_X$2!F4RWinQ`c~Zkd}A+_dG5ASGM|X!g$cGA zO8a{d-qm7*ytiW2TPg{{$l`ndPjA=#PxT+RWfaNR$}HRQ$m4nEbUL>{@yq>s{xw zqD6S!M$QhG*=r{)>-;-wQ^D-bj47#++)x{a`+xYe@ZA)4ZELC8?gt~%O}TR8P~?|c zJ&5XTJuxCQx~zsy$3-N>kC1oxl1^y2F0~wox#?b}LG< zwavK(Yn(z;4tnu}Xl^Dh!F3H*waf`6LP#rP+c+#I3y+O9b#KFU}=20f3dtFiB&vf-)Dn)aq+nzBMlH`^{2-oL{| zDPL#My2fOHtsOm>RXvdJT(_j=eK)3yfeCy{K|Dy@{^|7*v8eUQB{Q6i6tOc09Rg2D z1BCed3+mz+D>-+xdbyF+7MIECS?izGx_W3G|W>6z2hi<_xLd&a?~!!$QD6Lpug zW@{yw`1a4VIkef;ooyIu@&EN7eQudOabZfXN!<2i3O&h2Apbb60J-^D4m{np2wvHj z?)rwJ)wJ*Wai$qIxesV~APX%Ip!HCX6d^Y^u{!2PMGi*g51~Z=eE^Y6agEa`Z7l3&c3C=@bEIPU&t2u z?3W0kc<;+?U=2d5cFdzsC;@ za|A~opNd(extR3Dg@?Qgt&@L?vs(-+dY+0am#xALqm0E1K$N%j8K&i$>1#_4jz`rr zHYkDwLs=64;uApIHSDPP^pFVMS#Dj7pbMyg@Ledj7Sn#r>Gy`U`x!Z&OSMU{J^ zi}m}C8vmVV*)TuEM4fyqutY^aC+SH<*0mE#k5pP*F3oHS z+8&(+Qp8Hk+-9f|w*3m!O_Rrp9she@BN;8H;k_8QPv=V-OlF{lq<*;C6Zeg^3mzHP z#{=#NX_WqH`M7E5Yc182LjVKg;GqX}r&jzYT}@>cQ2MIn3Mg9R6z8Fef*TMVI9y$M zn&%8wyUbqqjHw~nV*noW@LephF%T`gZdiCWRt~auj)WOQ#nbs-iX#%vSMro%+(3qB zNb#FTe*;JUPm@@IC4>g4$m5Y8EK%V$0P4Oje~&Y z=M4)HpX1X}eN8i+`kyE;liwtW;D|*q_uUjO2k<}<>8>DcR#IHEXJ?;~!h)GZvVolP z-O~nGNGp~L_mOVciy*T$7rQbw+QU>;H1`wg{pyf}2`Ncy{8C)q4X~4+=o(lx*3c_K zSO=>n-f1Hl-;(&A_S%164P*w5kA+(>ARQz0M z$hZ1!`asp?CHuy{!hU%S7QqjigCVN3|KfVSd$HWw>jcwh)G+8N8s|=^4x@IU!O+6i zeee)pG#&D#=4PaI@*{pIm zJ;AA84+8m)=Tc6FZ(O6Wuuj7m{z5{`%_s{*0C^RRq)R_WVq;jPN0|l5+x{(4ld?7<2cgxH=_+_oYJ(Yy_J&^w<>pRyQ z@|C0Ga5zIi&UE_P!5qCL4NcS%zmU+pqTv37e$zBa3FCLRS66$U2yoe~O+>Fiy2oe3 zWF|)us(eqbqj4%$%5R2(p8%POod%0Tw=KKjFb+N46c$IrTKvCEHA%#hI5D@oP zXog1KCy0U()OJP8%qS#Sdp_=BH}(E8MoSk2Kw!C6a+L{W3;9=1AYK{DLqm`SH;zXx zf!|^Lj1q({eJwrE49p9zp;y`gH)E6li|Jme^IIgp;dFS(QK~U8(TXA{uzra}^=n)< zn+XCJ z*8BxzcZNlQi9j_FdMitV<)b|+I|lkfH;+`cBV7(LAE#I_%#T)3y$0+#C)roIss>B= zOpr4LMkk8Odcz^HeZ?5%I}({|=7{ft$*iF}l|BRbwT)j`10`yA*i#o=o}8RJ)Djx` z%f`Mn<5X{6u6#y%X~~cb@fUe}p7ajnPseLgCT^WW>Bk~RI$HH6`o zQG=thtQU26Yp%}d`8n7dP`re57PB)v~2I|isXcXhOHTx z3qI{&jU)YSJ`YobcUMhAT$h)gE4g#5RxjJi!wcvQdn9Fcg@i2%?f*STX zQ7mv)@=}LAz3zHtpJkB~!rut&wc;KsC1#K4PI@iM= zz17BIRs#&UuFvFk?9SG_Pqw%~Y=fOk!_e?@ii~?2tHCA-LT(>`0*f>gaJsZ9vYzSt z2QU0Z_$zjC_`nHedgglS)jPLwUg^+*!?{DWtMB?B^Qfg;2up@c_tB>5&Rv+q18xQ1 zx$3GbL$+E@_`y7VeM)Lq|CUK=BPHW&PZk_yk1x`>Bmx!WUmoZ_E4QA=f444rK{yR@ z=^~SVS>>gxaW)u&k@$t6a*Llq{47rLO`NTN-}y>-Uwk8?CZ7i6t+^^f@;YxeZr5H~ zG{36!$4QH7)=m?<^Z6-2QPcwkf|FMfdL)Z4elhtLHmm2xk90i^8PEdJ`>u}d+4pbL zaUs_NrJ4>kDNYP&mJ`t3-rg=#`Q}vQ5@~&A^BKQBxD-`B)$oVzQ`!jlJdEt&t6YNw z;lh{BBUzUo5)ltb`@?4jnPmDXV0;BSs-YC z{wJC^CSE`_j>DOUZz{ zWccl2T4-AE3XtL5MerG5;PS;Nq1fHkymGAtgWz+Gm#>Q%zy2R}ffO{$V|zU||ID69!*?@a@ z`Yp*Mbg!H_To2K5_Xd*}#u|4bz!+@=2XSmh=}eq>PT9e(6UTNteq7+^obhGEUqxG6{~(L`ni-e&x#jn*3%Xt3g&ZRe@EahB@&*g4q zBichP`%{W4e2*Shkb|0BpfQsW9Vl#GP=l=HC-h)!f{Pvpm?n*froBimtZ4%NEeP<1ARV}ISx`tn8lAXEM_Okv5$>Xj@ z6O&FpC*nF?Zsc-$Ern9(E~FIAQvo01+YC(#>_PeR$(JaITbJQ<6^H)t5NbBQ4$Rh& zCJQkdh-gs-9~ZZQ4_pD=-vCZ2_C05V&`~W%Mp2I-DTPk=wF|;^g>x^m>os1hsgAy! z3}ktZw){@I@K2gtQ(3>lxZIQUoZ_^*uI!M+JOvftP5*j;!tluqXO ze^$4(o#bPEQl>bf&`fu|f!!ZZ5Jn%Dw|y^9&i*8)?8c)mZ`(H~0;iwtb{~xuJE*Rm zs^>ENM>I4+7t6E7$R;mp`tQ|sZI)U2rWi_>_XLIr9Z2Ee#m$d?cvUk2NHEtryb3po zsJj0htfb94^BKQgIWxd&?xWNP-k$-$RuDk}yj2$W?L3!tZLy@`u6|KVyGV82??(3L z4ouh4M8T!VOEzfv;zr+*MibNA(ncoM3saV*~%{SZx^3wuP zE3ddd42b?Xp=vTf&>&@E9|{$SNS^k4L4HV4CCb56l>6HH2iiy$yVzbyJ0L7MqKrMy zJfb~H-jUd@VxZdR)L>L2Zc}k8G|y8&@NmJ0i||snQ~Z9;^^l%tpM+@gJmKM2V114P zlR>59V%P`a24J?Ue$9aXZ`f8_!R=)*`8`P@$F1GUm?Mhr0i(Ib^WYiv7D~ypc%R!l zG5a|@G>q4g)0}}oWo$$F$m097pg&rDXA-y?efM9A?L~qPoYDbeVDThc zyxVDCl~G8if3tWB5{mr*fapKV5oN#6lM~G@MByv5MapC%lQmi{Azw_%XJ+7TYC@O7 z_wn4qPw+EbfB`Bs1Gl+tr1ES#2q4bpMEW|x2f%4O|g!?QsjfiHF zQBjtUe#B*8>0Y0aN4-at{_n@K!g?j+K7^mjO=2lZG5+W*`szGmf>z-aDLk3u$Mg`Y zg)kX+_yb`Kehem3{Nw30SfehyuKeH6|Ns1tXgN4`a+rNf#9_{c4E}UA4K-e?+l2iO D$>`yV literal 0 HcmV?d00001 diff --git a/examples/ros2/package.xml b/examples/ros2/package.xml new file mode 100644 index 00000000..51c7cd57 --- /dev/null +++ b/examples/ros2/package.xml @@ -0,0 +1,22 @@ + + + + ros2-impulse-examples + 0.0.1 + Examples of making a bevy_impulse workflow with ROS nodes. + Michael X. Grey + Apache License 2.0 + Michael X. Grey + + + rcl + rosidl_runtime_rs + builtin_interfaces + nav_msgs + + + ament_cargo + + diff --git a/examples/ros2/src/fake_plan_generator.rs b/examples/ros2/src/fake_plan_generator.rs new file mode 100644 index 00000000..c3dc3f50 --- /dev/null +++ b/examples/ros2/src/fake_plan_generator.rs @@ -0,0 +1,121 @@ +/* + * Copyright (C) 2025 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +use rclrs::*; +use nav_msgs::srv::{GetPlan, GetPlan_Request, GetPlan_Response}; +use geometry_msgs::msg::{Pose, PoseStamped, Point, Quaternion}; +use std_msgs::msg::Header; +use builtin_interfaces::msg::Time as TimeMsg; + +fn main() { + let context = Context::default_from_env().unwrap(); + let mut executor = context.create_basic_executor(); + + let node = executor.create_node("fake_plan_generator").unwrap(); + let logger = node.logger().clone(); + let _service = node.create_service::( + "get_plan", + move |request: GetPlan_Request| { + log!( + &logger, + "Serving a fake plan from:\n - {:?}\nto\n - {:?}", + request.start, + request.goal, + ); + // Just linearly interpolate 5 points between the start and the goal + let num_points = 5; + let mut response = GetPlan_Response::default(); + for i in 1..=num_points { + let s = i as f64 / num_points as f64; + response.plan.poses.push( + interpolate_pose(s, &request.start, &request.goal) + ); + } + + response + }); + + log!(node.logger(), "Ready to serve fake plans..."); + executor.spin(SpinOptions::default()); +} + +fn interpolate_pose( + s: f64, + start: &PoseStamped, + goal: &PoseStamped, +) -> PoseStamped { + PoseStamped { + header: interpolate_header(s, &start.header, &goal.header), + pose: Pose { + position: interpolate_point(s, &start.pose.position, &goal.pose.position), + orientation: interpolate_orientation(s, &start.pose.orientation, &goal.pose.orientation), + } + } +} + +fn interpolate_header( + s: f64, + start: &Header, + goal: &Header, +) -> Header { + let t_start = secs_from_msg(&start.stamp); + let t_goal = secs_from_msg(&goal.stamp); + let t = s * (t_goal as f64 - t_start as f64) + t_start as f64; + let t = t as i64; + + Header { + stamp: msg_from_secs(t), + frame_id: start.frame_id.clone(), + } +} + +fn secs_from_msg(msg: &TimeMsg) -> i64 { + (msg.sec as i64 * 1_000_000_000) + msg.nanosec as i64 +} + +fn msg_from_secs(t: i64) -> TimeMsg { + let nanosec = (t % 1_000_000_000) as u32; + let sec = (t / 1_000_000_000) as i32; + TimeMsg { sec, nanosec } +} + +fn interpolate_point( + s: f64, + start: &Point, + goal: &Point, +) -> Point { + Point { + x: s * (goal.x - start.x) + start.x, + y: s * (goal.y - start.y) + start.y, + z: s * (goal.z - start.z) + start.z, + } +} + +fn interpolate_orientation( + s: f64, + start: &Quaternion, + goal: &Quaternion, +) -> Quaternion { + // Just do a rough slerp approximation. This is a fake planner so + // we don't need to do anything serious here. + Quaternion { + x: (1.0-s)*start.x + s * goal.x, + y: (1.0-s)*start.y + s * goal.y, + z: (1.0-s)*start.z + s * goal.z, + w: (1.0-s)*start.w + s * goal.w, + } +} diff --git a/examples/ros2/src/goal_requester.rs b/examples/ros2/src/goal_requester.rs new file mode 100644 index 00000000..fc4092a0 --- /dev/null +++ b/examples/ros2/src/goal_requester.rs @@ -0,0 +1,124 @@ +/* + * Copyright (C) 2025 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +use rclrs::*; +use clap::Parser; + +use geometry_msgs::msg::{Pose, PoseStamped, Point, Quaternion}; +use nav_msgs::msg::Goals; +use std_msgs::msg::{Empty as EmptyMsg, Header}; +use builtin_interfaces::msg::Time as TimeMsg; + +use rand::prelude::*; + +fn main() { + let context = Context::default_from_env().unwrap(); + let args = Args::parse(); + let mut executor = context.create_basic_executor(); + let node = executor.create_node("goal_requester").unwrap(); + + let task = if args.cancel { + let topic = "cancel_goals"; + let publisher = node.create_publisher::(topic.transient_local()).unwrap(); + + executor.commands().run( + async move { + log!(node.logger(), "Waiting for a subscriber on topic {topic}..."); + let subscriber_ready = node.notify_on_graph_change({ + let publisher = publisher.clone(); + move || { + publisher.get_subscription_count().unwrap() > 0 + } + }); + + subscriber_ready.await.unwrap(); + + log!(node.logger(), "Requesting cancel"); + publisher.publish(EmptyMsg::default()).unwrap(); + } + ) + } else { + let topic = "request_goal"; + let publisher = node.create_publisher::(topic.transient_local()).unwrap(); + + let mut goals = Vec::new(); + for i in 0..args.count { + let time = i as i32; + let mut rng = rand::rng(); + let x = rng.random(); + let y = rng.random(); + let z = 0.0; + + let orientation = Quaternion { x: 0.0, y: 0.0, z: 0.0, w: 1.0 }; + + goals.push(PoseStamped { + header: Header { + stamp: TimeMsg { + sec: time, + nanosec: 0, + }, + frame_id: "map".to_string(), + }, + pose: Pose { + position: Point { x, y, z }, + orientation, + }, + }); + } + + let request = Goals { + header: Header { + stamp: TimeMsg::default(), + frame_id: "map".to_string(), + }, + goals, + }; + + executor.commands().run( + async move { + log!(node.logger(), "Waiting for subscriber on topic {topic}..."); + let subscriber_ready = node.notify_on_graph_change({ + let publisher = publisher.clone(); + move || { + publisher.get_subscription_count().unwrap() > 0 + } + }); + + subscriber_ready.await.unwrap(); + + log!(node.logger(), "Publishing goals: {:#?}", request); + publisher.publish(request).unwrap(); + } + ) + }; + + + executor.spin( + SpinOptions::default() + .until_promise_resolved(task) + ); +} + +#[derive(Parser, Debug)] +#[command(version, about, long_about = None)] +struct Args { + /// How many random goals to generate + #[arg(short, long, default_value_t = 3)] + count: u8, + #[arg(long)] + cancel: bool, +} diff --git a/examples/ros2/src/nav_example.rs b/examples/ros2/src/nav_example.rs new file mode 100644 index 00000000..248aa4b8 --- /dev/null +++ b/examples/ros2/src/nav_example.rs @@ -0,0 +1,332 @@ +/* + * Copyright (C) 2025 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +use rclrs::{*, Promise}; +use bevy_impulse::prelude::*; +use serde::{Serialize, Deserialize}; +use schemars::JsonSchema; +use tokio::sync::mpsc::unbounded_channel; +use serde_json::json; +use bevy_app::ScheduleRunnerPlugin; +use bevy_core::{FrameCountPlugin, TaskPoolPlugin, TypeRegistrationPlugin}; + +use std::collections::VecDeque; + +use nav_msgs::{ + msg::{Goals, Path}, + srv::{GetPlan, GetPlan_Request, GetPlan_Response}, +}; + +use std_msgs::msg::Empty as EmptyMsg; + +fn main() { + let context = Context::default_from_env().unwrap(); + let mut executor = context.create_basic_executor(); + + let mut app = bevy_app::App::new(); + + let mut registry = DiagramElementRegistry::new(); + let node = executor.create_node("nav_manager").unwrap(); + + // Create a subscriber that listens for goal messages to arrive. + registry.register_node_builder( + NodeBuilderOptions::new("receive_goals"), + { + let node = node.clone(); + move |builder, config: SubscriptionConfig| { + let node = node.clone(); + builder.create_map(move |input: AsyncMap<(), GoalStream>| { + let (sender, mut receiver) = unbounded_channel(); + + let _subscription = node.create_subscription( + config.topic.transient_local(), + move |msg: Goals| { + let _ = sender.send(msg); + } + ).unwrap(); + + let logger = node.logger().clone(); + log!(&logger, "Waiting to receive goals from topic {}...", config.topic); + async move { + // Force the _subscription variable to be captured since + // it has side effects. + let _subscription = _subscription; + while let Some(msg) = receiver.recv().await { + log!(&logger, "Received a sequence of {} goals", msg.goals.len()); + input.streams.goals.send(msg); + } + } + }) + } + } + ); + + // Create a client that fetches plans from a server. Each pair of + // consecutive goals is planned for independently, in parallel. + // + // After issuing every plan request, we will await them in order of first to + // last and stream them out from the node in that order, regardless of the + // order in which the plans arrive from the service. + registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_node_builder( + NodeBuilderOptions::new("fetch_plans"), + { + let node = node.clone(); + move |builder, config: PlanningConfig| { + let tolerance = config.tolerance; + let client = node.create_client::(&config.planner_service).unwrap(); + + let logger = node.logger().clone(); + builder.create_map(move |input: AsyncMap| { + let client = client.clone(); + let logger = logger.clone(); + async move { + log!(&logger, "Waiting for planning service..."); + client.notify_on_service_ready().await.unwrap(); + + let mut from_iter = input.request.goals.iter(); + let mut to_iter = input.request.goals.iter().skip(1); + + let mut plan_promises = VecDeque::new(); + while let (Some(start), Some(goal)) = (from_iter.next().cloned(), to_iter.next().cloned()) { + log!(&logger, "Requesting a plan from {start:?} to {goal:?}"); + let request = GetPlan_Request { start, goal, tolerance }; + let promise: Promise = client.call(request).unwrap(); + plan_promises.push_back(promise); + } + + while let Some(promise) = plan_promises.pop_front() { + let response = promise.await.unwrap(); + log!( + &logger, + "Received a plan from {:?} to {:?}", + response.plan.poses.first().map(|x| x.pose.clone()), + response.plan.poses.last().map(|x| x.pose.clone()), + ); + input.streams.paths.send(response.plan); + } + } + }) + } + } + ); + + // We can't really execute the paths in this example program, so let's just + // print whatever accumulates in the buffer. + let print_paths = app.world.spawn_service(print_paths.into_blocking_service()); + registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_node_builder( + NodeBuilderOptions::new("print_paths"), + move |builder, _config: ()| { + builder.create_node(print_paths) + } + ) + .with_listen(); + + registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_message::(); + + // We'll provide a topic for clearing the goals from the buffer + registry.register_node_builder( + NodeBuilderOptions::new("receive_cancel"), + { + let node = node.clone(); + move |builder, config: SubscriptionConfig| { + let node = node.clone(); + builder.create_map(move |input: AsyncMap<(), ClearSignalString>| { + let (sender, mut receiver) = unbounded_channel(); + + let _subscription = node.create_subscription( + config.topic.transient_local(), + move |_msg: EmptyMsg| { + let _ = sender.send(()); + } + ).unwrap(); + + let logger = node.logger().clone(); + async move { + // Force the _subscription variable to be captured since + // it has side effects. + let _subscription = _subscription; + while let Some(_) = receiver.recv().await { + log!(&logger, "Received a request to clear the goals"); + input.streams.clear.send(()); + } + } + }) + } + } + ); + + let clear_paths = app.world.spawn_service(clear_paths.into_blocking_service()); + registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_node_builder( + NodeBuilderOptions::new("clear_paths"), + move |builder, _config: ()| { + builder.create_node(clear_paths) + } + ) + .with_buffer_access(); + + let diagram = Diagram::from_json(json!({ + "version": "0.1.0", + "start": "setup", + "ops": { + "setup": { + "type": "fork_clone", + "next": [ + "receive_goals", + "receive_cancel" + ] + }, + "receive_goals": { + "type": "node", + "builder": "receive_goals", + "config": { + "topic": "request_goal" + }, + "stream_out": { + "goals": "fetch_plans", + }, + "next": { "builtin": "terminate" } + }, + "fetch_plans": { + "type": "node", + "builder": "fetch_plans", + "config": { + "planner_service": "get_plan", + "tolerance": 0.1 + }, + "stream_out": { + "paths": "path_buffer" + }, + "next": { "builtin": "dispose" } + }, + "path_buffer": { + "type": "buffer", + "settings": { "retention": "keep_all" } + }, + "listen_to_path_buffer": { + "type": "listen", + "buffers": ["path_buffer"], + "next": "print_paths", + }, + "print_paths": { + "type": "node", + "builder": "print_paths", + "next": { "builtin": "dispose" } + }, + "receive_cancel": { + "type": "node", + "builder": "receive_cancel", + "config": { + "topic": "cancel_goals" + }, + "stream_out": { + "clear": "access_paths" + }, + "next": { "builtin": "dispose" } + }, + "access_paths": { + "type": "buffer_access", + "buffers": ["path_buffer"], + "next": "clear_paths" + }, + "clear_paths": { + "type": "node", + "builder": "clear_paths", + "next": { "builtin": "dispose" } + } + } + })) + .unwrap(); + + app.world.command(|commands| { + // Generate the workflow from the diagram. + let workflow = diagram.spawn_io_workflow::<_, ()>(commands, ®istry).unwrap(); + + // Get the workflow running. + let _ = commands.request((), workflow).detach(); + }); + + app.add_plugins(( + TaskPoolPlugin::default(), + TypeRegistrationPlugin, + FrameCountPlugin, + ScheduleRunnerPlugin::default(), + ImpulsePlugin::default(), + )); + + std::thread::spawn(move || executor.spin(SpinOptions::default())); + app.run() +} + +#[derive(Serialize, Deserialize, JsonSchema)] +struct SubscriptionConfig { + topic: String, +} + +#[derive(StreamPack)] +struct GoalStream { + goals: Goals, +} + +#[derive(Serialize, Deserialize, JsonSchema)] +struct PlanningConfig { + planner_service: String, + tolerance: f32, +} + +#[derive(StreamPack)] +struct PathStream { + paths: Path, +} + +#[derive(StreamPack)] +struct ClearSignalString { + clear: (), +} + +fn print_paths( + In(key): In>, + access: BufferAccess, +) { + let buffer = access.get(&key).unwrap(); + let paths: Vec<&Path> = buffer.iter().collect(); + println!("Paths currently waiting to run:\n{paths:#?}"); +} + +fn clear_paths( + In((_, key)): In<((), BufferKey)>, + mut access: BufferAccessMut, +) { + let mut buffer = access.get_mut(&key).unwrap(); + // Remove all goals from the buffer by draining its full range. + buffer.drain(..); +} diff --git a/package.xml b/package.xml new file mode 100644 index 00000000..d25dcd48 --- /dev/null +++ b/package.xml @@ -0,0 +1,22 @@ + + + + bevy_impulse + 0.0.1 + Examples of making a bevy_impulse workflow with ROS nodes. + Michael X. Grey + Apache License 2.0 + Michael X. Grey + + + rcl + rosidl_runtime_rs + builtin_interfaces + nav_msgs + + + ament_cargo + + diff --git a/ros2-feature.repos b/ros2-feature.repos new file mode 100644 index 00000000..55a336a1 --- /dev/null +++ b/ros2-feature.repos @@ -0,0 +1,37 @@ +repositories: + ros2/common_interfaces: + type: git + url: https://github.com/ros2/common_interfaces.git + version: jazzy + ros2/example_interfaces: + type: git + url: https://github.com/ros2/example_interfaces.git + version: jazzy + ros2/rcl_interfaces: + type: git + url: https://github.com/ros2/rcl_interfaces.git + version: jazzy + ros2/test_interface_files: + type: git + url: https://github.com/ros2/test_interface_files.git + version: jazzy + ros2/rosidl_core: + type: git + url: https://github.com/ros2/rosidl_core.git + version: jazzy + ros2/rosidl_defaults: + type: git + url: https://github.com/ros2/rosidl_defaults.git + version: jazzy + ros2/unique_identifier_msgs: + type: git + url: https://github.com/ros2/unique_identifier_msgs.git + version: jazzy + ros2-rust/rosidl_rust: + type: git + url: https://github.com/ros2-rust/rosidl_rust.git + version: main + ros2-rust/rosidl_runtime_rs: + type: git + url: https://github.com/ros2-rust/rosidl_runtime_rs.git + version: main diff --git a/src/lib.rs b/src/lib.rs index a36ccbf2..e1941166 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -133,6 +133,11 @@ pub use provider::*; pub mod request; pub use request::*; +#[cfg(feature = "ros2")] +pub mod ros2; +#[cfg(feature = "ros2")] +pub use ros2::*; + pub mod service; pub use service::*; diff --git a/src/ros2.rs b/src/ros2.rs new file mode 100644 index 00000000..e164a16e --- /dev/null +++ b/src/ros2.rs @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2024 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +use crate::Builder; + From cae0c3464c5eea447c2086e6c8bb0fafb7b71db9 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 10 Oct 2025 17:11:24 +0800 Subject: [PATCH 02/11] Introducing general-purpose ROS 2 subscription operation Signed-off-by: Michael X. Grey --- Cargo.toml | 3 +- README.md | 8 ++++- examples/ros2/Cargo.toml | 2 +- examples/ros2/package.xml | 22 ------------ package.xml | 15 ++++---- ros2-feature.repos | 8 ++--- src/diagram.rs | 48 +------------------------- src/diagram/grpc.rs | 4 +-- src/diagram/zenoh.rs | 2 +- src/lib.rs | 3 ++ src/ros2.rs | 70 ++++++++++++++++++++++++++++++++++++- src/service.rs | 2 +- src/utils.rs | 72 +++++++++++++++++++++++++++++++++++++++ 13 files changed, 172 insertions(+), 87 deletions(-) delete mode 100644 examples/ros2/package.xml create mode 100644 src/utils.rs diff --git a/Cargo.toml b/Cargo.toml index 38ccf547..50acacdc 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -72,7 +72,7 @@ zenoh-ext = { version = "*", features = ["unstable"], optional = true } # --- end zenoh # --- Dependencies for ros2 feature -rclrs = { git = "https://github.com/ros2-rust/ros2_rust", branch = "main", optional = true } +rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "crossflow", features = ["serde"], optional = true } # --- end ros2 tracing = "0.1.41" @@ -116,6 +116,7 @@ zenoh = [ ros2 = [ "dep:rclrs", + "dep:futures-lite", ] # Turn on all capability related features. This differs from --all-features diff --git a/README.md b/README.md index 0be364de..6838ace0 100644 --- a/README.md +++ b/README.md @@ -27,6 +27,12 @@ pip install git+https://github.com/colcon/colcon-cargo.git --break-system-packag pip install git+https://github.com/colcon/colcon-ros-cargo.git --break-system-packages ``` +For now we need a fork of `cargo-ament-build` until [this PR](https://github.com/ros2-rust/cargo-ament-build/pull/26) is merged and released: + +```bash +cargo install --git https://github.com/mxgrey/cargo-ament-build +``` + Create a workspace with the necessary repos: ```bash @@ -48,7 +54,7 @@ source /opt/ros/jazzy/setup.bash ``` ```bash -colcon build +colcon build --allow-overriding action_msgs builtin_interfaces common_interfaces composition_interfaces example_interfaces geometry_msgs lifecycle_msgs nav_msgs rcl_interfaces rosgraph_msgs rosidl_default_generators rosidl_default_runtime sensor_msgs sensor_msgs_py service_msgs statistics_msgs std_msgs std_srvs trajectory_msgs type_description_interfaces unique_identifier_msgs visualization_msgs ``` 4. After `colcon build` has finished, you should see a `.cargo/config.toml` file inside your workspace, with `[patch.crates-io.___]` sections pointing to the generated message bindings. Now you should source the workspace using diff --git a/examples/ros2/Cargo.toml b/examples/ros2/Cargo.toml index 555bf4ef..b19331a8 100644 --- a/examples/ros2/Cargo.toml +++ b/examples/ros2/Cargo.toml @@ -26,7 +26,7 @@ tokio = { version = "1.39", features = ["sync"] } clap = { version = "*", features = ["derive"] } rand = "*" -rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "worker", features = ["serde"] } +rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "crossflow", features = ["serde"] } nav_msgs = { version = "*", features = ["serde"] } geometry_msgs = { version = "*", features = ["serde"] } std_msgs = { version = "*", features = ["serde"] } diff --git a/examples/ros2/package.xml b/examples/ros2/package.xml deleted file mode 100644 index 51c7cd57..00000000 --- a/examples/ros2/package.xml +++ /dev/null @@ -1,22 +0,0 @@ - - - - ros2-impulse-examples - 0.0.1 - Examples of making a bevy_impulse workflow with ROS nodes. - Michael X. Grey - Apache License 2.0 - Michael X. Grey - - - rcl - rosidl_runtime_rs - builtin_interfaces - nav_msgs - - - ament_cargo - - diff --git a/package.xml b/package.xml index d25dcd48..82faed47 100644 --- a/package.xml +++ b/package.xml @@ -4,17 +4,20 @@ schematypens="http://www.w3.org/2001/XMLSchema"?> bevy_impulse - 0.0.1 - Examples of making a bevy_impulse workflow with ROS nodes. + 0.0.2 + General-purpose workflow execution Michael X. Grey Apache License 2.0 Michael X. Grey - - rcl - rosidl_runtime_rs - builtin_interfaces + rclrs + rosidl_runtime_rs + builtin_interfaces + + + geometry_msgs nav_msgs + std_msgs ament_cargo diff --git a/ros2-feature.repos b/ros2-feature.repos index 55a336a1..22fc8940 100644 --- a/ros2-feature.repos +++ b/ros2-feature.repos @@ -29,9 +29,9 @@ repositories: version: jazzy ros2-rust/rosidl_rust: type: git - url: https://github.com/ros2-rust/rosidl_rust.git - version: main + url: https://github.com/mxgrey/rosidl_rust.git + version: fix_actions ros2-rust/rosidl_runtime_rs: type: git - url: https://github.com/ros2-rust/rosidl_runtime_rs.git - version: main + url: https://github.com/mxgrey/rosidl_runtime_rs.git + version: fix_actions diff --git a/src/diagram.rs b/src/diagram.rs index 88cfae57..5d03efc4 100644 --- a/src/diagram.rs +++ b/src/diagram.rs @@ -64,15 +64,13 @@ use std::{ borrow::Cow, collections::{HashMap, HashSet}, fmt::Display, - future::Future, io::Read, - pin::Pin, sync::Arc, - task::{Context, Poll}, }; pub use crate::type_info::TypeInfo; use crate::{ + is_default, Builder, IncompatibleLayout, IncrementalScopeError, JsonMessage, Scope, Service, SpawnWorkflowExt, SplitConnectionError, StreamPack, }; @@ -85,8 +83,6 @@ use serde::{ Deserialize, Deserializer, Serialize, Serializer, }; -use futures::never::Never; - use thiserror::Error as ThisError; const CURRENT_DIAGRAM_VERSION: &str = "0.1.0"; @@ -1321,45 +1317,3 @@ mod tests { assert_eq!(result, 5.0); } } - -/// Used with `#[serde(default, skip_serializing_if = "is_default")]` for fields -/// that don't need to be serialized if they are a default value. -pub(crate) fn is_default(value: &T) -> bool { - let default = T::default(); - *value == default -} - -/// Used with `#[serde(default = "default_as_true", skip_serializing_if = "is_true")]` -/// for bools that should be true by default. -pub(crate) fn default_as_true() -> bool { - true -} - -/// Used with `#[serde(default = "default_as_true", skip_serializing_if = "is_true")]` -/// for bools that should be true by default. -pub(crate) fn is_true(value: &bool) -> bool { - *value -} - -/// This is used to block a future from ever returning. This should only be used -/// in a race to force one of the contesting futures to lose. Make sure that at -/// least one contesting future will finish or else this will lead to a deadlock. -#[allow(unused)] -struct NeverFinish; - -impl Future for NeverFinish { - type Output = Never; - fn poll(self: Pin<&mut Self>, _: &mut Context<'_>) -> Poll { - Poll::Pending - } -} - -/// Used by some tests in the grpc and zenoh modules -#[allow(unused)] -pub(crate) fn clamp(val: f32, limit: f32) -> f32 { - if f32::abs(val) > limit { - return f32::signum(val) * limit; - } - - val -} diff --git a/src/diagram/grpc.rs b/src/diagram/grpc.rs index 4a5be063..422047d2 100644 --- a/src/diagram/grpc.rs +++ b/src/diagram/grpc.rs @@ -16,7 +16,7 @@ */ use super::*; -use crate::AsyncMap; +use crate::{AsyncMap, NeverFinish}; use std::{future::Future, sync::Arc, time::Duration}; @@ -401,7 +401,7 @@ impl Decoder for DynamicMessageCodec { #[cfg(test)] mod tests { use super::*; - use crate::{diagram::testing::*, prelude::*, testing::*}; + use crate::{diagram::testing::*, prelude::*, testing::*, utils::*}; use futures::channel::oneshot::{self, Sender as OneShotSender}; use prost_reflect::Kind; use protos::{ diff --git a/src/diagram/zenoh.rs b/src/diagram/zenoh.rs index 818960df..7d48a9da 100644 --- a/src/diagram/zenoh.rs +++ b/src/diagram/zenoh.rs @@ -16,7 +16,7 @@ */ use super::*; -use crate::prelude::*; +use crate::{prelude::*, utils::*}; use ::zenoh::{ bytes::{Encoding, ZBytes}, diff --git a/src/lib.rs b/src/lib.rs index e1941166..cf843441 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -149,6 +149,9 @@ pub use workflow::*; pub mod testing; +pub(crate) mod utils; +pub(crate) use utils::*; + #[cfg(feature = "trace")] pub mod trace; #[cfg(feature = "trace")] diff --git a/src/ros2.rs b/src/ros2.rs index e164a16e..ac40e205 100644 --- a/src/ros2.rs +++ b/src/ros2.rs @@ -15,5 +15,73 @@ * */ -use crate::Builder; +use crate::{Builder, Node, StreamPack, AsyncMap, NeverFinish}; +use rclrs::{Node as Ros2Node, IntoPrimitiveOptions, SubscriptionOptions, RclrsError, MessageIDL}; +use tokio::sync::mpsc::{UnboundedSender, unbounded_channel}; +use futures_lite::future::race; +#[derive(StreamPack)] +pub struct SubscriptionStreams { + pub out: T, + pub canceller: UnboundedSender, +} + +pub trait BuildRos2 { + fn create_ros2_subscription<'o, T: MessageIDL, Cancel>( + &mut self, + executor: Ros2Node, + options: impl Into>, + ) -> Node<(), Result, SubscriptionStreams> + where + Cancel: 'static + Send + Sync; +} + +impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { + fn create_ros2_subscription<'o, T: MessageIDL, Cancel>( + &mut self, + ros2_node: Ros2Node, + options: impl Into>, + ) -> Node<(), Result, SubscriptionStreams> + where + Cancel: 'static + Send + Sync + { + let SubscriptionOptions { topic, qos, .. } = options.into(); + let topic = topic.to_owned(); + self.create_map(move |input: AsyncMap<(), SubscriptionStreams>| { + let topic = topic.clone(); + let qos = qos.clone(); + let ros2_node = ros2_node.clone(); + let (cancel_sender, mut cancel_receiver) = unbounded_channel(); + input.streams.canceller.send(cancel_sender); + + let subscribing = async move { + let mut receiver = ros2_node.create_subscription_receiver::( + (&topic).qos(qos) + )?; + + while let Some(msg) = receiver.recv().await { + input.streams.out.send(msg); + } + + unreachable!( + "The channel of a SubscriptionReceiver can never close \ + because it keeps ownership of both the sender and receiver." + ); + }; + + let cancellation = async move { + let Some(msg) = cancel_receiver.recv().await else { + // The canceller was dropped, meaning the user will never + // cancel this node, so it should just keep running forever + // (it will be forcibly stopped during the workflow cleanup) + NeverFinish.await; + unreachable!("this future will never finish"); + }; + + Ok(msg) + }; + + race(subscribing, cancellation) + }) + } +} diff --git a/src/service.rs b/src/service.rs index 731d2979..c170a702 100644 --- a/src/service.rs +++ b/src/service.rs @@ -224,7 +224,7 @@ define_label!( DELIVERY_LABEL_INTERNER ); -pub mod utils { +pub mod service_utils { /// Used by the procedural macro for DeliveryLabel pub use bevy_utils::label::DynEq; } diff --git a/src/utils.rs b/src/utils.rs new file mode 100644 index 00000000..13bd4e6e --- /dev/null +++ b/src/utils.rs @@ -0,0 +1,72 @@ +/* + * Copyright (C) 2025 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +//! Miscellaneous utilities used internally + +use std::{ + future::Future, + pin::Pin, + task::{Context, Poll}, +}; + +/// Used with `#[serde(default, skip_serializing_if = "is_default")]` for fields +/// that don't need to be serialized if they are a default value. +#[allow(unused)] +pub(crate) fn is_default(value: &T) -> bool { + let default = T::default(); + *value == default +} + +/// Used with `#[serde(default = "default_as_true", skip_serializing_if = "is_true")]` +/// for bools that should be true by default. +#[allow(unused)] +pub(crate) fn default_as_true() -> bool { + true +} + +/// Used with `#[serde(default = "default_as_true", skip_serializing_if = "is_true")]` +/// for bools that should be true by default. +#[allow(unused)] +pub(crate) fn is_true(value: &bool) -> bool { + *value +} + +/// This is used to block a future from ever returning. This should only be used +/// in a race to force one of the contesting futures to lose. Make sure that at +/// least one contesting future will finish or else this will lead to a deadlock. +#[allow(unused)] +pub(crate) struct NeverFinish; + +impl Future for NeverFinish { + type Output = Never; + fn poll(self: Pin<&mut Self>, _: &mut Context<'_>) -> Poll { + Poll::Pending + } +} + +/// A data structure that can never be instantiated +pub(crate) enum Never {} + +/// Used by some tests in the grpc and zenoh modules +#[allow(unused)] +pub(crate) fn clamp(val: f32, limit: f32) -> f32 { + if f32::abs(val) > limit { + return f32::signum(val) * limit; + } + + val +} From 515dcd48482171eade497cc0258cf453e61a8dc5 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 10 Oct 2025 17:53:42 +0800 Subject: [PATCH 03/11] Add ROS 2 publisher and client operations Signed-off-by: Michael X. Grey --- src/ros2.rs | 113 ++++++++++++++++++++++++++++++++++++++++++++++------ 1 file changed, 101 insertions(+), 12 deletions(-) diff --git a/src/ros2.rs b/src/ros2.rs index ac40e205..426ada00 100644 --- a/src/ros2.rs +++ b/src/ros2.rs @@ -16,38 +16,66 @@ */ use crate::{Builder, Node, StreamPack, AsyncMap, NeverFinish}; -use rclrs::{Node as Ros2Node, IntoPrimitiveOptions, SubscriptionOptions, RclrsError, MessageIDL}; +use rclrs::{ + Node as Ros2Node, IntoPrimitiveOptions, SubscriptionOptions, PublisherOptions, + RclrsError, MessageIDL, ClientOptions, ServiceIDL, +}; use tokio::sync::mpsc::{UnboundedSender, unbounded_channel}; use futures_lite::future::race; #[derive(StreamPack)] -pub struct SubscriptionStreams { +pub struct SubscriptionStreams { pub out: T, - pub canceller: UnboundedSender, + pub canceller: UnboundedSender, } +#[derive(StreamPack)] +pub struct ServiceClientStreams { + pub canceller: UnboundedSender, +} + +pub type ServiceClientNode = Node< + ::Request, + Result<::Response, Result>, + ServiceClientStreams, +>; + pub trait BuildRos2 { - fn create_ros2_subscription<'o, T: MessageIDL, Cancel>( + fn create_ros2_subscription<'o, T: MessageIDL, CancelSignal>( &mut self, - executor: Ros2Node, + ros2_node: Ros2Node, options: impl Into>, - ) -> Node<(), Result, SubscriptionStreams> + ) -> Node<(), Result, SubscriptionStreams> where - Cancel: 'static + Send + Sync; + CancelSignal: 'static + Send + Sync; + + fn create_ros2_publisher<'o, T: MessageIDL>( + &mut self, + ros2_node: Ros2Node, + options: impl Into>, + ) -> Result>, RclrsError>; + + fn create_ros2_client<'o, T: ServiceIDL, CancelSignal>( + &mut self, + ros2_node: Ros2Node, + options: impl Into>, + ) -> Result, RclrsError> + where + CancelSignal: 'static + Send + Sync; } impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { - fn create_ros2_subscription<'o, T: MessageIDL, Cancel>( + fn create_ros2_subscription<'o, T: MessageIDL, CancelSignal>( &mut self, ros2_node: Ros2Node, options: impl Into>, - ) -> Node<(), Result, SubscriptionStreams> + ) -> Node<(), Result, SubscriptionStreams> where - Cancel: 'static + Send + Sync + CancelSignal: 'static + Send + Sync { let SubscriptionOptions { topic, qos, .. } = options.into(); let topic = topic.to_owned(); - self.create_map(move |input: AsyncMap<(), SubscriptionStreams>| { + self.create_map(move |input: AsyncMap<(), SubscriptionStreams>| { let topic = topic.clone(); let qos = qos.clone(); let ros2_node = ros2_node.clone(); @@ -57,7 +85,8 @@ impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { let subscribing = async move { let mut receiver = ros2_node.create_subscription_receiver::( (&topic).qos(qos) - )?; + ) + .map_err(|err| err.to_string())?; while let Some(msg) = receiver.recv().await { input.streams.out.send(msg); @@ -84,4 +113,64 @@ impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { race(subscribing, cancellation) }) } + + fn create_ros2_publisher<'o, T: MessageIDL>( + &mut self, + ros2_node: Ros2Node, + options: impl Into>, + ) -> Result>, RclrsError> { + let publisher = ros2_node.create_publisher(options)?; + let node = self.create_map_block(move |message: T| { + publisher + .publish(message) + .map_err(|err| err.to_string()) + }); + Ok(node) + } + + fn create_ros2_client<'o, T: ServiceIDL, CancelSignal>( + &mut self, + ros2_node: Ros2Node, + options: impl Into>, + ) -> Result, RclrsError> + where + CancelSignal: 'static + Send + Sync, + { + let client = ros2_node.create_client::(options)?; + let node = self.create_map(move |input: AsyncMap>| { + let AsyncMap { request, streams, .. } = input; + let receiver = client.call(request); + let (cancel_sender, mut cancel_receiver) = unbounded_channel(); + streams.canceller.send(cancel_sender); + + let receive = async move { + let response: Result = match receiver { + Ok(receiver) => receiver.await, + Err(err) => return Err(Err(err.to_string())), + }; + + let Ok(response) = response else { + return Err(Err(String::from("response was cancelled by the executor"))); + }; + + Ok(response) + }; + + let cancellation = async move { + let Some(msg) = cancel_receiver.recv().await else { + // The canceller was dropped, meaning the user will never + // cancel this node, so it should just keep running forever + // (it will be forcibly stopped during the workflow cleanup) + NeverFinish.await; + unreachable!("this future will never finish"); + }; + + Err(Ok(msg)) + }; + + race(receive, cancellation) + }); + + Ok(node) + } } From 2cb2f11364ba0399ca696dc67b7ceb9144093349 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Fri, 10 Oct 2025 23:27:44 +0800 Subject: [PATCH 04/11] Implement ROS 2 action client operation Signed-off-by: Michael X. Grey --- Cargo.toml | 1 + src/async_execution/mod.rs | 2 +- src/channel.rs | 10 ++- src/ros2.rs | 135 ++++++++++++++++++++++++++++++++++--- 4 files changed, 134 insertions(+), 14 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index 50acacdc..970f683f 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -117,6 +117,7 @@ zenoh = [ ros2 = [ "dep:rclrs", "dep:futures-lite", + "dep:serde", ] # Turn on all capability related features. This differs from --all-features diff --git a/src/async_execution/mod.rs b/src/async_execution/mod.rs index d2dc40ba..e176ec0f 100644 --- a/src/async_execution/mod.rs +++ b/src/async_execution/mod.rs @@ -26,7 +26,7 @@ pub(crate) use single_threaded_execution::SingleThreadedExecution; #[cfg(feature = "single_threaded_async")] use single_threaded_execution::SingleThreadedExecutionSender; -pub(crate) use bevy_tasks::Task as TaskHandle; +pub use bevy_tasks::Task as TaskHandle; #[cfg(not(feature = "single_threaded_async"))] pub(crate) type CancelSender = AsyncComputeTaskPoolSender; diff --git a/src/channel.rs b/src/channel.rs index 2c97fb15..2ca6c5a1 100644 --- a/src/channel.rs +++ b/src/channel.rs @@ -24,9 +24,15 @@ use tokio::sync::mpsc::{ unbounded_channel, UnboundedReceiver as TokioReceiver, UnboundedSender as TokioSender, }; -use std::sync::Arc; +use std::{ + future::Future, + sync::Arc, +}; -use crate::{OperationError, OperationRoster, Promise, Provider, RequestExt, StreamPack}; +use crate::{ + OperationError, OperationRoster, Promise, Provider, RequestExt, StreamPack, Sendish, + async_execution::TaskHandle, +}; /// Provides asynchronous access to the [`World`], allowing you to issue queries /// or commands and then await the result. diff --git a/src/ros2.rs b/src/ros2.rs index 426ada00..eec3fd66 100644 --- a/src/ros2.rs +++ b/src/ros2.rs @@ -18,10 +18,14 @@ use crate::{Builder, Node, StreamPack, AsyncMap, NeverFinish}; use rclrs::{ Node as Ros2Node, IntoPrimitiveOptions, SubscriptionOptions, PublisherOptions, - RclrsError, MessageIDL, ClientOptions, ServiceIDL, + GoalEvent, GoalStatus, GoalStatusCode, CancelResponse, + RclrsError, MessageIDL, ClientOptions, ActionClientOptions, ServiceIDL, ActionIDL, }; use tokio::sync::mpsc::{UnboundedSender, unbounded_channel}; use futures_lite::future::race; +use futures::{StreamExt, future::{select, Either}}; +use serde::{Serialize, Deserialize}; +use std::pin::pin; #[derive(StreamPack)] pub struct SubscriptionStreams { @@ -34,12 +38,40 @@ pub struct ServiceClientStreams { pub canceller: UnboundedSender, } -pub type ServiceClientNode = Node< - ::Request, - Result<::Response, Result>, +pub type ServiceClientNode = Node< + ::Request, + Result<::Response, Result>, ServiceClientStreams, >; +#[derive(StreamPack)] +pub struct ActionClientStreams { + pub feedback: A::Feedback, + pub canceller: UnboundedSender, + pub status: GoalStatus, + pub cancellation_response: ActionCancellation, +} + +pub type ActionClientNode = Node< + ::Goal, + Result, Result>, + ActionClientStreams, +>; + +/// This is the final result returned by a ROS 2 action if it ended under normal +/// circumstances. +#[derive(Debug, Clone, Serialize, Deserialize)] +pub struct ActionResult { + pub status: GoalStatusCode, + pub result: A::Result, +} + +#[derive(Debug, Clone, Serialize, Deserialize)] +pub struct ActionCancellation { + pub signal: CancelSignal, + pub response: CancelResponse, +} + pub trait BuildRos2 { fn create_ros2_subscription<'o, T: MessageIDL, CancelSignal>( &mut self, @@ -55,11 +87,19 @@ pub trait BuildRos2 { options: impl Into>, ) -> Result>, RclrsError>; - fn create_ros2_client<'o, T: ServiceIDL, CancelSignal>( + fn create_ros2_service_client<'o, S: ServiceIDL, CancelSignal>( &mut self, ros2_node: Ros2Node, options: impl Into>, - ) -> Result, RclrsError> + ) -> Result, RclrsError> + where + CancelSignal: 'static + Send + Sync; + + fn create_ros2_action_client<'o, A: ActionIDL, CancelSignal>( + &mut self, + ros2_node: Ros2Node, + options: impl Into>, + ) -> Result, RclrsError> where CancelSignal: 'static + Send + Sync; } @@ -128,23 +168,23 @@ impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { Ok(node) } - fn create_ros2_client<'o, T: ServiceIDL, CancelSignal>( + fn create_ros2_service_client<'o, S: ServiceIDL, CancelSignal>( &mut self, ros2_node: Ros2Node, options: impl Into>, - ) -> Result, RclrsError> + ) -> Result, RclrsError> where CancelSignal: 'static + Send + Sync, { - let client = ros2_node.create_client::(options)?; - let node = self.create_map(move |input: AsyncMap>| { + let client = ros2_node.create_client::(options)?; + let node = self.create_map(move |input: AsyncMap>| { let AsyncMap { request, streams, .. } = input; let receiver = client.call(request); let (cancel_sender, mut cancel_receiver) = unbounded_channel(); streams.canceller.send(cancel_sender); let receive = async move { - let response: Result = match receiver { + let response: Result = match receiver { Ok(receiver) => receiver.await, Err(err) => return Err(Err(err.to_string())), }; @@ -173,4 +213,77 @@ impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { Ok(node) } + + fn create_ros2_action_client<'o, A: ActionIDL, CancelSignal>( + &mut self, + ros2_node: Ros2Node, + options: impl Into>, + ) -> Result, RclrsError> + where + CancelSignal: 'static + Send + Sync + { + let client = ros2_node.create_action_client::(options)?; + let node = self.create_map(move |input: AsyncMap>| { + let AsyncMap { request, streams, .. } = input; + let goal_requested = client.request_goal(request); + let (cancel_sender, mut cancel_receiver) = unbounded_channel(); + streams.canceller.send(cancel_sender); + + async move { + let Some(goal_client) = goal_requested.await else { + return Err(Err(String::from("goal was rejected"))); + }; + + let canceller = goal_client.cancellation.clone(); + let mut goal_client_stream = goal_client.stream(); + + let receiving = async move { + while let Some(event) = goal_client_stream.next().await { + match event { + GoalEvent::Feedback(feedback) => { + streams.feedback.send(feedback); + } + GoalEvent::Status(status) => { + streams.status.send(status); + } + GoalEvent::Result((status, result)) => { + return Ok(ActionResult { status, result }); + } + } + } + + Err(Err(String::from("goal stream closed without receiving result"))) + }; + + let cancellation = async move { + loop { + let Some(signal) = cancel_receiver.recv().await else { + // The canceller was dropped, meaning the user will never + // cancel this node, so it should just keep running forever + // (it will be forcibly stopped during the workflow cleanup) + NeverFinish.await; + unreachable!("this future will never finish"); + }; + + let response = canceller.cancel().await; + streams.cancellation_response.send(ActionCancellation { + signal, + response, + }); + } + }; + + match select(pin!(receiving), pin!(cancellation)).await { + Either::Left((received, _)) => { + return received; + } + Either::Right(_) => { + unreachable!("the cancellation future will never finish"); + } + } + } + }); + + Ok(node) + } } From 3c0b94d85061d56564477dc10862e0a44418a675 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Sat, 11 Oct 2025 16:06:51 +0800 Subject: [PATCH 05/11] Introduce diagram node builders for ros2 Signed-off-by: Michael X. Grey --- Cargo.toml | 3 +- ros2-feature.repos | 4 +- src/channel.rs | 8 +- src/diagram.rs | 5 ++ src/diagram/ros2.rs | 177 ++++++++++++++++++++++++++++++++++++++++++++ src/lib.rs | 3 + src/ros2.rs | 40 +++++++--- 7 files changed, 219 insertions(+), 21 deletions(-) create mode 100644 src/diagram/ros2.rs diff --git a/Cargo.toml b/Cargo.toml index 970f683f..4229c50c 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -72,7 +72,7 @@ zenoh-ext = { version = "*", features = ["unstable"], optional = true } # --- end zenoh # --- Dependencies for ros2 feature -rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "crossflow", features = ["serde"], optional = true } +rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "crossflow", features = ["serde", "schemars"], optional = true } # --- end ros2 tracing = "0.1.41" @@ -118,6 +118,7 @@ ros2 = [ "dep:rclrs", "dep:futures-lite", "dep:serde", + "dep:schemars", ] # Turn on all capability related features. This differs from --all-features diff --git a/ros2-feature.repos b/ros2-feature.repos index 22fc8940..61fe97d7 100644 --- a/ros2-feature.repos +++ b/ros2-feature.repos @@ -30,8 +30,8 @@ repositories: ros2-rust/rosidl_rust: type: git url: https://github.com/mxgrey/rosidl_rust.git - version: fix_actions + version: crossflow ros2-rust/rosidl_runtime_rs: type: git url: https://github.com/mxgrey/rosidl_runtime_rs.git - version: fix_actions + version: crossflow diff --git a/src/channel.rs b/src/channel.rs index 2ca6c5a1..651b7058 100644 --- a/src/channel.rs +++ b/src/channel.rs @@ -24,14 +24,10 @@ use tokio::sync::mpsc::{ unbounded_channel, UnboundedReceiver as TokioReceiver, UnboundedSender as TokioSender, }; -use std::{ - future::Future, - sync::Arc, -}; +use std::sync::Arc; use crate::{ - OperationError, OperationRoster, Promise, Provider, RequestExt, StreamPack, Sendish, - async_execution::TaskHandle, + OperationError, OperationRoster, Promise, Provider, RequestExt, StreamPack, }; /// Provides asynchronous access to the [`World`], allowing you to issue queries diff --git a/src/diagram.rs b/src/diagram.rs index 5d03efc4..a3986fe9 100644 --- a/src/diagram.rs +++ b/src/diagram.rs @@ -38,6 +38,11 @@ mod grpc; #[cfg(feature = "zenoh")] mod zenoh; +#[cfg(feature = "ros2")] +mod ros2; +#[cfg(feature = "ros2")] +pub use ros2::*; + use bevy_derive::{Deref, DerefMut}; use bevy_ecs::system::Commands; use buffer_schema::{BufferAccessSchema, BufferSchema, ListenSchema}; diff --git a/src/diagram/ros2.rs b/src/diagram/ros2.rs new file mode 100644 index 00000000..1cc770dc --- /dev/null +++ b/src/diagram/ros2.rs @@ -0,0 +1,177 @@ +/* + * Copyright (C) 2025 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +use super::*; +use crate::BuildRos2; +use rclrs::{ + Node as Ros2Node, MessageIDL, ServiceIDL, ActionIDL, QoSProfile, ActionClientOptions, + SubscriptionOptions, PublisherOptions, ClientOptions, PrimitiveOptions, IntoPrimitiveOptions, +}; +use serde::de::DeserializeOwned; + +impl DiagramElementRegistry { + /// Use this to register workflow node builders that will produce subscriptions, + /// publishers, service clients, and action clients belong to a specific ROS 2 + /// node. + /// + /// This will return a [`Ros2Registry`] which you can use to register messages + /// (for subscriptions and publishers), services, and actions. + /// + /// The node builders that get registered will be named + /// `{node_name}_{type_name}_{subscription|publisher|service_client|action_client}` + #[must_use = "no node builders will be created unless you register the specific messages, services, or actions that you need"] + pub fn enable_ros2(&mut self, ros2_node: Ros2Node) -> Ros2Registry<'_> { + Ros2Registry { ros2_node, registry: self } + } +} + +/// Use this to register message, service, and action bindings so that the +/// registry can build workflow nodes for ROS 2 subscriptions, publishers, +/// service clients, and action clients. +pub struct Ros2Registry<'a> { + ros2_node: Ros2Node, + registry: &'a mut DiagramElementRegistry, +} + +impl<'a> Ros2Registry<'a> { + /// Register a message definition to obtain node builders for publishers and + /// subscriptions for this message type. + pub fn register_ros2_message(&mut self) { + let node_name = self.ros2_node.name(); + let message_name = T::TYPE_NAME; + + let ros2_node = self.ros2_node.clone(); + self.registry.register_node_builder( + NodeBuilderOptions::new(format!("{node_name}_{message_name}_subscription")) + .with_default_display_text(format!("{message_name} Subscription")), + move |builder, config: TopicConfig| { + builder.create_ros2_subscription::(ros2_node.clone(), &config) + } + ); + + let ros2_node = self.ros2_node.clone(); + self.registry.register_node_builder_fallible( + NodeBuilderOptions::new(format!("{node_name}_{message_name}_publisher")) + .with_default_display_text(format!("{message_name} Publisher", )), + move |builder, config: TopicConfig| { + let node = builder.create_ros2_publisher::(ros2_node.clone(), &config)?; + Ok(node) + } + ); + } + + /// Register a service definition to obtain a node builder for a service + /// client that can use this service definition. + pub fn register_ros2_service(&mut self) + where + S::Request: Serialize + DeserializeOwned + JsonSchema, + S::Response: Serialize + DeserializeOwned + JsonSchema, + { + let node_name = self.ros2_node.name(); + let service_name = S::TYPE_NAME; + + let ros2_node = self.ros2_node.clone(); + self.registry.register_node_builder_fallible( + NodeBuilderOptions::new(format!("{node_name}_{service_name}_client")) + .with_default_display_text(format!("{service_name} Client")), + move |builder, config: TopicConfig| { + let node = builder.create_ros2_service_client::(ros2_node.clone(), &config)?; + Ok(node) + } + ); + } + + /// Register an action definition to obtain a node builder for an action + /// client that can use this action definition. + pub fn register_ros2_action(&mut self) + where + A::Goal: Serialize + DeserializeOwned + JsonSchema, + A::Result: Serialize + DeserializeOwned + JsonSchema, + A::Feedback: Serialize + DeserializeOwned + JsonSchema, + { + let node_name = self.ros2_node.name(); + let action_name = A::TYPE_NAME; + + let ros2_node = self.ros2_node.clone(); + self.registry.register_node_builder_fallible( + NodeBuilderOptions::new(format!("{node_name}_{action_name}_client")) + .with_default_display_text(format!("{action_name} Client")), + move |builder, config: ActionClientConfig| { + let node = builder.create_ros2_action_client::(ros2_node.clone(), &config)?; + Ok(node) + } + ); + } +} + +#[derive(Debug, Clone, Serialize, Deserialize, JsonSchema)] +pub struct TopicConfig { + pub topic: Arc, + pub qos: QoSProfile, +} + +impl<'a> From<&'a TopicConfig> for SubscriptionOptions<'a> { + fn from(value: &'a TopicConfig) -> Self { + PrimitiveOptions::new(&value.topic) + .qos(value.qos.clone()) + .into() + } +} + +impl<'a> From<&'a TopicConfig> for PublisherOptions<'a> { + fn from(value: &'a TopicConfig) -> Self { + PrimitiveOptions::new(&value.topic) + .qos(value.qos.clone()) + .into() + } +} + +impl<'a> From<&'a TopicConfig> for ClientOptions<'a> { + fn from(value: &'a TopicConfig) -> Self { + PrimitiveOptions::new(&value.topic) + .qos(value.qos.clone()) + .into() + } +} + +#[derive(Debug, Clone, Serialize, Deserialize, JsonSchema)] +pub struct ActionClientConfig { + /// The name of the action that this client will send requests to + pub action: Arc, + /// The quality of service profile for the goal service + pub goal_service_qos: QoSProfile, + /// The quality of service profile for the result service + pub result_service_qos: QoSProfile, + /// The quality of service profile for the cancel service + pub cancel_service_qos: QoSProfile, + /// The quality of service profile for the feedback topic + pub feedback_topic_qos: QoSProfile, + /// The quality of service profile for the status topic + pub status_topic_qos: QoSProfile, +} + +impl<'a> From<&'a ActionClientConfig> for ActionClientOptions<'a> { + fn from(value: &'a ActionClientConfig) -> Self { + let mut options = ActionClientOptions::new(&value.action); + options.goal_service_qos = value.goal_service_qos.clone(); + options.result_service_qos = value.result_service_qos.clone(); + options.cancel_service_qos = value.cancel_service_qos.clone(); + options.feedback_topic_qos = value.feedback_topic_qos.clone(); + options.status_topic_qos = value.status_topic_qos.clone(); + options + } +} diff --git a/src/lib.rs b/src/lib.rs index cf843441..91e44a80 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -428,5 +428,8 @@ pub mod prelude { diagram::{Diagram, DiagramElementRegistry, DiagramError, NodeBuilderOptions, Section}, }; + #[cfg(feature = "ros2")] + pub use crate::BuildRos2; + pub use futures::FutureExt; } diff --git a/src/ros2.rs b/src/ros2.rs index eec3fd66..aca58136 100644 --- a/src/ros2.rs +++ b/src/ros2.rs @@ -1,5 +1,5 @@ /* - * Copyright (C) 2024 Open Source Robotics Foundation + * Copyright (C) 2025 Open Source Robotics Foundation * * Licensed under the Apache License, Version 2.0 (the "License"); * you may not use this file except in compliance with the License. @@ -24,8 +24,12 @@ use rclrs::{ use tokio::sync::mpsc::{UnboundedSender, unbounded_channel}; use futures_lite::future::race; use futures::{StreamExt, future::{select, Either}}; -use serde::{Serialize, Deserialize}; -use std::pin::pin; +use serde::{Serialize, Deserialize, de::DeserializeOwned}; +use std::{ + pin::pin, + sync::Arc, +}; +use schemars::JsonSchema; #[derive(StreamPack)] pub struct SubscriptionStreams { @@ -54,16 +58,16 @@ pub struct ActionClientStreams = Node< ::Goal, - Result, Result>, + Result::Result>, Result>, ActionClientStreams, >; /// This is the final result returned by a ROS 2 action if it ended under normal /// circumstances. -#[derive(Debug, Clone, Serialize, Deserialize)] -pub struct ActionResult { +#[derive(Debug, Clone, Serialize, Deserialize, JsonSchema)] +pub struct ActionResult { pub status: GoalStatusCode, - pub result: A::Result, + pub result: R, } #[derive(Debug, Clone, Serialize, Deserialize)] @@ -101,7 +105,8 @@ pub trait BuildRos2 { options: impl Into>, ) -> Result, RclrsError> where - CancelSignal: 'static + Send + Sync; + CancelSignal: 'static + Send + Sync, + A::Result: Serialize + DeserializeOwned + JsonSchema; } impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { @@ -179,11 +184,16 @@ impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { let client = ros2_node.create_client::(options)?; let node = self.create_map(move |input: AsyncMap>| { let AsyncMap { request, streams, .. } = input; - let receiver = client.call(request); + let client = Arc::clone(&client); let (cancel_sender, mut cancel_receiver) = unbounded_channel(); streams.canceller.send(cancel_sender); let receive = async move { + client.notify_on_service_ready() + .await + .map_err(|_| Err(String::from("failed to wait for action server")))?; + + let receiver = client.call(request); let response: Result = match receiver { Ok(receiver) => receiver.await, Err(err) => return Err(Err(err.to_string())), @@ -220,16 +230,22 @@ impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { options: impl Into>, ) -> Result, RclrsError> where - CancelSignal: 'static + Send + Sync + CancelSignal: 'static + Send + Sync, + A::Result: Serialize + DeserializeOwned + JsonSchema, { let client = ros2_node.create_action_client::(options)?; let node = self.create_map(move |input: AsyncMap>| { let AsyncMap { request, streams, .. } = input; - let goal_requested = client.request_goal(request); + let client = Arc::clone(&client); let (cancel_sender, mut cancel_receiver) = unbounded_channel(); streams.canceller.send(cancel_sender); async move { + client.notify_on_action_ready() + .await + .map_err(|_| Err(String::from("failed to wait for action server")))?; + + let goal_requested = client.request_goal(request); let Some(goal_client) = goal_requested.await else { return Err(Err(String::from("goal was rejected"))); }; @@ -260,7 +276,7 @@ impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { let Some(signal) = cancel_receiver.recv().await else { // The canceller was dropped, meaning the user will never // cancel this node, so it should just keep running forever - // (it will be forcibly stopped during the workflow cleanup) + // (it will be forcibly stopped during the node cleanup) NeverFinish.await; unreachable!("this future will never finish"); }; From 6cbb737db9f93b4d9da0ddd9875c8740224d0254 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Sat, 11 Oct 2025 22:27:22 +0800 Subject: [PATCH 06/11] Migrate nav example to use new core ros2 feature Signed-off-by: Michael X. Grey --- Cargo.toml | 24 +++-- examples/ros2/Cargo.toml | 17 ++- examples/ros2/src/nav_example.rs | 174 ++++++++++++------------------- src/buffer/json_buffer.rs | 19 ++++ src/diagram/ros2.rs | 135 +++++++++++++----------- src/lib.rs | 4 +- src/ros2.rs | 4 +- 7 files changed, 193 insertions(+), 184 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index 4229c50c..b7e9fef4 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -16,17 +16,24 @@ categories = [ ] [workspace.dependencies] +bevy_ecs = "0.12" +bevy_utils = "0.12" +bevy_hierarchy = "0.12" +bevy_derive = "0.12" +bevy_app = "0.12" schemars = { version = "0.9.0" } serde = { version = "1.0.210", features = ["derive", "rc"] } serde_json = { version = "1.0.128" } +rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "crossflow", features = ["serde", "schemars"] } +tokio = { version = "1.39" } [dependencies] bevy_impulse_derive = { path = "macros", version = "0.0.2" } -bevy_ecs = "0.12" -bevy_utils = "0.12" -bevy_hierarchy = "0.12" -bevy_derive = "0.12" -bevy_app = "0.12" +bevy_ecs = { workspace = true } +bevy_utils = { workspace = true } +bevy_hierarchy = { workspace = true } +bevy_derive = { workspace = true } +bevy_app = { workspace = true } async-task = { version = "4.7.1", optional = true } @@ -37,7 +44,7 @@ bevy_tasks = { version = "0.12", features = ["multi-threaded"] } itertools = "0.13" smallvec = { version = "1.13", features = ["serde"] } -tokio = { version = "1.39", features = ["sync"] } +tokio = { workspace = true, features = ["sync"] } futures = "0.3" backtrace = "0.3" anyhow = "1.0" @@ -72,7 +79,7 @@ zenoh-ext = { version = "*", features = ["unstable"], optional = true } # --- end zenoh # --- Dependencies for ros2 feature -rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "crossflow", features = ["serde", "schemars"], optional = true } +rclrs = { workspace = true, optional = true } # --- end ros2 tracing = "0.1.41" @@ -157,3 +164,6 @@ doc = false [build-dependencies] tonic-prost-build = { version = "0.14", optional = true } + +[patch.crates-io] +rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "crossflow" } diff --git a/examples/ros2/Cargo.toml b/examples/ros2/Cargo.toml index b19331a8..229691ae 100644 --- a/examples/ros2/Cargo.toml +++ b/examples/ros2/Cargo.toml @@ -19,15 +19,14 @@ path = "src/goal_requester.rs" bevy_app = "0.12" bevy_core = "0.12" bevy_impulse = { path = "../..", features = ["diagram", "ros2"] } -serde = "*" -schemars = "*" -serde_json = "*" -tokio = { version = "1.39", features = ["sync"] } +serde = { workspace = true } +schemars = { workspace = true } +serde_json = { workspace = true } clap = { version = "*", features = ["derive"] } rand = "*" -rclrs = { git = "https://github.com/mxgrey/ros2_rust", branch = "crossflow", features = ["serde"] } -nav_msgs = { version = "*", features = ["serde"] } -geometry_msgs = { version = "*", features = ["serde"] } -std_msgs = { version = "*", features = ["serde"] } -builtin_interfaces = { version = "*", features = ["serde"] } +rclrs = { workspace = true } +nav_msgs = { version = "*", features = ["serde", "schemars"] } +geometry_msgs = { version = "*", features = ["serde", "schemars"] } +std_msgs = { version = "*", features = ["serde", "schemars"] } +builtin_interfaces = { version = "*", features = ["serde", "schemars"] } diff --git a/examples/ros2/src/nav_example.rs b/examples/ros2/src/nav_example.rs index 248aa4b8..c1742ca8 100644 --- a/examples/ros2/src/nav_example.rs +++ b/examples/ros2/src/nav_example.rs @@ -18,11 +18,10 @@ use rclrs::{*, Promise}; use bevy_impulse::prelude::*; use serde::{Serialize, Deserialize}; -use schemars::JsonSchema; -use tokio::sync::mpsc::unbounded_channel; use serde_json::json; use bevy_app::ScheduleRunnerPlugin; use bevy_core::{FrameCountPlugin, TaskPoolPlugin, TypeRegistrationPlugin}; +use schemars::JsonSchema; use std::collections::VecDeque; @@ -42,38 +41,12 @@ fn main() { let mut registry = DiagramElementRegistry::new(); let node = executor.create_node("nav_manager").unwrap(); - // Create a subscriber that listens for goal messages to arrive. - registry.register_node_builder( - NodeBuilderOptions::new("receive_goals"), - { - let node = node.clone(); - move |builder, config: SubscriptionConfig| { - let node = node.clone(); - builder.create_map(move |input: AsyncMap<(), GoalStream>| { - let (sender, mut receiver) = unbounded_channel(); - - let _subscription = node.create_subscription( - config.topic.transient_local(), - move |msg: Goals| { - let _ = sender.send(msg); - } - ).unwrap(); - - let logger = node.logger().clone(); - log!(&logger, "Waiting to receive goals from topic {}...", config.topic); - async move { - // Force the _subscription variable to be captured since - // it has side effects. - let _subscription = _subscription; - while let Some(msg) = receiver.recv().await { - log!(&logger, "Received a sequence of {} goals", msg.goals.len()); - input.streams.goals.send(msg); - } - } - }) - } - } - ); + registry + .enable_ros2(node.clone()) + .register_ros2_message::() + .register_ros2_message::() + .register_ros2_message::() + .register_ros2_service::(); // Create a client that fetches plans from a server. Each pair of // consecutive goals is planned for independently, in parallel. @@ -81,10 +54,13 @@ fn main() { // After issuing every plan request, we will await them in order of first to // last and stream them out from the node in that order, regardless of the // order in which the plans arrive from the service. + // + // We make a custom node builder for this instead of using the generic service + // client builder because we want the input to be processed in a specific way: + // breaking it into multiple parallel requests and reassembling them in order + // as they complete. In the future we might introduce generalized "enumerate" + // and "collect" operations which could replace this. registry - .opt_out() - .no_serializing() - .no_deserializing() .register_node_builder( NodeBuilderOptions::new("fetch_plans"), { @@ -130,54 +106,36 @@ fn main() { // We can't really execute the paths in this example program, so let's just // print whatever accumulates in the buffer. - let print_paths = app.world.spawn_service(print_paths.into_blocking_service()); registry .opt_out() .no_serializing() .no_deserializing() .register_node_builder( - NodeBuilderOptions::new("print_paths"), - move |builder, _config: ()| { - builder.create_node(print_paths) + NodeBuilderOptions::new("print_from_buffer"), + move |builder, msg: Option| { + let callback = move |In(key): In, world: &World| { + let buffer = world.json_buffer_view(&key).unwrap(); + let values: Result, _> = buffer.iter().collect(); + let values = values.unwrap(); + println!("{}{values:#?}", msg.as_ref().unwrap_or(&String::new())); + }; + + builder.create_node(callback.into_blocking_callback()) } ) .with_listen(); - registry - .opt_out() - .no_serializing() - .no_deserializing() - .register_message::(); - - // We'll provide a topic for clearing the goals from the buffer registry.register_node_builder( - NodeBuilderOptions::new("receive_cancel"), - { - let node = node.clone(); - move |builder, config: SubscriptionConfig| { - let node = node.clone(); - builder.create_map(move |input: AsyncMap<(), ClearSignalString>| { - let (sender, mut receiver) = unbounded_channel(); - - let _subscription = node.create_subscription( - config.topic.transient_local(), - move |_msg: EmptyMsg| { - let _ = sender.send(()); - } - ).unwrap(); - - let logger = node.logger().clone(); - async move { - // Force the _subscription variable to be captured since - // it has side effects. - let _subscription = _subscription; - while let Some(_) = receiver.recv().await { - log!(&logger, "Received a request to clear the goals"); - input.streams.clear.send(()); - } - } - }) - } + NodeBuilderOptions::new("print"), + move |builder, PrintConfig { message, include_value }: PrintConfig| { + builder.create_map_block(move |value: JsonMessage| { + if include_value { + println!("{message}{value:#?}"); + } else { + println!("{message}"); + } + value + }) } ); @@ -194,6 +152,7 @@ fn main() { ) .with_buffer_access(); + let request_goal_topic = "request_goal"; let diagram = Diagram::from_json(json!({ "version": "0.1.0", "start": "setup", @@ -201,19 +160,33 @@ fn main() { "setup": { "type": "fork_clone", "next": [ - "receive_goals", + "print_welcome", "receive_cancel" ] }, + "print_welcome": { + "type": "node", + "builder": "print", + "config": { + "message": format!("Waiting to receive goals from {request_goal_topic}"), + "include_value": false + }, + "next": "receive_goals" + }, "receive_goals": { "type": "node", - "builder": "receive_goals", + "builder": "nav_manager__nav_msgs_msg_Goals__subscription", "config": { - "topic": "request_goal" + "topic": format!("{request_goal_topic}"), }, "stream_out": { - "goals": "fetch_plans", + "out": "fetch_plans" }, + "next": "quit" + }, + "quit": { + "type": "transform", + "cel": "null", "next": { "builtin": "terminate" } }, "fetch_plans": { @@ -239,20 +212,26 @@ fn main() { }, "print_paths": { "type": "node", - "builder": "print_paths", + "builder": "print_from_buffer", + "config": "Paths currently waiting to run:\n", "next": { "builtin": "dispose" } }, "receive_cancel": { "type": "node", - "builder": "receive_cancel", + "builder": "nav_manager__std_msgs_msg_Empty__subscription", "config": { "topic": "cancel_goals" }, "stream_out": { - "clear": "access_paths" + "out": "trigger_clear_paths" }, "next": { "builtin": "dispose" } }, + "trigger_clear_paths": { + "type": "transform", + "cel": "null", + "next": "access_paths" + }, "access_paths": { "type": "buffer_access", "buffers": ["path_buffer"], @@ -283,20 +262,11 @@ fn main() { ImpulsePlugin::default(), )); + log!(&*node, "Beginning workflow..."); std::thread::spawn(move || executor.spin(SpinOptions::default())); app.run() } -#[derive(Serialize, Deserialize, JsonSchema)] -struct SubscriptionConfig { - topic: String, -} - -#[derive(StreamPack)] -struct GoalStream { - goals: Goals, -} - #[derive(Serialize, Deserialize, JsonSchema)] struct PlanningConfig { planner_service: String, @@ -308,20 +278,6 @@ struct PathStream { paths: Path, } -#[derive(StreamPack)] -struct ClearSignalString { - clear: (), -} - -fn print_paths( - In(key): In>, - access: BufferAccess, -) { - let buffer = access.get(&key).unwrap(); - let paths: Vec<&Path> = buffer.iter().collect(); - println!("Paths currently waiting to run:\n{paths:#?}"); -} - fn clear_paths( In((_, key)): In<((), BufferKey)>, mut access: BufferAccessMut, @@ -330,3 +286,9 @@ fn clear_paths( // Remove all goals from the buffer by draining its full range. buffer.drain(..); } + +#[derive(Serialize, Deserialize, JsonSchema)] +struct PrintConfig { + message: String, + include_value: bool, +} diff --git a/src/buffer/json_buffer.rs b/src/buffer/json_buffer.rs index 088a1f8c..5796153b 100644 --- a/src/buffer/json_buffer.rs +++ b/src/buffer/json_buffer.rs @@ -249,6 +249,11 @@ impl<'a> JsonBufferView<'a> { self.len() == 0 } + /// Iterate through the current elements of the buffer. + pub fn iter(&self) -> IterJsonBufferView<'a, '_> { + IterJsonBufferView { index: 0, view: self } + } + /// Check whether the gate of this buffer is open or closed. pub fn gate(&self) -> Gate { self.gate @@ -259,6 +264,20 @@ impl<'a> JsonBufferView<'a> { } } +pub struct IterJsonBufferView<'a, 'b> { + index: usize, + view: &'b JsonBufferView<'a>, +} + +impl<'a, 'b> Iterator for IterJsonBufferView<'a, 'b> { + type Item = Result; + fn next(&mut self) -> Option { + let next = self.index; + self.index += 1; + self.view.get(next).transpose() + } +} + /// Similar to [`BufferMut`][crate::BufferMut], but this can be unlocked with a /// [`JsonBufferKey`], so it can work for any buffer whose message types support /// serialization and deserialization. diff --git a/src/diagram/ros2.rs b/src/diagram/ros2.rs index 1cc770dc..a7128977 100644 --- a/src/diagram/ros2.rs +++ b/src/diagram/ros2.rs @@ -18,10 +18,12 @@ use super::*; use crate::BuildRos2; use rclrs::{ - Node as Ros2Node, MessageIDL, ServiceIDL, ActionIDL, QoSProfile, ActionClientOptions, - SubscriptionOptions, PublisherOptions, ClientOptions, PrimitiveOptions, IntoPrimitiveOptions, + Node as Ros2Node, MessageIDL, ServiceIDL, ActionIDL, ActionClientOptions, + PrimitiveOptions, QosOptions, + GoalStatus, GoalStatusCode, }; use serde::de::DeserializeOwned; +use tokio::sync::mpsc::UnboundedSender; impl DiagramElementRegistry { /// Use this to register workflow node builders that will produce subscriptions, @@ -50,101 +52,118 @@ pub struct Ros2Registry<'a> { impl<'a> Ros2Registry<'a> { /// Register a message definition to obtain node builders for publishers and /// subscriptions for this message type. - pub fn register_ros2_message(&mut self) { - let node_name = self.ros2_node.name(); + pub fn register_ros2_message(&mut self) -> &'_ mut Self { + let node_name_snake = self.ros2_node.name().replace("/", "_"); let message_name = T::TYPE_NAME; + let message_name_snake = message_name.replace("/", "_"); let ros2_node = self.ros2_node.clone(); self.registry.register_node_builder( - NodeBuilderOptions::new(format!("{node_name}_{message_name}_subscription")) + NodeBuilderOptions::new(format!("{node_name_snake}__{message_name_snake}__subscription")) .with_default_display_text(format!("{message_name} Subscription")), - move |builder, config: TopicConfig| { - builder.create_ros2_subscription::(ros2_node.clone(), &config) + move |builder, config: PrimitiveOptions| { + builder.create_ros2_subscription::(ros2_node.clone(), config) } - ); + ) + .with_fork_result(); + + // For cancel sender + self.registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_message::>(); let ros2_node = self.ros2_node.clone(); self.registry.register_node_builder_fallible( - NodeBuilderOptions::new(format!("{node_name}_{message_name}_publisher")) + NodeBuilderOptions::new(format!("{node_name_snake}__{message_name_snake}__publisher")) .with_default_display_text(format!("{message_name} Publisher", )), - move |builder, config: TopicConfig| { - let node = builder.create_ros2_publisher::(ros2_node.clone(), &config)?; + move |builder, config: PrimitiveOptions| { + let node = builder.create_ros2_publisher::(ros2_node.clone(), config)?; Ok(node) } - ); + ) + .with_fork_result(); + + self } /// Register a service definition to obtain a node builder for a service /// client that can use this service definition. - pub fn register_ros2_service(&mut self) + pub fn register_ros2_service(&mut self) -> &'_ mut Self where S::Request: Serialize + DeserializeOwned + JsonSchema, S::Response: Serialize + DeserializeOwned + JsonSchema, { - let node_name = self.ros2_node.name(); + let node_name_snake = self.ros2_node.name().replace("/", "_"); let service_name = S::TYPE_NAME; + let service_name_snake = service_name.replace("/", "_"); let ros2_node = self.ros2_node.clone(); self.registry.register_node_builder_fallible( - NodeBuilderOptions::new(format!("{node_name}_{service_name}_client")) + NodeBuilderOptions::new(format!("{node_name_snake}__{service_name_snake}__client")) .with_default_display_text(format!("{service_name} Client")), - move |builder, config: TopicConfig| { - let node = builder.create_ros2_service_client::(ros2_node.clone(), &config)?; + move |builder, config: PrimitiveOptions| { + let node = builder.create_ros2_service_client::(ros2_node.clone(), config)?; Ok(node) } - ); + ) + .with_fork_result(); + + self.registry + .register_message::>() + .with_fork_result(); + + // For cancel sender + self.registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_message::>(); + + self } /// Register an action definition to obtain a node builder for an action /// client that can use this action definition. - pub fn register_ros2_action(&mut self) + pub fn register_ros2_action(&mut self) -> &'_ mut Self where A::Goal: Serialize + DeserializeOwned + JsonSchema, A::Result: Serialize + DeserializeOwned + JsonSchema, A::Feedback: Serialize + DeserializeOwned + JsonSchema, { - let node_name = self.ros2_node.name(); + let node_name_snake = self.ros2_node.name().replace("/", "_"); let action_name = A::TYPE_NAME; + let action_name_snake = action_name.replace("/", "_"); let ros2_node = self.ros2_node.clone(); self.registry.register_node_builder_fallible( - NodeBuilderOptions::new(format!("{node_name}_{action_name}_client")) + NodeBuilderOptions::new(format!("{node_name_snake}__{action_name_snake}__client")) .with_default_display_text(format!("{action_name} Client")), move |builder, config: ActionClientConfig| { let node = builder.create_ros2_action_client::(ros2_node.clone(), &config)?; Ok(node) } - ); - } -} + ) + .with_fork_result(); -#[derive(Debug, Clone, Serialize, Deserialize, JsonSchema)] -pub struct TopicConfig { - pub topic: Arc, - pub qos: QoSProfile, -} + self.registry + .register_message::>() + .with_fork_result(); -impl<'a> From<&'a TopicConfig> for SubscriptionOptions<'a> { - fn from(value: &'a TopicConfig) -> Self { - PrimitiveOptions::new(&value.topic) - .qos(value.qos.clone()) - .into() - } -} + self.registry.register_message::(); + self.registry.register_message::(); + self.registry.register_message::(); + + // For cancel sender + self.registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_message::>(); -impl<'a> From<&'a TopicConfig> for PublisherOptions<'a> { - fn from(value: &'a TopicConfig) -> Self { - PrimitiveOptions::new(&value.topic) - .qos(value.qos.clone()) - .into() - } -} -impl<'a> From<&'a TopicConfig> for ClientOptions<'a> { - fn from(value: &'a TopicConfig) -> Self { - PrimitiveOptions::new(&value.topic) - .qos(value.qos.clone()) - .into() + self } } @@ -153,25 +172,25 @@ pub struct ActionClientConfig { /// The name of the action that this client will send requests to pub action: Arc, /// The quality of service profile for the goal service - pub goal_service_qos: QoSProfile, + pub goal_service_qos: QosOptions, /// The quality of service profile for the result service - pub result_service_qos: QoSProfile, + pub result_service_qos: QosOptions, /// The quality of service profile for the cancel service - pub cancel_service_qos: QoSProfile, + pub cancel_service_qos: QosOptions, /// The quality of service profile for the feedback topic - pub feedback_topic_qos: QoSProfile, + pub feedback_topic_qos: QosOptions, /// The quality of service profile for the status topic - pub status_topic_qos: QoSProfile, + pub status_topic_qos: QosOptions, } impl<'a> From<&'a ActionClientConfig> for ActionClientOptions<'a> { fn from(value: &'a ActionClientConfig) -> Self { let mut options = ActionClientOptions::new(&value.action); - options.goal_service_qos = value.goal_service_qos.clone(); - options.result_service_qos = value.result_service_qos.clone(); - options.cancel_service_qos = value.cancel_service_qos.clone(); - options.feedback_topic_qos = value.feedback_topic_qos.clone(); - options.status_topic_qos = value.status_topic_qos.clone(); + value.goal_service_qos.apply_to(&mut options.goal_service_qos); + value.result_service_qos.apply_to(&mut options.result_service_qos); + value.cancel_service_qos.apply_to(&mut options.cancel_service_qos); + value.feedback_topic_qos.apply_to(&mut options.feedback_topic_qos); + value.status_topic_qos.apply_to(&mut options.status_topic_qos); options } } diff --git a/src/lib.rs b/src/lib.rs index 91e44a80..aa7e3ae5 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -420,11 +420,11 @@ pub mod prelude { ImpulseAppPlugin, ImpulsePlugin, }; - pub use bevy_ecs::prelude::In; + pub use bevy_ecs::prelude::{In, World}; #[cfg(feature = "diagram")] pub use crate::{ - buffer::{JsonBuffer, JsonBufferKey, JsonBufferMut, JsonBufferWorldAccess, JsonMessage}, + buffer::{JsonBuffer, JsonBufferKey, JsonBufferMut, JsonBufferView, JsonBufferWorldAccess, JsonMessage}, diagram::{Diagram, DiagramElementRegistry, DiagramError, NodeBuilderOptions, Section}, }; diff --git a/src/ros2.rs b/src/ros2.rs index aca58136..aa726415 100644 --- a/src/ros2.rs +++ b/src/ros2.rs @@ -70,7 +70,7 @@ pub struct ActionResult { pub result: R, } -#[derive(Debug, Clone, Serialize, Deserialize)] +#[derive(Debug, Clone, Serialize, Deserialize, JsonSchema)] pub struct ActionCancellation { pub signal: CancelSignal, pub response: CancelResponse, @@ -119,7 +119,7 @@ impl<'w, 's, 'a> BuildRos2 for Builder<'w, 's, 'a> { CancelSignal: 'static + Send + Sync { let SubscriptionOptions { topic, qos, .. } = options.into(); - let topic = topic.to_owned(); + let topic: Arc = topic.into(); self.create_map(move |input: AsyncMap<(), SubscriptionStreams>| { let topic = topic.clone(); let qos = qos.clone(); From 14f09a9cfffb77f1839129a1e5af5adc444ef0ca Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Sat, 11 Oct 2025 22:39:08 +0800 Subject: [PATCH 07/11] Refactor nav_example into catalog Signed-off-by: Michael X. Grey --- examples/ros2/src/lib.rs | 19 +++ examples/ros2/src/nav_example.rs | 152 +---------------------- examples/ros2/src/nav_ops_catalog.rs | 172 +++++++++++++++++++++++++++ 3 files changed, 195 insertions(+), 148 deletions(-) create mode 100644 examples/ros2/src/lib.rs create mode 100644 examples/ros2/src/nav_ops_catalog.rs diff --git a/examples/ros2/src/lib.rs b/examples/ros2/src/lib.rs new file mode 100644 index 00000000..6ae0354b --- /dev/null +++ b/examples/ros2/src/lib.rs @@ -0,0 +1,19 @@ +/* + * Copyright (C) 2025 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +mod nav_ops_catalog; +pub use nav_ops_catalog::register_nav_catalog; diff --git a/examples/ros2/src/nav_example.rs b/examples/ros2/src/nav_example.rs index c1742ca8..0d7137db 100644 --- a/examples/ros2/src/nav_example.rs +++ b/examples/ros2/src/nav_example.rs @@ -15,22 +15,13 @@ * */ -use rclrs::{*, Promise}; +use ros2_workflow_examples::register_nav_catalog; + +use rclrs::*; use bevy_impulse::prelude::*; -use serde::{Serialize, Deserialize}; use serde_json::json; use bevy_app::ScheduleRunnerPlugin; use bevy_core::{FrameCountPlugin, TaskPoolPlugin, TypeRegistrationPlugin}; -use schemars::JsonSchema; - -use std::collections::VecDeque; - -use nav_msgs::{ - msg::{Goals, Path}, - srv::{GetPlan, GetPlan_Request, GetPlan_Response}, -}; - -use std_msgs::msg::Empty as EmptyMsg; fn main() { let context = Context::default_from_env().unwrap(); @@ -41,116 +32,7 @@ fn main() { let mut registry = DiagramElementRegistry::new(); let node = executor.create_node("nav_manager").unwrap(); - registry - .enable_ros2(node.clone()) - .register_ros2_message::() - .register_ros2_message::() - .register_ros2_message::() - .register_ros2_service::(); - - // Create a client that fetches plans from a server. Each pair of - // consecutive goals is planned for independently, in parallel. - // - // After issuing every plan request, we will await them in order of first to - // last and stream them out from the node in that order, regardless of the - // order in which the plans arrive from the service. - // - // We make a custom node builder for this instead of using the generic service - // client builder because we want the input to be processed in a specific way: - // breaking it into multiple parallel requests and reassembling them in order - // as they complete. In the future we might introduce generalized "enumerate" - // and "collect" operations which could replace this. - registry - .register_node_builder( - NodeBuilderOptions::new("fetch_plans"), - { - let node = node.clone(); - move |builder, config: PlanningConfig| { - let tolerance = config.tolerance; - let client = node.create_client::(&config.planner_service).unwrap(); - - let logger = node.logger().clone(); - builder.create_map(move |input: AsyncMap| { - let client = client.clone(); - let logger = logger.clone(); - async move { - log!(&logger, "Waiting for planning service..."); - client.notify_on_service_ready().await.unwrap(); - - let mut from_iter = input.request.goals.iter(); - let mut to_iter = input.request.goals.iter().skip(1); - - let mut plan_promises = VecDeque::new(); - while let (Some(start), Some(goal)) = (from_iter.next().cloned(), to_iter.next().cloned()) { - log!(&logger, "Requesting a plan from {start:?} to {goal:?}"); - let request = GetPlan_Request { start, goal, tolerance }; - let promise: Promise = client.call(request).unwrap(); - plan_promises.push_back(promise); - } - - while let Some(promise) = plan_promises.pop_front() { - let response = promise.await.unwrap(); - log!( - &logger, - "Received a plan from {:?} to {:?}", - response.plan.poses.first().map(|x| x.pose.clone()), - response.plan.poses.last().map(|x| x.pose.clone()), - ); - input.streams.paths.send(response.plan); - } - } - }) - } - } - ); - - // We can't really execute the paths in this example program, so let's just - // print whatever accumulates in the buffer. - registry - .opt_out() - .no_serializing() - .no_deserializing() - .register_node_builder( - NodeBuilderOptions::new("print_from_buffer"), - move |builder, msg: Option| { - let callback = move |In(key): In, world: &World| { - let buffer = world.json_buffer_view(&key).unwrap(); - let values: Result, _> = buffer.iter().collect(); - let values = values.unwrap(); - println!("{}{values:#?}", msg.as_ref().unwrap_or(&String::new())); - }; - - builder.create_node(callback.into_blocking_callback()) - } - ) - .with_listen(); - - registry.register_node_builder( - NodeBuilderOptions::new("print"), - move |builder, PrintConfig { message, include_value }: PrintConfig| { - builder.create_map_block(move |value: JsonMessage| { - if include_value { - println!("{message}{value:#?}"); - } else { - println!("{message}"); - } - value - }) - } - ); - - let clear_paths = app.world.spawn_service(clear_paths.into_blocking_service()); - registry - .opt_out() - .no_serializing() - .no_deserializing() - .register_node_builder( - NodeBuilderOptions::new("clear_paths"), - move |builder, _config: ()| { - builder.create_node(clear_paths) - } - ) - .with_buffer_access(); + register_nav_catalog(&mut registry, &node); let request_goal_topic = "request_goal"; let diagram = Diagram::from_json(json!({ @@ -266,29 +148,3 @@ fn main() { std::thread::spawn(move || executor.spin(SpinOptions::default())); app.run() } - -#[derive(Serialize, Deserialize, JsonSchema)] -struct PlanningConfig { - planner_service: String, - tolerance: f32, -} - -#[derive(StreamPack)] -struct PathStream { - paths: Path, -} - -fn clear_paths( - In((_, key)): In<((), BufferKey)>, - mut access: BufferAccessMut, -) { - let mut buffer = access.get_mut(&key).unwrap(); - // Remove all goals from the buffer by draining its full range. - buffer.drain(..); -} - -#[derive(Serialize, Deserialize, JsonSchema)] -struct PrintConfig { - message: String, - include_value: bool, -} diff --git a/examples/ros2/src/nav_ops_catalog.rs b/examples/ros2/src/nav_ops_catalog.rs new file mode 100644 index 00000000..2878a177 --- /dev/null +++ b/examples/ros2/src/nav_ops_catalog.rs @@ -0,0 +1,172 @@ +/* + * Copyright (C) 2025 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +use rclrs::{*, Promise, Node as Ros2Node}; +use bevy_impulse::prelude::*; +use serde::{Serialize, Deserialize}; +use schemars::JsonSchema; + +use std::collections::VecDeque; + +use nav_msgs::{ + msg::{Goals, Path}, + srv::{GetPlan, GetPlan_Request, GetPlan_Response}, +}; + +use std_msgs::msg::Empty as EmptyMsg; + +pub fn register_nav_catalog( + registry: &mut DiagramElementRegistry, + node: &Ros2Node, +) { + registry + .enable_ros2(node.clone()) + .register_ros2_message::() + .register_ros2_message::() + .register_ros2_message::() + .register_ros2_service::(); + + // Create a client that fetches plans from a server. Each pair of + // consecutive goals is planned for independently, in parallel. + // + // After issuing every plan request, we will await them in order of first to + // last and stream them out from the node in that order, regardless of the + // order in which the plans arrive from the service. + // + // We make a custom node builder for this instead of using the generic service + // client builder because we want the input to be processed in a specific way: + // breaking it into multiple parallel requests and reassembling them in order + // as they complete. In the future we might introduce generalized "enumerate" + // and "collect" operations which could replace this. + registry + .register_node_builder( + NodeBuilderOptions::new("fetch_plans"), + { + let node = node.clone(); + move |builder, config: PlanningConfig| { + let tolerance = config.tolerance; + let client = node.create_client::(&config.planner_service).unwrap(); + + let logger = node.logger().clone(); + builder.create_map(move |input: AsyncMap| { + let client = client.clone(); + let logger = logger.clone(); + async move { + log!(&logger, "Waiting for planning service..."); + client.notify_on_service_ready().await.unwrap(); + + let mut from_iter = input.request.goals.iter(); + let mut to_iter = input.request.goals.iter().skip(1); + + let mut plan_promises = VecDeque::new(); + while let (Some(start), Some(goal)) = (from_iter.next().cloned(), to_iter.next().cloned()) { + log!(&logger, "Requesting a plan from {start:?} to {goal:?}"); + let request = GetPlan_Request { start, goal, tolerance }; + let promise: Promise = client.call(request).unwrap(); + plan_promises.push_back(promise); + } + + while let Some(promise) = plan_promises.pop_front() { + let response = promise.await.unwrap(); + log!( + &logger, + "Received a plan from {:?} to {:?}", + response.plan.poses.first().map(|x| x.pose.clone()), + response.plan.poses.last().map(|x| x.pose.clone()), + ); + input.streams.paths.send(response.plan); + } + } + }) + } + } + ); + + // We can't really execute the paths in this example program, so let's just + // print whatever accumulates in the buffer. + registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_node_builder( + NodeBuilderOptions::new("print_from_buffer"), + move |builder, msg: Option| { + let callback = move |In(key): In, world: &World| { + let buffer = world.json_buffer_view(&key).unwrap(); + let values: Result, _> = buffer.iter().collect(); + let values = values.unwrap(); + println!("{}{values:#?}", msg.as_ref().unwrap_or(&String::new())); + }; + + builder.create_node(callback.into_blocking_callback()) + } + ) + .with_listen(); + + registry.register_node_builder( + NodeBuilderOptions::new("print"), + move |builder, PrintConfig { message, include_value }: PrintConfig| { + builder.create_map_block(move |value: JsonMessage| { + if include_value { + println!("{message}{value:#?}"); + } else { + println!("{message}"); + } + value + }) + } + ); + + registry + .opt_out() + .no_serializing() + .no_deserializing() + .register_node_builder( + NodeBuilderOptions::new("clear_paths"), + move |builder, _config: ()| { + let clear_paths = clear_paths.into_blocking_callback(); + builder.create_node(clear_paths) + } + ) + .with_buffer_access(); +} + +#[derive(Serialize, Deserialize, JsonSchema)] +struct PlanningConfig { + planner_service: String, + tolerance: f32, +} + +#[derive(StreamPack)] +struct PathStream { + paths: Path, +} + +fn clear_paths( + In((_, key)): In<((), BufferKey)>, + mut access: BufferAccessMut, +) { + let mut buffer = access.get_mut(&key).unwrap(); + // Remove all goals from the buffer by draining its full range. + buffer.drain(..); +} + +#[derive(Serialize, Deserialize, JsonSchema)] +struct PrintConfig { + message: String, + include_value: bool, +} From 3adda2693550782a67039e6040a721d1b5b3c4eb Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Sun, 12 Oct 2025 00:11:33 +0800 Subject: [PATCH 08/11] Enable diagram editing for nav example Signed-off-by: Michael X. Grey --- diagram-editor/server/api/error_responses.rs | 2 +- examples/ros2/Cargo.toml | 9 +- examples/ros2/README.md | 26 ++- .../ros2/diagrams/default-nav-system.json | 136 ++++++++++++++++ examples/ros2/src/nav_example.rs | 150 ------------------ examples/ros2/src/nav_executor.rs | 140 ++++++++++++++++ examples/ros2/src/nav_ops_catalog.rs | 5 +- package.xml | 1 + src/diagram/ros2.rs | 20 +-- 9 files changed, 323 insertions(+), 166 deletions(-) create mode 100644 examples/ros2/diagrams/default-nav-system.json delete mode 100644 examples/ros2/src/nav_example.rs create mode 100644 examples/ros2/src/nav_executor.rs diff --git a/diagram-editor/server/api/error_responses.rs b/diagram-editor/server/api/error_responses.rs index a0911b3c..e56441ce 100644 --- a/diagram-editor/server/api/error_responses.rs +++ b/diagram-editor/server/api/error_responses.rs @@ -2,7 +2,7 @@ use axum::{ http::StatusCode, response::{IntoResponse, Response}, }; -use bevy_impulse::{Cancellation, CancellationCause}; +use bevy_impulse::Cancellation; pub(super) struct WorkflowCancelledResponse<'a>(pub(super) &'a Cancellation); diff --git a/examples/ros2/Cargo.toml b/examples/ros2/Cargo.toml index 229691ae..18492af6 100644 --- a/examples/ros2/Cargo.toml +++ b/examples/ros2/Cargo.toml @@ -4,8 +4,8 @@ edition = "2021" version = "0.0.1" [[bin]] -name = "nav-example" -path = "src/nav_example.rs" +name = "nav-executor" +path = "src/nav_executor.rs" [[bin]] name = "fake-plan-generator" @@ -16,17 +16,22 @@ name = "goal-requester" path = "src/goal_requester.rs" [dependencies] +axum = "0.8.4" bevy_app = "0.12" bevy_core = "0.12" bevy_impulse = { path = "../..", features = ["diagram", "ros2"] } +bevy_impulse_diagram_editor = { version = "0.0.1", path = "../../diagram-editor" } serde = { workspace = true } schemars = { workspace = true } serde_json = { workspace = true } clap = { version = "*", features = ["derive"] } rand = "*" +tracing-subscriber = "0.3.19" +tokio = { version = "1.45.1", features = ["macros", "rt-multi-thread"] } rclrs = { workspace = true } nav_msgs = { version = "*", features = ["serde", "schemars"] } geometry_msgs = { version = "*", features = ["serde", "schemars"] } std_msgs = { version = "*", features = ["serde", "schemars"] } builtin_interfaces = { version = "*", features = ["serde", "schemars"] } +example_interfaces = { version = "*", features = ["serde", "schemars"] } diff --git a/examples/ros2/README.md b/examples/ros2/README.md index 5177b3e3..3d803f2b 100644 --- a/examples/ros2/README.md +++ b/examples/ros2/README.md @@ -2,7 +2,7 @@ The examples in this directory showcase how to incorporate ROS primitives into a workflow. We model a small portion of a navigation workflow that involves receiving goals, fetching paths to connect those goals from a planning service, and then queuing up the paths for execution. -This diagram represents the workflow implemented by `src/nav_example.rs`: +This diagram represents the workflow implemented by [`diagrams/default-nav-system.json`](diagrams/default-nav-system.json): ![nav-example-workflow](assets/figures/nav-example.png) @@ -17,7 +17,7 @@ source install/setup.bash # run in the root of your colcon workspace 2. Then you can go into this `examples/ros2` directory and run the example with ```bash -cargo run --bin nav-example # run in this directory +cargo run --bin nav-executor -- run # run in this directory ``` 3. The `nav-example` workflow will wait until it receives some goals to process. You can send it some randomized goals by **opening a new terminal** in the same directory and running @@ -46,3 +46,25 @@ Paths currently waiting to run: ``` which indicates that the buffer has been successfully cleared out. + +5. You can view and edit the navigation workflow by running the web-based editor: + +```bash +cargo run --bin nav-executor -- serve # run in this directory +``` + +Open up a web browser (chrome works best) and go to [http://localhost:3000](http://localhost:3000). Use the upload button to load the default nav workflow from [`diagrams/default-nav-system.json`](diagrams/default-nav-system.json). After you've edited it, you can run it immediately using the play button (enter `null` into the input box that pops up). Or you can use the export button to download and save your changes. + +6. The diagram editor does not currently have a button for cancelling a workflow. To stop a workflow that is currently running, use + +```bash +ros2 topic pub end_workflow std_msgs/Empty +``` + +The default workflow will listen to the `/end_workflow` topic for any message, and then exit as soon as one is received. After you have triggerd the workflow to end, you should this message in the response: + +``` +"workflow ended by /end_workflow request" +``` + +7. To see how to register custom diagram operations and any ROS messages, services, or actions that you need, take a look at [`src/nav_ops_catalog.rs`](src/nav_ops_catalog.rs). diff --git a/examples/ros2/diagrams/default-nav-system.json b/examples/ros2/diagrams/default-nav-system.json new file mode 100644 index 00000000..00c4db84 --- /dev/null +++ b/examples/ros2/diagrams/default-nav-system.json @@ -0,0 +1,136 @@ +{ + "$schema": "https://raw.githubusercontent.com/open-rmf/bevy_impulse/refs/heads/main/diagram.schema.json", + "version": "0.1.0", + "templates": {}, + "start": "setup", + "ops": { + "quit_request": { + "type": "transform", + "cel": "\"workflow ended by /end_workflow request\"", + "next": { + "builtin": "terminate" + } + }, + "end_workflow": { + "type": "node", + "builder": "nav_manager__std_msgs_msg_Empty__subscription", + "next": { + "builtin": "dispose" + }, + "display_text": "End Workflow", + "config": { + "topic": "end_workflow" + }, + "stream_out": { + "out": "quit_request" + } + }, + "setup": { + "type": "fork_clone", + "next": [ + "print_welcome", + "receive_cancel", + "end_workflow" + ] + }, + "print_welcome": { + "type": "node", + "builder": "print", + "config": { + "message": "Waiting to receive goals from 'request_goal' topic", + "include_value": false + }, + "next": "receive_goals" + }, + "receive_goals": { + "type": "node", + "builder": "nav_manager__nav_msgs_msg_Goals__subscription", + "config": { + "topic": "request_goal" + }, + "next": "quit_error", + "display_text": "Receive Goals", + "stream_out": { + "out": "fetch_plans" + } + }, + "quit_error": { + "type": "transform", + "cel": "\"error: unable to receive goals\"", + "next": { + "builtin": "terminate" + } + }, + "fetch_plans": { + "type": "node", + "builder": "fetch_plans", + "config": { + "planner_service": "get_plan", + "tolerance": 0.1 + }, + "next": { + "builtin": "dispose" + }, + "display_text": "Fetch Plans", + "stream_out": { + "paths": "path_buffer" + } + }, + "path_buffer": { + "type": "buffer", + "settings": { + "retention": "keep_all" + } + }, + "listen_to_path_buffer": { + "type": "listen", + "buffers": [ + "path_buffer" + ], + "next": "print_paths" + }, + "print_paths": { + "type": "node", + "builder": "print_from_buffer", + "config": "Paths currently waiting to run:\n", + "next": { + "builtin": "dispose" + }, + "display_text": "Print Paths" + }, + "receive_cancel": { + "type": "node", + "builder": "nav_manager__std_msgs_msg_Empty__subscription", + "config": { + "topic": "cancel_goals" + }, + "next": { + "builtin": "dispose" + }, + "display_text": "Cancel Goals", + "stream_out": { + "out": "trigger_clear_paths" + } + }, + "trigger_clear_paths": { + "type": "transform", + "cel": "null", + "next": "access_paths" + }, + "access_paths": { + "type": "buffer_access", + "buffers": [ + "path_buffer" + ], + "next": "clear_paths" + }, + "clear_paths": { + "type": "node", + "builder": "clear_paths", + "next": { + "builtin": "dispose" + }, + "display_text": "Clear Paths" + } + } +} \ No newline at end of file diff --git a/examples/ros2/src/nav_example.rs b/examples/ros2/src/nav_example.rs deleted file mode 100644 index 0d7137db..00000000 --- a/examples/ros2/src/nav_example.rs +++ /dev/null @@ -1,150 +0,0 @@ -/* - * Copyright (C) 2025 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * -*/ - -use ros2_workflow_examples::register_nav_catalog; - -use rclrs::*; -use bevy_impulse::prelude::*; -use serde_json::json; -use bevy_app::ScheduleRunnerPlugin; -use bevy_core::{FrameCountPlugin, TaskPoolPlugin, TypeRegistrationPlugin}; - -fn main() { - let context = Context::default_from_env().unwrap(); - let mut executor = context.create_basic_executor(); - - let mut app = bevy_app::App::new(); - - let mut registry = DiagramElementRegistry::new(); - let node = executor.create_node("nav_manager").unwrap(); - - register_nav_catalog(&mut registry, &node); - - let request_goal_topic = "request_goal"; - let diagram = Diagram::from_json(json!({ - "version": "0.1.0", - "start": "setup", - "ops": { - "setup": { - "type": "fork_clone", - "next": [ - "print_welcome", - "receive_cancel" - ] - }, - "print_welcome": { - "type": "node", - "builder": "print", - "config": { - "message": format!("Waiting to receive goals from {request_goal_topic}"), - "include_value": false - }, - "next": "receive_goals" - }, - "receive_goals": { - "type": "node", - "builder": "nav_manager__nav_msgs_msg_Goals__subscription", - "config": { - "topic": format!("{request_goal_topic}"), - }, - "stream_out": { - "out": "fetch_plans" - }, - "next": "quit" - }, - "quit": { - "type": "transform", - "cel": "null", - "next": { "builtin": "terminate" } - }, - "fetch_plans": { - "type": "node", - "builder": "fetch_plans", - "config": { - "planner_service": "get_plan", - "tolerance": 0.1 - }, - "stream_out": { - "paths": "path_buffer" - }, - "next": { "builtin": "dispose" } - }, - "path_buffer": { - "type": "buffer", - "settings": { "retention": "keep_all" } - }, - "listen_to_path_buffer": { - "type": "listen", - "buffers": ["path_buffer"], - "next": "print_paths", - }, - "print_paths": { - "type": "node", - "builder": "print_from_buffer", - "config": "Paths currently waiting to run:\n", - "next": { "builtin": "dispose" } - }, - "receive_cancel": { - "type": "node", - "builder": "nav_manager__std_msgs_msg_Empty__subscription", - "config": { - "topic": "cancel_goals" - }, - "stream_out": { - "out": "trigger_clear_paths" - }, - "next": { "builtin": "dispose" } - }, - "trigger_clear_paths": { - "type": "transform", - "cel": "null", - "next": "access_paths" - }, - "access_paths": { - "type": "buffer_access", - "buffers": ["path_buffer"], - "next": "clear_paths" - }, - "clear_paths": { - "type": "node", - "builder": "clear_paths", - "next": { "builtin": "dispose" } - } - } - })) - .unwrap(); - - app.world.command(|commands| { - // Generate the workflow from the diagram. - let workflow = diagram.spawn_io_workflow::<_, ()>(commands, ®istry).unwrap(); - - // Get the workflow running. - let _ = commands.request((), workflow).detach(); - }); - - app.add_plugins(( - TaskPoolPlugin::default(), - TypeRegistrationPlugin, - FrameCountPlugin, - ScheduleRunnerPlugin::default(), - ImpulsePlugin::default(), - )); - - log!(&*node, "Beginning workflow..."); - std::thread::spawn(move || executor.spin(SpinOptions::default())); - app.run() -} diff --git a/examples/ros2/src/nav_executor.rs b/examples/ros2/src/nav_executor.rs new file mode 100644 index 00000000..57b73ed1 --- /dev/null +++ b/examples/ros2/src/nav_executor.rs @@ -0,0 +1,140 @@ +/* + * Copyright (C) 2025 Open Source Robotics Foundation + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * +*/ + +use ros2_workflow_examples::register_nav_catalog; + +use rclrs::*; +use bevy_impulse::prelude::*; +use bevy_impulse_diagram_editor::{new_router, ServerOptions}; +use bevy_app::ScheduleRunnerPlugin; +use bevy_core::{FrameCountPlugin, TaskPoolPlugin, TypeRegistrationPlugin}; +use clap::Parser; +use std::{error::Error, fs::File}; + +#[derive(Parser, Debug)] +#[clap( + name = "nav-executor", + version = "0.1.0", + about = "Example navigation execution system." +)] +struct Args { + #[clap(subcommand)] + command: Commands, +} + +#[derive(Parser, Debug)] +enum Commands { + /// Immediately run a nav exeuction diagram + Run(RunArgs), + + /// Starts a server to edit and run diagrams + Serve(ServeArgs), +} + +#[derive(Parser, Debug)] +struct RunArgs { + /// Path to the diagram to run. + /// + /// If not provided, we will run the default example. + diagram: Option, +} + +#[derive(Parser, Debug)] +struct ServeArgs { + /// What port to serve the diagram editor on + #[arg(short, long, default_value_t = 3000)] + port: u16, +} + +fn run(args: RunArgs, registry: DiagramElementRegistry) -> Result<(), Box> { + let mut app = bevy_app::App::new(); + + let diagram = if let Some(file) = args.diagram { + Diagram::from_reader(File::open(file).unwrap()).unwrap() + } else { + Diagram::from_json_str(include_str!("../diagrams/default-nav-system.json")).unwrap() + }; + + let mut promise = app.world.command(|commands| { + // Generate the workflow from the diagram. + let workflow = diagram.spawn_io_workflow::<_, String>(commands, ®istry).unwrap(); + + // Get the workflow running. + commands.request((), workflow).take_response() + }); + + app.add_plugins(( + TaskPoolPlugin::default(), + TypeRegistrationPlugin, + FrameCountPlugin, + ScheduleRunnerPlugin::default(), + ImpulsePlugin::default(), + )); + + log!("nav-executor", "Beginning workflow..."); + + while promise.peek().is_pending() { + app.update(); + } + + if let Some(response) = promise.take().available() { + println!("{response}"); + } + + Ok(()) +} + +async fn serve(args: ServeArgs, registry: DiagramElementRegistry) -> Result<(), Box> { + println!("Serving diagram editor at http://localhost:{}", args.port); + + let mut app = bevy_app::App::new(); + app.add_plugins(ImpulseAppPlugin::default()); + let router = new_router(&mut app, registry, ServerOptions::default()); + std::thread::spawn(move || app.run()); + let listener = tokio::net::TcpListener::bind(("localhost", args.port)) + .await + .unwrap(); + axum::serve(listener, router).await?; + Ok(()) +} + +#[tokio::main(flavor = "current_thread")] +async fn main() -> Result<(), Box> { + let args = Args::parse(); + + let context = Context::default_from_env().unwrap(); + let mut executor = context.create_basic_executor(); + + // Set up the registry and get rclrs executor running + let mut registry = DiagramElementRegistry::new(); + let node = executor.create_node("nav_manager").unwrap(); + let executor_commands = executor.commands().clone(); + register_nav_catalog(&mut registry, &node); + let executor_thread = std::thread::spawn(move || executor.spin(SpinOptions::default())); + + tracing_subscriber::fmt::init(); + + let r = match args.command { + Commands::Run(args) => run(args, registry), + Commands::Serve(args) => serve(args, registry).await, + }; + + executor_commands.halt_spinning(); + let _ = executor_thread.join(); + + r +} diff --git a/examples/ros2/src/nav_ops_catalog.rs b/examples/ros2/src/nav_ops_catalog.rs index 2878a177..e2655b18 100644 --- a/examples/ros2/src/nav_ops_catalog.rs +++ b/examples/ros2/src/nav_ops_catalog.rs @@ -27,6 +27,8 @@ use nav_msgs::{ srv::{GetPlan, GetPlan_Request, GetPlan_Response}, }; +use example_interfaces::action::Fibonacci; + use std_msgs::msg::Empty as EmptyMsg; pub fn register_nav_catalog( @@ -38,7 +40,8 @@ pub fn register_nav_catalog( .register_ros2_message::() .register_ros2_message::() .register_ros2_message::() - .register_ros2_service::(); + .register_ros2_service::() + .register_ros2_action::(); // Create a client that fetches plans from a server. Each pair of // consecutive goals is planned for independently, in parallel. diff --git a/package.xml b/package.xml index 82faed47..cbb37626 100644 --- a/package.xml +++ b/package.xml @@ -18,6 +18,7 @@ geometry_msgs nav_msgs std_msgs + example_interfaces ament_cargo diff --git a/src/diagram/ros2.rs b/src/diagram/ros2.rs index a7128977..383ef9a7 100644 --- a/src/diagram/ros2.rs +++ b/src/diagram/ros2.rs @@ -54,13 +54,13 @@ impl<'a> Ros2Registry<'a> { /// subscriptions for this message type. pub fn register_ros2_message(&mut self) -> &'_ mut Self { let node_name_snake = self.ros2_node.name().replace("/", "_"); - let message_name = T::TYPE_NAME; - let message_name_snake = message_name.replace("/", "_"); + let message_name_minimal = T::TYPE_NAME.split("/").last().unwrap_or(""); + let message_name_snake = T::TYPE_NAME.replace("/", "_"); let ros2_node = self.ros2_node.clone(); self.registry.register_node_builder( NodeBuilderOptions::new(format!("{node_name_snake}__{message_name_snake}__subscription")) - .with_default_display_text(format!("{message_name} Subscription")), + .with_default_display_text(format!("{message_name_minimal} Subscription")), move |builder, config: PrimitiveOptions| { builder.create_ros2_subscription::(ros2_node.clone(), config) } @@ -77,7 +77,7 @@ impl<'a> Ros2Registry<'a> { let ros2_node = self.ros2_node.clone(); self.registry.register_node_builder_fallible( NodeBuilderOptions::new(format!("{node_name_snake}__{message_name_snake}__publisher")) - .with_default_display_text(format!("{message_name} Publisher", )), + .with_default_display_text(format!("{message_name_minimal} Publisher", )), move |builder, config: PrimitiveOptions| { let node = builder.create_ros2_publisher::(ros2_node.clone(), config)?; Ok(node) @@ -96,13 +96,13 @@ impl<'a> Ros2Registry<'a> { S::Response: Serialize + DeserializeOwned + JsonSchema, { let node_name_snake = self.ros2_node.name().replace("/", "_"); - let service_name = S::TYPE_NAME; - let service_name_snake = service_name.replace("/", "_"); + let service_name_minimal = S::TYPE_NAME.split("/").last().unwrap_or(""); + let service_name_snake = S::TYPE_NAME.replace("/", "_"); let ros2_node = self.ros2_node.clone(); self.registry.register_node_builder_fallible( NodeBuilderOptions::new(format!("{node_name_snake}__{service_name_snake}__client")) - .with_default_display_text(format!("{service_name} Client")), + .with_default_display_text(format!("{service_name_minimal} Client")), move |builder, config: PrimitiveOptions| { let node = builder.create_ros2_service_client::(ros2_node.clone(), config)?; Ok(node) @@ -133,13 +133,13 @@ impl<'a> Ros2Registry<'a> { A::Feedback: Serialize + DeserializeOwned + JsonSchema, { let node_name_snake = self.ros2_node.name().replace("/", "_"); - let action_name = A::TYPE_NAME; - let action_name_snake = action_name.replace("/", "_"); + let action_name_minimal = A::TYPE_NAME.split("/").last().unwrap_or(""); + let action_name_snake = A::TYPE_NAME.replace("/", "_"); let ros2_node = self.ros2_node.clone(); self.registry.register_node_builder_fallible( NodeBuilderOptions::new(format!("{node_name_snake}__{action_name_snake}__client")) - .with_default_display_text(format!("{action_name} Client")), + .with_default_display_text(format!("{action_name_minimal} Client")), move |builder, config: ActionClientConfig| { let node = builder.create_ros2_action_client::(ros2_node.clone(), &config)?; Ok(node) From 326904a8a20bd957b96d0aabd35b19c7ac51f617 Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Sun, 12 Oct 2025 16:28:40 +0800 Subject: [PATCH 09/11] Simplify nav-executor example Signed-off-by: Michael X. Grey --- diagram-editor/server/basic_executor.rs | 6 +- examples/ros2/Cargo.toml | 21 +++-- examples/ros2/README.md | 2 +- examples/ros2/src/nav_executor.rs | 120 +++--------------------- 4 files changed, 26 insertions(+), 123 deletions(-) diff --git a/diagram-editor/server/basic_executor.rs b/diagram-editor/server/basic_executor.rs index 6c5b358d..ee9c8fe7 100644 --- a/diagram-editor/server/basic_executor.rs +++ b/diagram-editor/server/basic_executor.rs @@ -56,8 +56,8 @@ pub struct RunArgs { #[arg(help = "path to the diagram to run")] diagram: String, - #[arg(help = "json containing the request to the diagram")] - request: String, + #[arg(help = "json containing the request to the diagram. Defaults to null if not set.")] + request: Option, } #[derive(Parser, Debug)] @@ -72,7 +72,7 @@ pub fn headless(args: RunArgs, registry: DiagramElementRegistry) -> Result<(), B let file = File::open(args.diagram).unwrap(); let diagram = Diagram::from_reader(file)?; - let request = serde_json::Value::from_str(&args.request)?; + let request = serde_json::Value::from_str(args.request.as_ref().map(|s| s.as_str()).unwrap_or("null"))?; let mut promise = app.world .command(|cmds| -> Result, DiagramError> { diff --git a/examples/ros2/Cargo.toml b/examples/ros2/Cargo.toml index 18492af6..d305b25b 100644 --- a/examples/ros2/Cargo.toml +++ b/examples/ros2/Cargo.toml @@ -16,22 +16,23 @@ name = "goal-requester" path = "src/goal_requester.rs" [dependencies] -axum = "0.8.4" -bevy_app = "0.12" -bevy_core = "0.12" -bevy_impulse = { path = "../..", features = ["diagram", "ros2"] } -bevy_impulse_diagram_editor = { version = "0.0.1", path = "../../diagram-editor" } +# Dependency to help us run the diagram editor and executor +bevy_impulse_diagram_editor = { version = "0.0.1", path = "../../diagram-editor", features = ["basic_executor"] } + +# Dependencies for the nav operation catalog +bevy_impulse = { version = "0.0.2", path = "../..", features = ["diagram", "ros2"] } serde = { workspace = true } -schemars = { workspace = true } serde_json = { workspace = true } -clap = { version = "*", features = ["derive"] } -rand = "*" -tracing-subscriber = "0.3.19" -tokio = { version = "1.45.1", features = ["macros", "rt-multi-thread"] } +schemars = { workspace = true } +# Dependencies for our custom ROS operations rclrs = { workspace = true } nav_msgs = { version = "*", features = ["serde", "schemars"] } geometry_msgs = { version = "*", features = ["serde", "schemars"] } std_msgs = { version = "*", features = ["serde", "schemars"] } builtin_interfaces = { version = "*", features = ["serde", "schemars"] } example_interfaces = { version = "*", features = ["serde", "schemars"] } + +# Dependencies for goal-requester and fake-plan-generator +clap = { workspace = true } +rand = "0.9.2" diff --git a/examples/ros2/README.md b/examples/ros2/README.md index 3d803f2b..c8f2ee0a 100644 --- a/examples/ros2/README.md +++ b/examples/ros2/README.md @@ -17,7 +17,7 @@ source install/setup.bash # run in the root of your colcon workspace 2. Then you can go into this `examples/ros2` directory and run the example with ```bash -cargo run --bin nav-executor -- run # run in this directory +cargo run --bin nav-executor -- run diagrams/default-nav-system.json # run in this directory ``` 3. The `nav-example` workflow will wait until it receives some goals to process. You can send it some randomized goals by **opening a new terminal** in the same directory and running diff --git a/examples/ros2/src/nav_executor.rs b/examples/ros2/src/nav_executor.rs index 0da77150..fb151ebd 100644 --- a/examples/ros2/src/nav_executor.rs +++ b/examples/ros2/src/nav_executor.rs @@ -16,125 +16,27 @@ */ use ros2_workflow_examples::register_nav_catalog; - -use bevy_app::ScheduleRunnerPlugin; -use bevy_core::{FrameCountPlugin, TaskPoolPlugin, TypeRegistrationPlugin}; -use bevy_impulse::prelude::*; -use bevy_impulse_diagram_editor::{new_router, ServerOptions}; -use clap::Parser; use rclrs::*; -use std::{error::Error, fs::File}; - -#[derive(Parser, Debug)] -#[clap( - name = "nav-executor", - version = "0.1.0", - about = "Example navigation execution system." -)] -struct Args { - #[clap(subcommand)] - command: Commands, -} - -#[derive(Parser, Debug)] -enum Commands { - /// Immediately run a nav exeuction diagram - Run(RunArgs), - - /// Starts a server to edit and run diagrams - Serve(ServeArgs), -} - -#[derive(Parser, Debug)] -struct RunArgs { - /// Path to the diagram to run. - /// - /// If not provided, we will run the default example. - diagram: Option, -} - -#[derive(Parser, Debug)] -struct ServeArgs { - /// What port to serve the diagram editor on - #[arg(short, long, default_value_t = 3000)] - port: u16, -} - -fn run(args: RunArgs, registry: DiagramElementRegistry) -> Result<(), Box> { - let mut app = bevy_app::App::new(); - - let diagram = if let Some(file) = args.diagram { - Diagram::from_reader(File::open(file).unwrap()).unwrap() - } else { - Diagram::from_json_str(include_str!("../diagrams/default-nav-system.json")).unwrap() - }; - - let mut promise = app.world.command(|commands| { - // Generate the workflow from the diagram. - let workflow = diagram - .spawn_io_workflow::<_, String>(commands, ®istry) - .unwrap(); - - // Get the workflow running. - commands.request((), workflow).take_response() - }); - - app.add_plugins(( - TaskPoolPlugin::default(), - TypeRegistrationPlugin, - FrameCountPlugin, - ScheduleRunnerPlugin::default(), - ImpulsePlugin::default(), - )); - - log!("nav-executor", "Beginning workflow..."); - - while promise.peek().is_pending() { - app.update(); - } - - if let Some(response) = promise.take().available() { - println!("{response}"); - } - - Ok(()) -} - -async fn serve(args: ServeArgs, registry: DiagramElementRegistry) -> Result<(), Box> { - println!("Serving diagram editor at http://localhost:{}", args.port); - - let mut app = bevy_app::App::new(); - app.add_plugins(ImpulseAppPlugin::default()); - let router = new_router(&mut app, registry, ServerOptions::default()); - std::thread::spawn(move || app.run()); - let listener = tokio::net::TcpListener::bind(("localhost", args.port)) - .await - .unwrap(); - axum::serve(listener, router).await?; - Ok(()) -} - -#[tokio::main(flavor = "current_thread")] -async fn main() -> Result<(), Box> { - let args = Args::parse(); +use bevy_impulse_diagram_editor::basic_executor::{self, DiagramElementRegistry, Error}; +fn main() -> Result<(), Box> { + // Set up the critical rclrs components let context = Context::default_from_env().unwrap(); let mut executor = context.create_basic_executor(); + let node = executor.create_node("nav_manager").unwrap(); - // Set up the registry and get rclrs executor running + // Set up the custom ROS registry and get rclrs executor running let mut registry = DiagramElementRegistry::new(); - let node = executor.create_node("nav_manager").unwrap(); - let executor_commands = executor.commands().clone(); register_nav_catalog(&mut registry, &node); - let executor_thread = std::thread::spawn(move || executor.spin(SpinOptions::default())); - tracing_subscriber::fmt::init(); + // Get the rclrs executor running its own thread + let executor_commands = executor.commands().clone(); + let executor_thread = std::thread::spawn(move || executor.spin(SpinOptions::default())); - let r = match args.command { - Commands::Run(args) => run(args, registry), - Commands::Serve(args) => serve(args, registry).await, - }; + // Run the workflow execution program with our custom registry + let r = basic_executor::run(registry); + // Close down the executor and join its thread gracefully to avoid noisy thread-crashing errors executor_commands.halt_spinning(); let _ = executor_thread.join(); From 7148b69a98d857697ef563b2aa36e83f844ac5db Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Mon, 13 Oct 2025 15:37:32 +0800 Subject: [PATCH 10/11] Remove unnecessary notice on README Signed-off-by: Michael X. Grey --- README.md | 5 ----- 1 file changed, 5 deletions(-) diff --git a/README.md b/README.md index 575a5874..ab185b0a 100644 --- a/README.md +++ b/README.md @@ -4,11 +4,6 @@ [![ci_web](https://github.com/open-rmf/bevy_impulse/actions/workflows/ci_web.yaml/badge.svg)](https://github.com/open-rmf/bevy_impulse/actions/workflows/ci_web.yaml) [![Crates.io Version](https://img.shields.io/crates/v/bevy_impulse)](https://crates.io/crates/bevy_impulse) -> [!IMPORTANT] -> For the ROS 2 integration feature, check out the [`ros2` branch](https://github.com/open-rmf/bevy_impulse/tree/ros2). -> -> That feature is kept separate for now because it requires additional non-Rust setup. It will be merged into `main` after dynamic message introspection is finished. - > [!IMPORTANT] > You are on a branch with experimental support for ROS 2 via [`rclrs`](https://github.com/ros2-rust/ros2_rust). > This will require more steps to set up than usual, so installation instructions for the necessary packages are below: From ce84cc1f7e78b935540954d742007c0c884cc3fe Mon Sep 17 00:00:00 2001 From: "Michael X. Grey" Date: Mon, 13 Oct 2025 18:18:24 +0800 Subject: [PATCH 11/11] Update nav diagram Signed-off-by: Michael X. Grey --- examples/ros2/assets/figures/nav-example.png | Bin 41822 -> 48579 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/examples/ros2/assets/figures/nav-example.png b/examples/ros2/assets/figures/nav-example.png index 1e41af96613b6e5532295cb2c9c741351e5712bb..2d249f6958c6fd265dc5d17cf360778958f16e19 100644 GIT binary patch literal 48579 zcmafaWmr^Q+x8Fx(jAf`h;&Iwg9=E8)X?C7ba$tuq;!LXG(&etw{&-RNDI8%`>F5W zxBqa!0mIsBU3JC^RZ@_`LMKB9fk0T&AKt5gK!|V<2!ZYy3h)!sbA)XW$QLC2UR>2x z?=T(Jld$_fcn0O!2c>A5ka1)}@gm3AvEtu)U0EYfoH_PuYXX(#pO<3~%np zya0hkdD(;e*Bi3y1g`>1ySZbTUZh%L^U{)kKjXR}2C8XhX1O0qEhFVluX-$_=Co~G zgzfMIwOt&Rs4YrMcnWugB`yXps|1Km|Mz#&zMrR4R~m1L(JJB&j*48SQ7iN&jhwqE zO7QeIeiUjcYY0-|lmVF?Yh|qWb zqLJcxQ8Z5(S6y3}pI95ky~JYMmiJq*3RX4eg3(n1spdLyF98=h+BlBf2q!zn{HeG0 z#meH20uEKgOVY|2WdoM+a$4X$iz^8DPA%&qn`^vVMEBEWkSl$*UkMUdSioPWoG z!~rXaD`fV7!FId#%bVaBM@osvvgY#v;d4>L;gp*2d3AcBE~N7mfrI@L4nG1L%hVbx zxkxnur>k!_t~0$kdtdThp+vv)kxh#|)$%eo+>!z}0)Apq%`vMM+P*uOF3mg{&l?Oo zUTUJ=Uu>wVNDzqIIW_2wq$H`cTDV%HkqA3|jXWD_`TVP!$c*BVh z+W321c6jG+2;=l;4ni-k3H;Z;q_=by5H+S|{SdFcWG@|lr}({1;eqap74<74-mb!{ z$4<-N3A>{3#D2Z8Ga;c)X)+P`R)YCN{_tvqvp_;*SqZcgM0(H=P_u^rXzVMpin5 zFs?;zRs#+;ovN3dC>vU;)Uz2d;Ogp+{b)GRTVK)(Mj8b~ld|@}b37y{(9+W0y0Bhv zAG!B7kyqrV#a(J{LuZaBLE+q8deAH}KZ}Jr8_}KYV5<2SPSc*zTCz>UY5WdSJ0s~& z5nsQSZn!o^_|4g#7P`IQ^?CeryXnNO;eSu%MoGtyIz4VZkuSdhF}xaezucd47MfA6 zcfX;1M+_@1`4dM#1xc+@>V3OK=a|9yf-4VFe7U5*5=xcoenTXxeNdnkz9q8h+_~Y` z!Fg%~N|LGp4rRjo;qJkCvoGc)j)H|>RegQ^68>A~?cr3ClUDM#Z`E|9_KiPiS-Vj_ ztPm&)RSxS(b?~574gB;us+l3S70Q6N2H4iKOJuP0X+dx4>3@qSq&kksa4`v6A)083 z5vTLJNXo77=`L2DMPl@f4jg5MFp;QDqD6`8w-Zox6q9kAj=^OU**vf*-kfIMwpSCo z9;~!IMG~`WVMgy{XiDk5eA{55sV~*AKU3}_HB+X0O)cQKo8~q&jc9Y;?GV=-nPD%) zKGQYy<=ly|0S>V+-pWiHLxoZ$%}i=RE%MQl%)rpnje@9f_+Jcmw0hn$4ze^R-rjUR@!0qDeS179Ev&vWXe{W7$9J&KEc2KRLP=x*IPo&o*1l zS0{5iAI`1}ZPXA`Xjd3?=pW73geUHZWI8N2*@*K_!o;Ts21NO@ao~&JF(&ms-b)b} zAc5gp9*W0A0d+VcnLg8(&xu6KZz49_Oasr60=#xS5tYG$&WH6Dz(+L=qvqAD&SnUE zysxufiX3q832<0WB`$&tIyuHyzdaY2Z!sQBAlN?B!icn^blMx=3K6=N_%6Y}^Qo-# zt@OX6;0`hOz)?M>z9MC2R8Xd>90e>>~1Nef<-6S$(>x$Pm$lpM?+FyR8~$DD3Z+RIDCaq zmuh1)P_Orp+Yp|1V6Zo@TA}U^JPD# z4;!5h-kXp~XM!MGc`+@%xKT>vPREf|J;gdq(K9h^R~u2HVTW^7;XsuNY4Nyr-?`Ae zK3dSwvG1o_KPYcgzvv`|4GLtq9w>Rffd4P}8#`@ETJo>hU$vus$@@FxIc; z>cWA_{_?y}{pNe8tio==>Nq5I293j4=NYUrjEFg`NUiu)N}cf_F{kA$$JCLa$q=a> zPzqljl4Yqp6&qzVyY= z2G{T9r>ZiJ04*VWJWrOne#&au^FrQk&NwkttH%6?(^)%@`D7o)OCYOA67{_s3UwOb zVNrkgPC`yDf+S=q8!X1=(`1PJX^Bm@v9N8X1WFr5$VgMxbSwatsatk0-mgXRAO0j$ zN(cHNVHQL&dP!IWk#*sPcsM}HX?-G2L_d$D?Kg5J-o7S)g{HHq7DhL2*IQe+-kQYl z+2~bz-rAoCfLLbq93887XDf3X+3KfTZ`Ltt(h^_R_MZcrrsC#1S9Uws@jCIdsH%QQ z$^S|>x#MG498;?mq9sJkd1oy>=Q?dU5c?V0U=A?+p&KnNYu;Y(S(xj5TsjkK29goa zG5Tn#SRz2&fP*fwMMeqV z8%+}RX}yaW6}gvlGeW>w-*PmE0(xyR z&BCLbD~Y9?CquMV`ibm>?fzr4>)FeU)yWhL7=|EKG?v!>_p`w(67m*voEb~V77BFT zbAl2UT9c5O%7A_K*2JHMogG-~H8vv58yEp5!wFYzfk8#0)^e_^-4Cf{;RZ;kNvACR z9`3&J!FFfO-am^5TAfagsh`Ao9sd_fj=?)@WBFoSXz@F8A@Zz!86qB95w~U$g(9Vm zg|+o5g%1u#u)*o+KiS)(_S9j5863e%>SN-y1|9x-<*z1Ojex>xM^s$2fSAMb6KQ|B zXDs`j#B>QXUMl{0p1G`^M!E-~IadtHH(ZKD%!$42Vnk4_4(^fp+kjoNnv3*9FtyO- z}8uuW9q1m>RtKWq+z1Y4X5%I zp9CIzJ0!C^1RR#PJr+Ga{+>`Is97`qa(ibSKKjOX)z^i8)&2gcE*uyv+zQM@jk-c! zW+qaZi1T8?#IKqkZ+ECGtrmDMbHib08{0ywYn1}*|FnB9oZ;6sK0jKz17|0F4;4MU z@sCVu2bZ4Pct!9^G1(cBAdRJ#(?Y0*Xtq zQ%F>vi{I?APJ=xo4(n5IPfyVn8O-VaH!lX<5P|{Ukr;{;qAS8+iRE!V)O4b9{h*be zNN@)UKMf>i6NDcYzk=l>!=4XauGg`L6;&05rL0U5I?c=o>!(cjI#=$p{*rP~?}N^u zJy5_Ibj681fCe<>*$j85Li*$=_aZ}U;uJ1&HT#Ll`qv+dqwJRZtzqMSKtiV#-kjGa8+&l<&=d^xlvnl)&TKotCh&8m6gwnVWJ?*#`yzYD^$IMr`NP0Whoi@g<7(Px3t9&J&Qs~D8LYTlHW>K=b zY=3U`bieYXy2t{NB@wk+TtjtTFKfBd;xuRnO(pDrDyxsJD&*c(u}9}I*Ngcf4lJNx z?%jU3r72mP`tW+Sw9}m5Kui~#@%25P^->R{TJ+2Sf%4I7^fwBqyxPTQN5>;DZ?aTdLtZ<&My86T zFC!5QjbiD$O91BPL9CQ&WeFJ(jq}i1-O5lSV|HY?VALU@SK{xyEWZJ)R2_;E_TsA6 zk&MCe*5>?;eroc4LomZTv4oqCjrV6+dr8wNJQiU<3DHA9wiRDwu>wI8;$9b<{>sS# z`oelJwKuMIowZtqs$|I1`5?Qw81aEdk*YMp>xD5W_J^6RWqQ6oeEmUQ;J60Zuf6}m z4JJZ=53~jCdfV*z;Pb7);7tQ|Q6L6Tzqed;oD0VfTQz)R6iYbCHT?Ny|NeNQAgVF) zrWKeJz8e+vzsYXd-8Nu9e|{mXn8YFOH5!zwQCv@_O}EKeja@+? zC=CoP<{tDvbjt(76f=Z=tjo9@&Kk0vGnxxcJhnYOa*^B;;?T~=&5Tl~3%V%O(CdzN zJMK?1P9>ny!XXFR3a-8^>ub_xQ`*c5MQ<4K`i>)rhNpQy5;atl4)Gk%*yUXPnfLDQ zNFlBg-hRJ!9CYF&bUAd^^X2C|8dHd@0BhqN@L%p<4sxg%S5hdFO@NSpM4kE%cqu=v zIL+vWqRet|1efU~d=kr3u#ZBh?qWF?GT`Toh~S9WYfP1mHc#?BU&5UynW1a8Cly zaYTdXE@ZI!&MUGkzETSx7;R2%3{NGxLToo?tU`5jEuy&j9P5%+`}>R}UH7j@Ib}C( z9mCD0d%0e_|2E}WpKB4ttl;SW8QeJUs%qLh{3T}KWsS+azoilX8WI2?+;-!d;950w zQ>_>NC4m#WUw;`bKf3KFX&mX(39#+$h6X$wt=m;dTWYja(V-@K_Md(8-FzW#`tA*b zDI`@3Nisx!)5js1xA6hU`XpE@uWrX+S|;%)4*@I<2rEqNsyRKL*T(bDqcz%(=GRz# zjabjN1ZB;L>M*=Uh3KKjZ15Q9kiR8q-`~(6gt-}fV}YuaPBgnYfTJDzV}8cCbtN`P z(AbUeEn`dGc%OEl=DZ8WE-LjV*gjGXj~Uo>d1>fs^()IQNm$#SG@0=rc?+VM4RiI0vg6BmdR_gjtlk(?Pnaa03=p$0D zJzDa|>!C=WW@L+<7U=8br#Y)!b=7X#6`tNbTO@8_ygR*g(SNGn@S7Ei+*!j_ zfJ0I{rW+hcI9>mEo=sOztv}pqch%GRgq#gtzw+xDGCw>(9dr&?#;85^ynRY&UCKHV zmIt_&$N#i)6+}3YZslaVVwdEQDZ&@XmIr>QR7w-y3k~Oyr5v}1p4*H&V8JI@KBwH! z=o?W(%fz7pEPl87ApL|jo@tt~3^x-7B$_Xw#>6m!K{U~53CByWn{a^*HS0r%jR_u& z=|xNbA8nFbWik^?!(W-Gr^KyKOnNs$v3gMhz;l?jwg_{-FzQ0_^q-jYZXJK@zRVsF zQn2XY`F977$B)*nF^@Nw&9Q6Tl=s-p4xY4^;h~XydM(fPL4Vw!NIU^~N{$bh3Hxg~ z$CoP7Y*D_8Cj{>0pTgl09mLPr+0H6lL%gJCRQ?GdSAUlEe0guEP(fZ^cLJ%-`d2b$ zbIWK0_ntsCec~4WJI#2gTEeE)w`=bPZyqzgHyQQaw&?V>2k=&}d*bM}9r_gjusIRK zCRRGZuu>`BPs9I73S?MK@TE~tpWOQh=7~(t^UzAVC{m6ddo1{O2F|*zL2gU)=%eY< zRF5i|#*A7NsQ*nen_AJgU*ojtV~hXfIR-q0oR80T{j#vxDZE;MUuJVx>+W(qm&pri zW>|N-#EY%NeLCtlh)NarM7_`3w9t4?o%po>rIoLl!LFvk(x+*IQB>B*b=~Htv4IB7 zaE7p;`}Rtv&oMU75CNn~4hfQ9vhRbzyujMxJyuNpB7xTMW8wvCJRFbY4rGOsTWAbFOcBL+)*qu1al6a&qq7I<*#%) zA204bq>2w%hJXGx$Hw*F!hzODL-ne9$IvLuvxLQC|3|^(@4blvweinzERLH2R;kBlW4^g-*J|gkM;YB55l7|TCMmV%KF9-fPOH=lQ^oJUn_548cqZ;RDOboe(?7Om>S zl+jit?6_*(Z6={j1w|efCYK`mJy5)INqqMf=+hTSk*j9jhejGLw z<1|98P)U4Ak->9a@71-ovEmDx>IOYYZDjw$HUjm-bO90X70O%r7TFO!_dPm1BBHJIT8KrwH5}rhM+Rdzna2oIFVS3MWm)B2HaW{lO5wA~ zaA(+aZhvX3Rjkg+BR>;CJO}P`&Ki6&`&lfjj?~<&#R!JJA9h;qTv}jL&Izo`s0Gh; z*|YS0q3rAF?pBNLJl72eK5n#8y&ow<1pf%l88&sm}aGyddFKgZ6Q|q`lH^P*D9OS+-PQeWpTD)VN zkR%D<)eX8t+(5zO`gf(W(w6T2t#|v(H5BD#i=UP2taX)3G&#Y{x93|Qi5?a?7ILL< z;`5`9ssTc&MT|?4oqhs+flk!v{_04r9RJAi`8Wsa9OcHwb&HVQTu16qEu&IC7@8q3 z#uyNp{7Rpnf1>~62#zeE1l z7ly)VQYAmblUmg;Hv2a&@|ZOL)nBJ`0TPEgxRT_$xCeAcxCLyzuG#eQR+JA*5>bx$|^((0`Cwb<;@WpB6)xzHaudJ?THL(-qn zPN8w7*Ya+TMlF~2X{>=GcBRSptNmx--(m*unC?m-1pzl>Kb@=
-R3NPZiXyZ6)ffKldK;lEeAWA`KB7mry4{cm{#09h-`xUalw1 zY1kR~@&JbN-*tCXr7W)a$U)@uDD^805XNGxAq$nCq?7?|=H*2VCtSy6=hKSk#aI97 z_3m)y6U*bphIr13ZvaogPj&4K(&)s$Ay@;62HnpM~m*>7`=|X=oZeTlANAFsscgv3V+-Ch$SHC9pj>4hR_lA z2(u^sO+Z4H=sYc=-23P9qYSQ(pYMi}xtL17#j6$e12GE>;+rC(8%RnIHS{{EGJMh9 z&(7BLJV%k4a1;_{LF8SEs(Q%kf7Yr-*S2toDp}_8FIWtJ-V>r%xpsd}FLD z)bafT%_PV)KlS+=1X!|EgZ1l7j>2HC$vHfhK0VbJ2=L}CrI&s~NUnbxcu6TrC*GFn zG^o^&i+I-GJ^qln9b|920mHlcVzK;6_(7ZjsQp>u^KTqP{ef}%r65H>#ocYH1 z5v0LN08^wE@w|z+jmG>ANQ)nhg%M=7J{J*clW{wdqo?D--|xSiS98CX+`qb<~=4zbveECg;qb{geZv^ss`q$Z4-wLX)kud~>H=I$lxF|Y+ z_7t>23z6N^5aXQ$bz#A8zb~<5?_;iHyES)ksPNcR;-(m}aeb9T@oZD*bdu6xX6KLy zCsxb0ukQFXdM$4XTG({?d6j&!OuVdqK5)**F5zl?c`1Wl2Xq+yqtphR4vrZo)n(w& z8qo>+5c6Dh6Az&@?p6nM`$uJoB{g%uBt081KH44L0R5&0jt>6UR&33<_Lo4b^sW(# zNUH85&ZDWt?`$3{L>H1v>?2z#zFP-^<(rOOAC3@k?6%M}ez}~Kn<0_-QJ-2_P_vB)xbXyn5y)}8IJRz zC9Au;+bZ?|QQF!pdYHBp20-8)Ea2E$ZnLV1DekvZZAPlC7MyD~&b}i+va#Ua5pwnS?IHLK>^b_sb`3ZY? zLaG*1R%snGW0!f8&%wj`Y9=ZXW`U}sDDH#=+{TSzAmq8nVP&tUdfWQfsF)T%Voov4 z&I)v!zgtQS`^$bb+h=abe~5RU?iC_{38pMK2tiWS$c&}K0S;^LaU@-kI`;Z|)%MSE ztyTHu4IDs6yOwu529&8A70^pn@#*`wFUxaVml~Y}hd|61Nu}UrD)-&&rC+~(+4MR1 zRBfDv5o`k`W%8SPw6N3uw~z(AouH|tl}}yKm+vOwf7RP-mu7Y{OY1BUAAgpY)rG}C zZfa~26hdrDClWph>2l_*_pRnSuTX6el3X;8d70+xg!l`I@q9FPH5ueue3}4|_%Fqs zmz&+_KHsy2RLD}j^SXU&LfIfuQ8j*cL2a&|GO&z^fGw>co_s^ zQ(pBSFlc35$41i2g(RZ4#wj%cN~akDw7Jmd@v>kSUK&m!b6{P_{H2sEp>S!Lz@s~S zL7%Wv+bfuydw%Le$#R2$#0wNaA}K*sFPcai&m#oJn1l3S`UE$iM4+ft=wiUv*n9mg z`}|54N43VW??970`aTal0fA`^4m$}66TzOl2?z zK>O!JtMmaB@H5lo*Tz)QJI%2hZqK*!z9mllqvQhbH*PjO&&!PW4G~^m?zv=HRQw&6G;1SYASG%3&WemrU3^b!h3xwN3#uR50|FAp44z|ZmwwD%&#AO zz;K}NL7BHyA4$xjX}jNnO1%gO-}gv)GV$*3GY+)I2j1*#e0s+klu9In(T5m<#E12p z99EM+rN`80b&|lanDz67QgwZ6vwf0~QDE~p9Pp;3gvajYMv16cE#+s&O}^NyMwYLS^nEc=Gj{t4(K{B~#@P=HwMMU{&%Q(cUKNVTma(@4b z;cMhuR9#Iro+2qBvGlQ6y|kZF(0OqlkdS>ooLjRxO#=>xPo>&*dh924)Uf{8ycVH0 z&Pe)`9jr)t$>ifzB~0eA@tK&b0sL|_1D?d0UoGbXDKwc<3x|MbXG5TIBT}$FvZw!` zFdaC58f|gBon{TuZ{@jtYFa=~R%_vby`j25OBqMDi5Q3(GLoFCRBNakUnK0i&V ztu|CD+G!!vY3=qb$8runFcCIGRL>iqCUv!w>7yk1`FM6bFUy~Azos5v<`xUHmWCjoDDaqJ zeXoh_5v#NwcmL4D)!`0p%34Y`5YBT-oR%P4{iUi!*^5*uL8&O0dzBNE!>4|LztikO zoz=K}=9=mjW6n@oQ>_rWBe0&fm~61^R+TV&EXUzR>69?7u0>#0Ly6P1yzA<&TEfTs zEuJ_Uyg6@WmPixLb2%`g0T^Q%j;~W&H5yDGh{Wcz-=W55%}Jkzy*@1x4?roRs@85b zf)yxcmd&e(E|vniWO1!(?=M8y4<4)I%&#$DDS+C`#nXq+2D!F~#0e2jmfJ?iM0DK> zXU|=Gzyoc4!Cg1rqe7`Y9qD;PRY*6TfXcvOGAz2`$rIa?#nv8>G@D8pMNb?;_g$=) z`-_0DEvB!kbFTyCnM#)!@A>AmBfh@Ww%dTMM^Po$VGG-c1|_qg;|x7Cqoc>E3q!nQ zqal(>FoQ%vsFKX+=axX29H0#V&I5V@oBcHN=m+y94H|dp>X13&-026ipNd6HnleGX z@kM+9nyqKhZ*3+q55^J{-5nz7YwQ-Q`by4+e#=4Vb@yA@>W6k2xDP+kV!+>W6TlIv zX5tBc+V+{#H@=!E?!V;8<;D zkIA=@oN_cAF{@yWHm%Wr_#mX(sGXQyk`J&68s#@fZi^fa-JL&uO|z z%13=R{|yk=KgJ_mKRdbj*h2;wDC{xMtMFPJpS(iHz;_$=fBB}py(E&D`mfFPc)APFT(=uS;5_#0x|j z>qDaGm^-v>T8!Dw!?Z@vPrHD&Fj>tWP03^aEky&MH#h+tX)|nZ9>etnFiNMjV3^16 z-L>>-IE0+vzLNr0AfK9`-MNBBEtaGr$YDG{C`2Kyp`)WiaO)=Jb@)z50(a<2oEYa_ zBsp%!;Lm{9O&bXKRB5CTlcV+gQIZ|(pR#C+2vlhswqJ0(DD6tF1Y}Yh%4tUoU+PN5 zTnAfs{r-AB7%{YkL$vF_6QGm9ADfhk1n zOG+ZGG@oKR@mx)@^`qdoFT_PiPb6k%I||L6D$=ScLKn5w0DS^2l-4a5&0~{tvzy$TOb6lF2@&IDD63{3Ja z&MC>=dB^^BKm1|);(MACTPa564=*faAhNdIiq|OGi=~r&H6SVGkD!4S zN5Z11wCJ{z&g8-AJiVrGSeKLfu3EFVc{OPIeb9k{lvO4}M+NvlnwO{@Y1gF+DaszZdhW&nF0(66QG^i?R`bp~{t;$C{?FNbL%i||I{>bp9_Sq3 zw`20d*U?$Es&R2dZnAEGd3w?lopse}%4n731#0Vi9*)|*t1GRbOkj7R+zTJ&+L0xE zSWOMVUCjeWz4tdmxm^P(NB>xqX~X~z;rkGTZoF-8J`G2$C22qAfcjV@&64hXVxvFf zXGVZ`lj%EzZdsGLI3k+h1w;@yCI2d~-VD7-eHwz}5uo_`|wW$-!RC1~L)vDRpH+;9C}ZKe3P zF0oPRTM30gUzS+kH$PFi^@jZM)gg7-7Pa)$CAV%Cebg4Ub#S;0bttETK3e75N6`@- z6XSSm07B9Deq(z8^tm55lX)xbL~)4<#JPzP#MJD!nnT*0ihr&aY>J{g0iG{+b!LD` zb@M&$U)r+f6d{tN$~TxuDMr@%`g_!9$~!vte_r8E#@|xHEN}Q$U41WK%)f-#t_rX^ zWERy2B_@z+*^k8XVvKlXfKKy1(~BJ9dR`bO^QydeEw^;ZY5%g z?mm$D!|bLj{VQngE1jU{b%Qfj`%Uufp8VF5MJ+~V=D(c@Z%!^+eXLS)?>S{ubsle#4&~UH;V2XZ4%&y0h;dKSIyBOvxrU7gI z%8`%&W^2_l_1kupIjl%3VX_JYeM}Bo?3n>tJ^ULs6&2Ru{Z4xt0$9^6NOoeJLR}1< zwIN+sq_*Xs)*{Ey9_9eDM9|~ct}&l#07&==L8txdDu9WfcCQZ)e?OlLNtPifso)fax%3=R$PYF`*|As7*eF|PV6?gy;OIq%WHWmHY# zp0~!>$|XstCN-Cbb03MgKw=-YG5sj2Tih>Irs~rI(e>TVH}L=$OZoX9$s)klwOwkf z-t21UUsJ7JxIG*KrhA zrUeDx|nU#Pc%BB~%E5e1`a zkAZWVksjfyzIth0mp-atae(O^fJD0q28T@m?r#9&;ES4Xj>Sy#`bir*-cr-fg}X_O zTB(+r+Bl-g$Nl7`s?SjjI`tKOv2@`~l(Ji;iF&|rWV52D<2+~lwzY+M>?=3Isb@j6 zTr;pQMf*u@cYq>A^r!W9J9Rtfy*q%tRht0Ib@6y>t0h356&(TI)2w;x<>tBBfglM> zo&#l0R=P$&EtztM4L_?+dxi{s>36P69lcjm9Z1x7=`nhx>uLCU%XIiES&7VOZbk=- zoY(RfFyPa2nGD?oQ_&L)mE{t-y%` zBZTZV&l)noMGyc)zcwQ_nZjKCN-+7BMFCZN?udlB&-GJn+exNf)7hK>s zEM<$-(kG4DJEY4oP%8M+^J)Nob_-DDxr?E2g*Y5Ad?8j9{B`J$owc)MKmi;0ntLT2 zj{XJcy{^hN%932a-acWma>g<6f-;RvX3X zIFAW=zR=xW)067RrM$s;)}nAu>hcOk(8Et0Q9{7>YzALmTJd?(r4&5^1 zMaFIy+iFh^%`n@s9Isr-ug#eSbwPFWShM9VS1IVJs}~{Q{Nb7zz2fGIkWrJ21t2J2 zW_TR)U-ID|PH* za@h|ZQ&?o&^#y=FdT;qg{B9PYW&hYznG9$Awewd~MD7H2x*H?0aB8J%Fc%M%P6Fhb zl8WV5G9DRjt9ez=M>pq6!=FU>V{lhi5s~oOw#=i6xZRMcVgmMpheUl74KYE}F$h|d zN8Dva3gQ4dAww1<=#tuX6`=tqb8vLQhF9&J1a?Mic*o)eJ9;z(*4*~9hBszD0CK> zvRrKz7v=>%bbRH{V=>JT{nvcbe1PCo5=^hctO*%(iJF<@uDj;qj~hPB;nxk^1^AeFrHB=Io>Y!IwR2V?@hWtyow}^^0pcogR$289Eh)~Vntr?U9ZV@dUPlXhy_Kt=lk3$Bp7RiKMD^l73 zx9t0ik2LiD;>6OcfBHa5Z9mar3tCmew+8Ydy6+w}tGu2)iw0--79I#X?p8=G<0z)I z$CGX7{d77S1SrMW?_Tan%k+Bt!^Y1IF|Ur6Tkh@Lj-`hsO)!Kuh+#+!oC9X`FRs$6 zoz^LdS`Cfk`Qx>s!Q3BakWUfd?WR*jw_Wo!iQ(^pM?4I@=JqBcXKRmM&pm3{0ny}v z>W4Sc=lqdr{RMCVp-3pFop$Nue5~tYRP@AZgS{{IIMj@QX{mEUiX8Yt^FZ(d1Zs@* zn35#nyPpNDAb`OSd7%lguB!=f8bCcPYC@dAVS8G=ND7jO&DHti1h6xq)ZQ;^j8ih$ zf60tvtAJBBt|uUjH6~v5jT?twCtpkhr4HO|@`nZ3vs?S{M8xfle(BP*XQ)uO^l7Je zg>8ml)y>!=#XH|we%15W3&A12uc(eO-!RPsGUtTP(}N5Cs?1kFkCoOf?uP=#ZPmV* z20ae>6M_*82dE_JbpT+aKlNyaYI*m@b@(nLkn7=!0n@L>Su6TV1$>}chP7{8VsMql zR|aQ3C%jFo1`#l0mf;R2>a)rDb~_(8tG*rFLU;GmcX@@xIspb>slp_`@X;&6`v zhY1*@q#E0&@LHvq{~Q+PKg-G<4k`h9#PSuUfl+&!9!dpg)-aYudj{2J{sO{)HG`aD zw7hIY3HHL+x|Wf*J*0R6H($KDSj0QbQZ8L!YT;Ew2{>0OO8vq~$PUP-H+|@e`F`?f zxceHKewKU&wNbC@@cnyP^qP~(Zk322;Uv*IDReLUGPn$xYx1*W5*@BRo1^cpyB>yg z*pt3Y_$P{Y_7539HwK)UBJ`sY{AOUvQD4E-mi7TA{J*3WY3SA@Bn%bn#a=)^=(hfF}p@%B!(p-fct z%+e}F6XVjC4TwlBa92w*93%XJoXaHQyz%sT*TKHE1FMiI;8qD@`t$b&0OKzBd@M*T z;myZ7(%};ksXa8fz-UQ=D5N-u@5>n8`nS-UEwbqsNW`#!Vq}gMQ%!_u^pX@%DyRl& z=;{Rn7TnQd75k`MiAxt5{n;%;*&kI*JMEw#-zQ1Lw~A$i2{Ol?>^h&NACmPtr##o6v_%%x)@Xom13Dby7G`#BS+9=k-y=lqmDG! z4*|b={wBKTb5mZ&X#kFh(%&mBMtDOT+3V9>qe8jc!H9k5zTMi^?(t|pvnbsnV!(5& zGM#4PXgLM!gz94TzLs3Qs9hN^huSTvb2`c8u_r9@;$_&Q!IBLHljZs=f>9k2fA5UA zXXhq{dk}2tqA8ABx!#%x9~&-a?oQcxINb`rhP>9UwJb`)Y@t#VzEq9%TF+4YKy+|1 zezeT@)*HBhm-V=vA#s9taM}Pg69PjG3+BF=e*n7=9BlS7o{a{ z-vY%Nju9P9_zbvlrAxzbG<&9X>wFR#C+v*5I>`9q(sS|9A3PW9%K|~^yGyMRdq;{? zLCmJJ8zdowvZ=Dw0|jny*mzLB9V<|zJ`u7{+~-yY1UDtzVi~?R1uyWo{n@$l);pQu z-0)Nc{bSE^SHb#@4aWE14vftY3#kGfa5FcpdKPSAzXwccHG_g{oI!i1p$f0_+DxZ?#CBRwD;W1Kr=vmPOpF z-~0#6C6=EdRAT-vGOoojY!I(?L~4o6BT@$=wBgr?qu@E*`m=Rt z-dA#DzvI7Gnrwl~UXAY2wrsaLjk~xn5XiLn*)1`m&?c@|eA-;Jg-B=Vr+Y2L1)FI$ zWv9+E(@3beONzsVSAz`av339tno%zmIwbse0}B-XUBKH*uDv(`JeTz>YGwjID`D`! zE9%dENnnE2`IGcG*`DP0vDk{nLDVkmSC7QnEb}0q>gZlL1U?R z2Tw~~^KM*RiU(6=X?yuXfQ&2l52RZxr0&KoU<#n|_o(~c+5hoz%!stNDu7aqhnI3EfH#?cKs&>dn@mojKHvS_~DfoCeD1ZKv zU;`h#f@UTUN2CH@aJ>2I+|_AM&>Mj9J2}4T4O=IkX*kIwMOq-}?*-%{4g^qG1+so` z`)vpFVC`uvhgBFV1`fq)nlsE`H7#jfr}E@ZbEzAIduz^5g%znqA*kzr{Hga|PFom) z4dSc9zKJap>v?xzw4N=Y9f@NnCztvH-(BCagq_MVzoq~hexjZ!``DYiNeo5P9F1T$ z8Kby}8{|5SO6x;{N^arwr|=y7az2_rirxXZA=(wXr8%3H%W1>gdyymn(%gK`^r|gD zp3W74@Mh3F+x{}~5x)ZUm1|(HOfd3JltPz(i1G+YJH$=2zRqkVCFi|n@s(6xFahqF;U_ezlGlV0f+Dd#pD{oXB}6dHFy zPypq%{hMfmLOiU18A_eUbZj;HImRBZcinl=iJYqHWIrCQWYQekD_K*RnCcfM1lTY~ zaP?cOG4bi&@O>&mdzS+@)q5m{hNyEIOR^T>=2P8ge>v{#G|cTrQuh60FJN35#Jsk7 zTSgk({yGDJWx`Oby{blwdB*VxmxxbKasjEt)ntjYLg3K% zmSx8(om;&mIB{rY_AezEOTZ6F81iVThLg9mEh6)2>YWhj-#t8U;)x>>>)jeVV(j&^S-NY7><~f5aX>;NUkD2 z1F9efbBT*8tcF3Qc(`;e8OIzDVRRhnN1MCFHN@iP6V(dkqOo9!X-ORZ0-4)ctP?I> zV1p5QIv@Y*JYhlUv;90?wvyj|_b+x+;=&O0y0f;1Fwjmx!oJ|u9`xD&z=;v0&o*t? zh#G&t5hFXX@@Me16^|sP6;o9#<5jZVNf) zJ)#j}3~{5WlLDu7F?HSpkYn&Ciqx@OUU5P-&PJY-r|Q%QD9^gD^z(lNzFcO7S~E3q zG-!19#%^IL{~A18XV1%+WPZ=v-ym6hybk*8OJ+js58&mWVy>rJSbiu{?t=PR_WZ>C z)bMgAv$B7|juZw0RDhqAhYSZ3K6Kj4Ac%W|hxORe2czDvhQ-4TY&5LTe*Wk1m*33j z@O!fux^~N{9s9RQh=uq8y>|+a6e-jmY_$lvzV$89AwA4QwabAdS{43L2 zf`~a&js&dOjWlKpIv$J2&>4BdZN4zO!#}yW>y*?`V*Z<*oY?4uv~nA0$I^3)tkNr>rW9O&1%g`?V$AU9D0hiSOdUEUrW&=u}>1eY#1XQcs`2 z@)puJJ#dt^T*kXx03!_g6BC|4JKztGBL!y*OIr#GJd@5?`~Ukj8-0W}&}YjP3SqzL z)HF@z>G{MJiExhV8j4#ba$viqD37#imWfstgrgdAyI$34U$BV|b=sSfF8=a62nG3D zmSn_IdMj~=M);?*}pd+j%WU zdN2vwONQF@1dR@3v48ee?&>FsL^y@{D~S8f(1TY5GwHCW<;{c+okcs?L^fH0_NL^g zhHev9T@xPSeIKj``Kk|QY!-03xI=tfy|iKT}1`Xeh}U#Z%=w|_#Z2q&Cyl$jG4`Q2wkrf(cJxi@_BTT-g3RO53~hfg4u%S9dWkE0BK!;bKDYc+T!U+vy7%&i`pl zo+3ef;c9Gpa&8sC0)Tr{{P_AU^tL}ht^y))bc+pPq@(l`WEWBgIiAPKNmX6X8X&e7 z4CXO>>3{mls@w7{jYg~P7W3qObXE@T720K5 z{x)Sp|Cwo`1&Hy*VJj)>Zc$3Dvyq@{zMJOo=EKr_YcHkHb4@I(G#o!QF2G*Rub4wPhn!eEJ zJB|K0c3Qc9rbzNZe;le@OLJ>S9svblQe25xcI}B{q*7_om4G)IteAxLU4( z^N!mEyxfBcBIm8nq9l5x=W}Z1yg!Z>t9riKz4lbB z?#tdCe1!|U?;3dWE{cXp2J->$j@!QdAdXZQiXfgg*kC#H^rhQY1%f{qPn&5!975@O zgJB%!&~TZE<$2OX+x?0VX60T0Cw`}3jn#Y&4Xdv^VKb*ofAu?{AsbQZCoOO|E;HA{ z|LXTtHL6IWsQS6g4}T4=A@@*`4%lz&G_1d4*Y#3IHp3k;TsfcFKMx<^0*D>Mhp>`H zSb}oAbX!IqftTHULVU;>K1+Z&1ls=o-MehUm#E@~?*Bj^NtqA>(G|AO_$LFQq>Hk{ z6l_zLc7uaN1yLK#*-P}l_10|A==3k0%;<38{z7C9e59AYBP*N^@rZ~)U~|NZ4BfR_ zyJ556{ay%sZXlaa3x*5t-&58}l$!dln!wG6>09(TZ^cbO+-lo{^2V#Jc_WxIU5*64 zYo&shE3*4|u;ru&e^*C1501IccQ`&W^?x;%O(a_E7(C=895W<`)(S(iEiBa|8FYyi z{3)rpLcrGT#o(#lYGs+n&8h2C4}KvENu8(=;xDXq`=C+sk3OEZ{&d}_P};tlYirq5 z&egzS;KV2x9R%-Q`8S4(y~MXe?0QGD!g24DZ+m}#`}^r}Kv^`>&V)4)BSifE|GkuW zcs<>RFZx$6Oo5C7W0S(iz~#!>gNSXF-Z?v>Rp-HwYMqkLVRb|-&%-_rhA~}lF};JX zigGWcUZA~996_DAyN^_iXCz2oM#4TxIl247U)!91DBi2JTMj`TF)S+0XQnJ9IEBHg z{)VKXHPLDNyQpQzjSF5?5N$R}xGySW%XKD4Z_!dtIL~JLA&OuOmOdg14#QiueTv364s_>k#`6JrZ+IvP2fGA{1i0BKGw7Fv&|8)FN`h zSnz_G)9Uto$DHs9Ykd!!xoZQLeA@IQaJX3jdIk$Bq#PNGA`cbbVP~ChlOqCLA+AQf zY(JKi<{`ch-8h)YmCjxYt%<7S{>${kKdCrRWFA5(UwVD@YO7u-{*H0v_0%?DC$ECj zXu3n-)+1skDK_K_*TqNZD>H$lfg%O^5`3?5-2Cf`x=>5HDF*99`yQL9Gw2N}|HOA1 zsKyP*?O6-fO4k4PEeyPv9S7y8glZ!B2cH>L%HJGcGEbyQ@Rc<+MdPRZCGAMbyYC%v1WmxW?Ra)$Q&_V$AAPr+84B++ILkv5CR7(7AEC7N zLg8meWki{K@F<^-Oc*L9%RjZ*9l#jQW^cw~lOOE9XzWQ|?zu70vtsDAC#?Tsr{g=f z0$YqQdz^qU+xEZbRY$GZ!CqRWK)~%V(+Kzmt>^N5s<*0|Btyp{oIE4ldBry zwvgGo@HLIqWY{V@kuP7Cry8A)kkNUM+YTGSI;aH9JSVrBQok1geBfyjv>=e~&Udh; z>ulHA!?&}2a9;3MH+_2X$YCzTes2WiBoJiN0KrHO=+XorP`QF;=bSlQ0^oRozYT-U zo^2TKRjowhFc=DPEM`GNV(&g9>t&qpPVQ}V1!IjcAAV0@KTEFM%7{V;WD@JSINzH- zaslcp2Q(qTJbas@U+VLU{*<5P^&S8ang2>D^?RxEIPl+r1z0s{Dor4ncICV`b@0vY z9ej|3I|%JOl_=&8&z~+V(-ixFW+vE!KV^|zO8#sX57HK}oGBx_ti}Iuce_^_@k|jb zO-xL53#WYXa>P=v6ZLtTzM<@Wo=MNv#0JrlT*~mXmCfd=b{0(1UAJB`hHnimXslQQ zt4i*s|B2kQF@E4oM?-_Z7b^tEMK(gYPNKJK4KMT=p~e9~NXte#hM*Jx4ivr#(ACkN z)^^s$=sg?5n{jdaFGlabH&cgf&)U-|7;0Sq>{BE@vGybuIB`aVwTF z-FXSTN}fgP?IMH`LJ)OWPT{cOpE3eFuSSoE& z0ga6;d`55u$dOt^xGMqLRM}YQPUFWclodmaT%+F22Te`u%DMIRbnSyyrj2sRAJb?g zQd~b!oPRHvaSs0y_yUlUtPis!VrmknQ@}U^s%%7!&GI9X>mdq&ea*JH8g;@#B>JUY zMPH%)Eyl^uoWt4n5k`+v;%09K3Bzi@P2gSdg;f}WQ8LP&jB@${>gopo0eZRxS35fm zHe}vIQO#5LwSY92zCTyJR|6ilG_bEo;kbI?ix+OVG?lx4KyO3f;h#b)ww9apDbSDg zT-`+cgA#|t-oxg{?3eQGt+NJYIIQ8yFSDkPu2v7k+uiUsoCf0|uTR>8<8RbdZE#q} z$;ye`GF&k9h-P&|J)Ql_zw0_%%c0f%eo?!hd)gyOI|DS)X0S`47|(&8+lTN45UzV zt!H4}EU&164{qFFKl%n|@vZcv&Hp}(IobhuB5~qJ6h?h|GwJN=gehqaMl)xr#xHZt zN!{o^>nUQ~xwX`g2E`P7XR%Na? z`Kw^{t>6Tcn-$2$)3W8OW?SrGI}+Nw(Y*22o}YYbMI4RWt~Qh3p4XThc+dblGplz4 zi&a-sDIr7!4)fC935=R+rtSBxkMv4RN8W)b+U|%U{c-+x(wXkJfppW#vm?8X<-!Q3 zkCe6Ep$CN{b=6&ux1(`2U#5%7Zo+e_TP#MidZO9s_q>+Mr3bqh4t857ejA-X5FF-p zI)?OqeSXm4QT9X37HyN?_P);z(p^S)ZmC%lUsa;fiVN6pdNJ&{c+qNo*5Wa1wFat( zF9)Wr;`|-xoh!$cl=Tw2e@i1N;_jei;{*$i6c&=B6i<4Z$ z2i?FlL08iH=;rAE#|}5HOM$EaR@-^eackdaZ%WhV9dKAMnV8W0=fk3i|NemxaHHzE zbQz07t7yh{B`v6mld9swk-9XDuq~e2&c=z{to;5?tqp(aO|oK{;na2b&Edogqxo6G z70@Gwj$DXYICngF$CgxAkX$-r66Q}lMmTEBRjyj%rOiF$1R73%?kd~N>TKoUKMp$| zOy+K~*lPPWWm+a>k~U0P2@7Y|RZ3x(INQ|i9vAti@WgGlrJmB7)Zi8u3CPln6gv#SEn`qpUz^X2zlO4yS$ z%XHRs3WAVktbj+=&wEF1q}L{q>i z3vS}FwHx4fHHL@Scni>kr*c{`NJiyJk~!=8rc(FU=m0F>tBxwKhYQt7{#3#E7h5-H z+p0{med3CgGO2Relw60k%U<(Z`w7?jpjZHHxfwr8L+ zjBiiTRkM;i>N+UL&`fS zPq%`(aTFW<{@G6xtc4}q{u~kT5b|i%i@i2n#F2nueS7easIt2!E+Z(AbqRZYnSdCP ze^e3HHG5t%*rKFmcY!`TgwRT>bQiridD3n0#Dj?Y3)MCqYe&&z8r00nxjPBvzB307$F#)@2cq6;wd9efQ^8FCxib(6+9--k?iI zKDch%GLv{^R3NkxV7o`8vZP#RKjW>K{Kj)V;cWr&PTAvKhkM8m1;P?P&8B!kLL1h5 z=_@$x!?(05MaK;Gdtmij1A2+VK^bV;N(D041v)2=bg=fr zyqRkT_}f=y7`@D9V;_%hLEK8Vs)dmcI2Lyk`EUP`*+;3?o%t?Wl+=q6pwHFW{+Yu$ zV}&u?vY9Cpk{+Lw4VL6>8Pu(}%T5*mS^(Si+VN`VTJzPC;$6{5zGfTS8JB>yt##sv z=1yM><>d1IG6>ygK7u%$edcA7s7#{&ewEp{ozzP{{Wf#+{Wg#ztrHUcxsa~jh6L@{ z^Pl#GJjBY8@2`A+(a6j?vx1DmkAK-M`TO8xH71>D9um28*2M*{6)ZrZN(bYI^Y;L@ zsSCMjCg=N1Ue85gvr?1k@2A7vDW$K30-Tn5Z1gpUjlr+J@l@wiTGzF-^;H;Ie+&^R zAC$3-4BpC4S!0(`4^|$?5-Kjyg{KIV6lV_$kK@XF10~|?8%cx@g3BG)=_l^ND*F?-hVl(pK1>#=D?)&Qu35C9lZ(*nTEChPalQTmQ^eS?|?ERJHcNGMYad7Kw*JX*c|HW(Jd!3!G%yq)ha{{?b=1Yzm(%M z$EDs6mKzJw!t)j}@mMj*S=xxn?o83)Lof8Irx_2>1(yxxJzi&M9{;3e5NI}7f{s%R zs-Mj?nb{D6t&Y@_J+BY$%;-Pg7({iinEmacq<0YJ)GsckH~1!_&kVWmuL%k|kX>G{ zD;d@g2l=rg_l|=lTzQ1z0Bj8LHd76__(pj(ZOzLGhe^*^$2+x%2T;6LekMXbLA~nM z?w4a!2;W#daxy&fc}{832j_LbLi;|;!OVbhcwuB#`kPw!H^O^Ja4v!q9`E;6@(n2@ zFIbIY(0JDMrC(Ano|#cYhyfP$N@v1DFTuBE0o4RpJ=ctwu)*S2il*T<^` z^f=ab9d~^#Fi|*I={hyN-Ql3P-Jq?4iOklHAmnR$Gjy{_{u`9JODwu_3QP z9(VErJlF~@`>hF%T701~!NT7v=$KYjI4g`jD zwOVHSoaoK(AFllmp4^^>zC_U7nqLQhL+1I*Trn=-xp^IlbI4<76Or=+zekBvB?t0b zQT59vr)seQ^NC2tcZ1RGhwfPcvEUbx^qVdf1TU=L$gXs?K)55xDV!$qJ!4FCqq zJjGliiTgnT3I+b7Qxso1+cN8&l53LB-(4z6OfBZB@-;4j2a!_a2MQnqitZYG%zGa} zci@0pil}b??fq|57nViRoY)#L@5^T1SYu2};S;>FCBeXz(d>9HM=ThRYoz!Af3Fo- z!Oa0E&Q!AF9}JPtZmFn&nvl5p{m%#6;KSO1D-Nc4kzb#nyFaZqVb#mstG>;j3>^g# z8S~Niv`#AW&elf#`rsW%Z$a zH#ZM%wOmf#rN&=0*z#?QTssST3smS_Gc9*WpL77didDTr%ZuSIPJJYfCS7-;R9kFe zJUbru^eg^JcjD68bfEv+y5wy#SO{Jh{5?|10Oz;R?$Ayz7|TIjdk?D~V3O!rpQz*g z;8@LpH2(Em zeqi!K@BTolZ5?U!OPySo*qwR4-Y!Uu?})4XI;6MjN9WO7tffP0M1d(`JUthaAMZ0I zEY&fzA1I8f3*z5!=w$R-1fuBJv(rq+@t!x2#D}Pt6qfL+UN=|_8@TaI(!M+M67%Oa zn%FjgCo;>qG}^Gxo_Or`ypL34KR_-&XjJVM(0okTaA7b;CdPLWL{4QPhu*%TXF`iC z2EO@B*A_u+Img=HwYY?%;~3}_zOi^@DVQ#kV{Ia+5_Xx58SEfUUY*?X2D;0x;dVR? z%)(eh9HQ^afvik*#i##rzQ*c|fovILwDa*kVzvdq4%g0WgNx;`NWVpF6D_ltI- zNOG0lw_Lkw83$x&6{!F0LfRb9&gh}W3=&jn`oaZ7#^8C0W5pk79=0Gw=+;D3sYWpn z7IbZ}Kv5%$Q{P91eR?+Xr3%9T{Oxby<-M^|a1iPun=kwxQmB+4ZJLgt{uvLsg4$QL z7N!|&FKK)rO6iO{yp=$MS029~Ie(@?Tg7~UuGK?Y5Ls%|UDl9~+UR)et2)UW3cEPC-n$ZSy@#lN8F99cO&r28^R-Y^|JBqJ zU{Oz;12)SghpS(>mSam z%3x>1?qsrF=}51t$2BrOQ@kj?CjPSP9t)H zNTVa(RBUZS$y{NXfQlSsRJ07Xx24lle7!u}ymIzpTU1z_P=ZBZxjr>sis^TWmYlxm-AJxs2cZXqf3 zWU_x+pBeGqI#2_(3hvP(!6QQJIO#dUwGWykj0t)T^GHP$7VJgDRUcO`5=8h6X)op4 zNXCr(EZ?D2;MBf|%>E|o=2P?yaD-xBm&`5*7in}~#ix=ILTnGC)=rn)k1k$+l(Ip= zk3`E7XBB!>poD$DD7I3`!;bZhTu*~hx7u8}f;dD?#+hRvIIf$vZ+Sz-(FE6YzNR=C z{W`iaZ1lc%(J5t`tVo|;jW`5%ZUL@Qyze z3NwyC0i$kUf0C)79NMZLZZbm<-fjz)h0pY4|5Aml?qxGguIhyZ%O5}ZO|bq+eF>-j zarImoONCJn+-27%60ajM4yacZL|492`UMC%)6l^`LtDxJhA*_bNlDxDQO5YvjX-+V zpnIznN;?oZz+c7)dEM6NO0p`N%{Pk&H5({D zsW+yADX$#do_Ry8S**ckW5ie^WcYW=*^TGnta~Y6s^`e;c5TK(k%>G3OtFls+{1Qp`)*TC^~A}hWI?M+ z7_ug1G=rIaLqq-YO}iO$#g4he+!gH)y0rSB-cVZ;)& z&_L6(hDjSpMn)s^R5+_^k|jq)@dzKe<>T0Fr!*v4 zbHA`B#V$r(ZcQ@&??MM`Ai6r4V|#QlbRPqvJg>tCltxJrq&?LUHGWatN_%Ri7~RvW zR7KJ#R|J{6%2=_Ylg+Q~YlLzd&*9Lh32M9PKdf9H;g9LWQR&P~#1v~bMh8DCY)|op z57MaO&K{{0u!VTb33%0r4|#5PS|!pYd6XeDHAKs$3@Mb+MCD`(mCI6VIQtt~Wt_^A#B_#_Wd# zTy-I+e$z*`3gD9D9bhZv2S3jc@UKwdy_Cb0RZQ0N&yzY_ayQGot3LMU@jGCDIEEav z^<0kf@FY2DdU^B@hCm>AVpB3lnrD8&Yr}5tWw$1aQUwY(V-yAhOqKJhyjV_J>Tw&; zp9WF?@7I2z?QvjyrHiie(|UPR79O>@TO*-Ru?TIzP`8kINaoEcHTN)fj1m53xnp2V z;7MnG=KTkMww$c-hb26j6eNCH#8biyn(>5-HQQXK%y;onw5oqMRD}5#Dmm%*BKE(( zv%y}$A;MH1tr98qTiDkSqPWN|Az6bzE6!EnHI(!oS8h8AsR5D4ekdI?F(Ez5u@L(@ ztmxh73^gN~T-dIvBBd%1zvXh0vLEhjKrxwAejhkT;yY+1iRI+bvTd`n3c`{z9$1Ls z8Kt0JZq!J9432VK@oyIhOD^7N|Mk-8Bcl-Xl@2EUEC_AJjrKSu7(&R4i4%l})Ow+h zTi|}}7NGoISDOW2^9?A-+lCvnz45_Cwh|fT>_8nqm#VaH?%=6Qdc0#$BF?hM8J&+N z{~2(=Q`s*>mO?9b`JAb~c>n!}i~~$2I7kLtnP47~1}n=1;yT1m6VI4!-CR=q zp7&RnglgT>)NB2_;iB-0D84eYosr7(WgUF)d*-QVTV(zJP*Tf`&bEeFp9(=+ipNs@ z(<1Qf7(gC29Lad>HpE#2c0p=zL3F2MrrRXVF`h?L+@R?r$MXQSq&7ov^+!gTp0*{e z7+83Io9|~`j~3rw)(J#Y^#+bM?QMljgi81iHgTly<*E#$PsA*ipW?;19Zv)?P}oTw zsO@&$)-s>$EVWMrJXq*_+Nw)8Po#X_6@Wroy= zA=QG2veN}X-xNF-k(&uxcEP~x=QdLg$vq8?T5L9IytQ~RuD02>c9#DhGzm4v=BEO4 zfq+glzPjhDQ!~~^$+1^<0;R*Ug-09}Sc(d*PV*nBXU!pJ1>x~gLvY9zkOX?ooMV0G z1=}A<=^#!P{5P71$Lrn&EA)8}S)iC3uHK^84rgd56;GG{j00tDYGMP7q&P*OmNvS9 zM458ucQj>CuT27pi*@nuLDwhhVvu)4PA#Uu?lrD+!^H0V4z`wHpI6+DVhs9Uv` zI**z;(pE)cm%x!F54c9CW?#Gx5}6H^04it_9QrT`2prkqR1_R78F$RwLghkZou{kT zCp3onM(5IGu%I`90N(_7ewK&fmq*J)TCb_8skg#+SK9r}!O<%@2azP72N$Cw-A}^9 zqc)||%5K3!JUq{S7eFt|ge;FMAW&^4F5)D#3s);0-LWkeYKcfL#_p+3HeYXVV#r_2 zR0^!}^3QufpiVMboxB4H?pNwWtsS>n;w%L8)jm#6g!6`k#)&(?Wrqj9zkCQ>cEXu8 zv&Fn-kca-f{IE%A1K0E6P0FBQP;|3$98s*>+M+(JEAuI>S6mcCVj?lX!g6C&c?j6} zN`U?~w1~y`I^~m@feu#vA_#_k%XqlEQUwR5$bqwhIObOzfv;=O%ewKPMvsTYdDSQ* zs=8+nm+@QqMF^u?hq&%r*$E1#Cs06p|8As%-4L)zm13@zPfV<635?NT>IKtqomfp2 z?kw3}WE9_cNUcyX5%`iGXyktRoZuwR1IN{mVtf+-hV8esI^kg@D_h;&L@;6P(O@g4fajMjg@fg_49*xT zLnC@S#|w(}cGoBc6le;0s%+QfDS%QYyMhR~**8M5_=9TGQPRYeM%Odrn4^v#pi5ia zUL$h9yUEoojekQ7+`(ZSKPm`$(MM+ilYU}!Y zn^;DC0M{Bt(8^?$GfyG0%Gz-imA6JhmLeOvkMR+_*z5$2l~;;Vzd|p`C1d5lSrB2f z(1x_;V|&|M18Ik}dRs&(}PS;Q8)7(~^WU({-U>9*O z3OuG?9VUe}U|mT;atL|YK5QR|mV-{;(TNCCO-LvMQ?VPREg(4b8gIuA0Xm%N>}KU< zJvw8H*p!YMvu5IS^sRwoR7>4sqx;n%zWBYY(&$NBT7q~3h!S!*9?Ur&f=9%E9e^c6 zwTEE+hN+5OGUYr}H*sz$7%F2AzFse~0dYCBSMLVB+nkay14E*EPqzh(Gx$|aOh++j zy%5R0Hr|tIRvJrBf*~0RLP+I?m6i~UP4SyM(2+`#~FZ|G=2Zw_1u2h1I?ust1l?#g^*ft!3N*#~;FcofvkfR3n)2Qkvq$ zpVP))H7y`JxLex*3B+_J@#T#jk&Z`b(Zlbqu6PCjOWp)vtA{Iq&=wHC4ZiEfF_H!= zk(T$xq^gY>Xf!A?ep~Gtr0|3|b#zP=epW!iwoKdri~Ife+@>jNjiG9W>G#TqGixFJ z@zjqd!E1q6Y`lMVOZc@%7O%RRRTEEDLj)RFM-sLA-Q{;fi6a>gQx3^q^!NkCW~m z-Lgk;jFU7zz8YB&yTw#dV(325@ga7`rQj^4N^R~q<}gNEFp6TG!-}Rd3a1Jdy$^#D zh2Mk~;i?aS69or<=(YL4=AdwlmnGoLv`=csTKMXmuEM~#j@p~k=E#F#C&PWkwK1aW!Pu)4s_muN{v zr>#sofAaI58>8MD1u(B2SK9T)U*~Hjt>K5@&^Aep7`FL(PRjCH%l=_4I5?a*9BiJ} zS~`ch(8ODTF%%D*MyGhKV82XY-bMVfmBH>JZUINW~ z9zMR$t&B8rp?`OCC$$ShrpPt6&C<3I6qqI5f7oDS1v8NqN>9R?7dA|X?7#7}%e#?e zBXdro9i$?J6Bw(p(litap1Axs`gtgknXHbFhT-`Pu;-(2a+Y7uKY>HfgloFFAAeg~ z^)lB;Bf$IF96nY`rCN9rY;kdDkV1ID??e2*w_<18D{_KR@)tx1R6zUg?#F`pl@#O8(sO4ocaSU& zDu`m0`oud*D)uD~8D*^G41YElMKQy1{v)#o!*#mdxP6m~WAS*i;6!<~3QzHC9b(Cl z^5%XN+(sP@&+1!?#orgdreZX(s)Jm-)r!P_%St8CG;GvWkjI0sdc($O;H|FeV_ozf zZ9HRjIpn0n`;Va%&SK!tw+!M-`8PvBq74sTjU`LHGBwJp*9s{#s&r{NS65%^4MU#1 z46+Rq68LJa$JPhpuA4;4JDx`Oq7+V(v7esgHJr`SPT`JxuR7eqOA%AYvD3jQLxa6;@?Kr7)^vxue zmmrRyma4cTAhzl*(_Cn-mn0v7I-gqKstCKJblqAY!mzba1pB5)?{9(We(BFMeYbu{E4_CkrfF ztru_{f$y3ZEFtTGY!#ypfIE`pR1!sg>)217o9KEzL$)0^JrPAtXG4g*#Bj*<K?Z7(xF)4z0-SpT@(6J)46J z!ZWxG^2{}l(zP?!zGAU>B8r3KKjr`nlS5!ck+@W8BKu9d--$D`-W*R}biP6ed#wG`N2&BR%KxiV^+{df15uEc{4tBpV1!Clayi8-6}K z5Pb}}?V%%NjZy4uZ?ov8lk%#2&07j@8VzqDYaNny8G;60iSaR-x z@we6@%+?!z25Uiw`u~E?4G;79Li&mi5v-G$ysDc7bD89SRH{`WOA`z*XTT?$q*6tQeJ9>&lE13EU6W;#Az9i)z>S#Oepy?k`~M%2&<;+M&N@Cp&BjT)sSv*KC+gqs@HXs zzwdShNd3Yc<~{GCxS)CuTf_SVv!_=aIe6pOf%rjFJJthua-dYB8Foa4Ld`X-|%GbEtQzc z8-vb}h^Wn8KdPbnIkiB~9nsm`&)K?|uDsWEm_N?pPP0$+?XgI2Viez}Bbr{o#2D$PtVivtj+-KJK zV?I>CR#akE-7o#EsR@0F192%Iw@Pi^n94Ge-+um&w^(SmeHEn5{u&>iE_OEi;ZS9OGgwb-5?(&ZD^E{oO2M zsrzaUYxKf{n&NK4liK1{6uz{@M;G)a)jLS2DO*1FHh>=OTN1 z+Jf!Fv!BsPG5Z(Dq+GfCHd!iY6}ZpJbBTolZTmZp0GX!LUXu&{EGWS;U}5}{K{X9b zp8o2WU0AXK#R+M*!1eM~`!gb*ZNg^kYdm#As}p#!4H_>D-xuVSI|!gUzmiR_4Tc84 z(bclYjS&k?)YQB8L&LAeZR#-X@I!0Vx&DTh52Js;ng{W_viMVxr8IF2hgc~6TR5-* zaCaQ`LFLe*rQ7IK_gOc@Aco)B8~9g^L}MtVdv@&SCQ%aAPHT`?B8LqMHM@=~DgXPV zlcP2dS!WDY3Pqd3=mN_ZjU4E*K7CN;S}^L%DFlk5F?+Kf`05>;HHC*U9==05(X2H| zw69yRlvWx?)~ys!nJOIu{#3l!c^^yi=aV{m@zT=jm}%zuv}iieGFg+;4?Sq<$+!Q-}3uV*5Q|U)4sLrsBU~iQ;VkjJC6C66E5@EW4;GaQ79bqlm8x zzs`QE2IOjCOPBgVr~w>McPx75dmQF&IF?-g(14VU+g6fE=xA3L3o+C%f)CsBbDFU^ zUF*e^ra5TQ765yKF;C4Q{Z<_ap7nTCpzX3%ddyXs8P^MZaRPb(g>FK5=R@z0`W7H{ z4DLPq4Q%NfK(cm-e+iVRl@DN-{kWnQm$m_B5pla%xe;z(j7 zhSx)uwv2Mcz98Ak_=c~`N0cUl;wRlO2I+R9eXq@e#L{XzOPxNH5DUe%9jZ_Y;56QB zpMN0>JFSv~a_D2r^0PlD_}5sx0#&HxwwT@zG<@UC!soO4&bCK5_8!6Ug|8VXf4ZM^ z;}n9s{`_o{Fy``pnAe+V0)elTX=@Y4@ZTWn(_T|)GQvL43Qj0tmF}tm%_WlglmhSe zv(15AfDen@r0au$;q#IZ5mK6uyh&27ct1;qN1}>_lf%De{Ta#??gCEJJK%CAAfYHq z+T<2|LKwtOYuj(b*$A4)G^+_nqN=#hUbGz2A10Sq8>ZjpbpJ}Xfk0;A4ZRtygeQ3^ z+;oDu0L3)(+{sQD)FS|!JQZ+^jEW677*fll}|unOr8$?`DI>;q5dPpUBn`3#2r-D ztdc5ZD5FHuKXx)yv8}Tdzef^(xbaT7+@1)usIPg6_v1)l?RN0O=Vfs*+Sja0@y$^Y z*m`jB)EpLi>nT`!(Kw-Wft#*h`_Qj|61Ldw_Xelw1xLl>1l*|%umk6T6LB#yxjcbi z>gzl>6SYI>-M4Co9fgY(fAj*d%?~{2{dt5t?>JoztZ;^jQRJCY!~0;2yO^azlN zb97{DlA57qjr5-YbGXb98X7$ZC8RDesb+F4X)KAf?|Lsylo36(sI3ZRVi&d;$gU?J z5Gn6_ujX1PGNM< z0Bxl-ZpW{&xMWQL$FO3HS?oAYz|@2)NlPZWOShfXnb(WL27vQ9Cl zz91hu+8)}AfyN)X5iGn;6E>Y9Y0%~M3yad`Eq0U+^gSR6;<89Dy6qKHz-@L!aEor3 zeWpwT(7_QagFzMoGZ0WQoI4?teLEOPWZ>0i#tH(gXJjqjPmhu8B4v4J68Ps6in94Y zJPNGBup?wlz*FzyjlVcrUjBNfzHS^5ROIcVrGO%tz+h!(CNV-1aS4KMC=4cq1YH2= zPZC2Y_zHGZx$(oeL;(z#jKd+2eEJZ5zP+N#!N-SQfS+dt?xAKq21Yl~iI%=|K`V$H z6vN)Ya6DXxK2`quNG>9-!(s{1t|@&Dt@y{DJvGG5n>O^7ml%V7zG3%>{a=h7d&c3wf;XUA}xBdPy!V86>!@S%$ zPCSnYmF5f_qw@AsRE-*M6qVOM7bQtNQm?XLCiS5HibGJQ807SAl5vYB5u*^OFlB+) zi#FW(g2VK$AOYt$V$P!__anCXXZd*Wlb9coC2DctNpP@;ZISTW3VB|XcDX^|&WCQ3 zCGGEZBnI`%d0s#P-;#jk%A2sLHmbhw2wnQtiI#&ViyX9do8S#j3f|30v1S>VeFS!K z{{eAkJ;EKtM@P_^&ISsib&LDqV;-wiSHi)wReTqm9FJ}RrufDvzG&uX7Mb8~3>)4K za-;EpjgN<7QzI>{v2ITvvR@xMCUha77I~qN?7+S?Fd-BO@CtImEMBa(P=$JADxn_q z{kg}{acM6a;1$Tv&+qwWz=UTP!=6Q6_omwbj{-L6?^K?A=LV&QODdSsA30n;BtpK@ z%CiY1Vzwq>gRw3YRz$@PE+g-cJ#1NCF{POIi13C;Y`{^5_kx zYXNLJ6RKP##~s8XzJWfsPRbFLK8NiVq6>U|&!12``^LkVueA6FUgnB=4FkxZ_gUIl zTh`ew^^wFPt*hd?|97L7dF~g<`#~Ap{`kz-Tmm`Xv;_roIhKM1T@k)uzcK&04yaHl z_lB?}th`oc*#`WsqJbT(Hg0ebugdq~tgu#pH9By5VDJ798N;HH$c!lB10U{m2f{yR zQf@gKoDD7p5c}#bDB??RNb@RNZCGSwz*7XvufY7yg#%>abc)_kI%>p_A3HctFLJI9 zt=zxRJ{%^O|#LiggDJaPt=Dgw3(872O*$CvPF{EjfUqKDC zIoOQj?Zw`~;YgaMxo#yHJAC90mk$qefWyh`1O*gRDc+#(upz?-#@-I}vPj(jdqv;= zc&_7Eo9@(rJrtGvS*U4Tix&CfwuZQY-5|7KU#oP2ODdFrM|r^bNXo6 z1*_F8-5~i^!l??be%r<=XT~m^680~6?6k^66Er3(D+xMoH`uKhD@9+QXkEbq_;=`3 z*D{X`dgl4of)b>}4d!92Y}~%-i(eIop?oq|P@FOEx=0t<*-R;X*h&vd}>%8xp09Ea>BGs_z$T-fZI^LciJ z<(ub#L9)RS_8^V%#Pau-1p-HL4`A_`r2Cwx^$2`E)3K`+a)hC=i1D@`vV@NtKx>C$ z5{9W`<8aPuR!bv%pp~9v`vh|W%97~o{O@cXN11P-W+ylo(@79s)#DM595s$!b1JqN zEEGl#GFjn8jWWCX1z~% zqM=TxH+a+;asTKr)aQtIEyVl`(?CsP_SsX$`#_z9`51Ess*p07mLV_7TCowOh!C)9 zl|+$|O8E-)y#13b{Q`;2dbXA+WH#Nq$mvpFnM(eAkW!$=eeC^k4*vH z!nPLeTgd>}d~PVEF40Cp->I5Lslp*~+RF zVX0`nKMnam&As5l=M*Lq)BSRCv2;#h1- zaEZvBm#suB z%ZSwXpE&WM0MR@&*AB?mQ}7&UQHRBXlYPI$YEQY3)2zZ-&DE+jz8|akxpyqN zx@QmPUG`o9Q{tH>@Sz1qr2GaQnPs56wcx$tTKxDf9M@R1hdy&|Rmmy~m~=-_sD}e( zA&goiI8yL_BylK6smhL(3UWf%ClXXGcBl zS^GR-62pi4|p9-egzObpVFGR!QduC@`&-hQ!? z6Nw!nBDTH4fd9LfGXN1~EIPC5OSWded< z=X_8-SG2?hubPN)Uiwhg4>zq5sg^E8s063{^fJTZgzy$yjid7)Ssa98F}Wm{s*{g4 zL5bsp=Bs-fh=`EhHb%0@_&9}OxXY)75#pMY#9UbxZ*A2;D~7kqLyc$+?cuDR?wlsQ8Jeyh`i7IS2Jw6XoYFQE#(4D5r_;M`4y^pfw+ zp49-#)%JL#J|0x>PO%WHQs$an5JOyZ!CxK$E0ozsS?@4t!Sl3yx?oTKE@sbQ+4_7l z#=(l?@s@6d7MMRoJK3{_h0axw#{~2q?~gV2u98Y(ORo1jij{f+-gNi}RAh3q8~SGz z9v}YdJo#{YWjjKC<`t|}^c4~ho>*crYzXZ$C)6mL37UH$?+=DE(;X5olmYSU*6WRJ z&{`~K{p<)SvL^gOB?)ULsG|u=^{yQi+J1q19Be3Rzo5n(ls?HO< zolmcoHn;uD0iL0X<>42Ao=Da#n`tjs^p@CLyv~ByS6~$M z(PSJriCt@t<{#w9I;R?1nq2*}Rn~7~+UKO&Yridkf2Su*L(&vApTsnQ(7C2pBj9VCwLUPg6cR3e5NWml~|g!0W!RT1pIAcpIu zmYS{@p?vfrYL{5*g*ryy-{a7B;bOBju7rkBrX$^=zh(1vAAIMa(C490(MlmApYm#F zG)@|f0PAO&nZXyzGz8vDePtzS_5-n^M0lQGV%UW$7w7cOIj5jdagnfmsU+i}v)>!l z?17oZ@J$w+aJ=*7e^6Iz|0G6gNF123&8d0_M%S!vtxx%JU>pd$9+8?2;O*Mj(veT8 zhUG>6jEQ5rGG(|YRX-rHknD8OpUT}8TPD3OLGStu!(*!!y^O~jNJOXIPPMd-bR+mr zLZ+kg<*6FFgjT1qgx&PQ(}WQj)8gd!x>Jf}MF$fDl;6nl>4|aQWC>F3laId)3>AHI z_=20%wq&_1bAF_GF~#+-v>E1p2&KpAa4S5G@0hv{)xdgx1P}RuHHUOEWv~C@qt(qX zEj=*W*O>F)K1yLFOP_RZCtbfV(kpk7ix7g@OfhOjf}qNc14>UwhMi(mpb%+ z=)=V`OeOoZdr_@33z{dNEv|ju8*Dqlyf#J7oHqStTY^9A+JrmWFQb(^aLIBQu~`ba8PJ@k^2e$N$xZyTR5rCxbDn=sXmp9sv6;#k(tXZ3WIUf6wWv19c;Fa+QTR*z z9;ePI63gP*O^mS>1+aMbA<-C)-aXGxa#f68@5h&>5kiHTCsq}h5wOB1kr_s|e%UmX zWf12Hh}v|4_O6R&$N^duTX-C)3Smh;CfH0Ad>)Q#~)#Upw_c^(8X!cweq z0`XXDytEtA6>k$8~_s~v}Q<(G;XPk=V<|+Cq}#H08R6UKXf@htN}r$lk!l+ z|0CfX#U?wUe8CCaF()(IALHBpzRNv(=aRoE1cG4;lL%%J4|K6YdkYe4acKI2vgX-# zc)fV$b@!hzGo}c%qD7E9raB2&CqeVWYq;OjUaUjax$w0$r&ok7%)Z1*J92u?5>W9k z8!UWT>RYcpjlpQ$=5vGJjO3#~Kjj{MsSEdMrpy{|-y4=9KS?m8bcc#&%A&z{{ms5? z%?|PTP`5xg$G+%PF0UPU^9~n#|CjBNey{iq(c$Yuxe;}z?o^yg(8-XUz*F%cDOI|M zdCSrXnb;G*b@J_SX}RFb+xrK9{PMNajlOS6TV{@x?H|VKDK1?^^BN*9PsAr5n%tm3u=8C{ zxLoA^qN~k%zu49~uuchNNp;D-`jnRNXx2-n*9KCIL)dnzgU(939E$&dRvyK*(Y06> zQ$o;HzJiEwzDbI>`PqmZMF^YaT4EK_qc5nPt0W$~F&6FFYQ;tEx7Jo`H z+^26gkW;fI-9OB#z1D+5vwU?^!j(QSg1RH1Pwa;`2`-X%0a>_O@Yrr#Y-|O zJtcOoVpWa0!u-W*#zI?*AMRJikXX0Ys85b+yyoT;Eo`Q)p>)fXy#y8I$0%e2z$kD% zhsGGA1#bzX&prjxY054EU!?ey;f~6JgnChot-`(kW)7weS6Gcokd=66ny-Bxw7$h* zSqw=rQiQuCn8P9~Se2|aIk#*r*>bkCuG+}FG@?p)wEmK=&jNKTFU^JRdaUiFdtB?c zN7b9ebmIw@ukRcY9*|N`zOXTK6y9E@It&WvTxo3sz;+>Y*O!W$D&(u#< zzQj*Ne2qxH^Fl?QjUGXWcFMS$C?>a;L@Lwug=DIHqKTM`^ua{r-QHaR-FhX01;Z)~nb4#B$3(ykMD3CRms2wB5}<{jBg)Z&o=j?0yXURTXK=Vkyb!ckEjQ8f9HKG54^D3RMmv_MzR5%3Ip?0z&gvE98rhU;X zH%3^*u+kBPoLbpZ0^4{p)mD*Luo;t!P=O0p%UMi8mOoo=?|#dJFK!2*_oH#X6IqPJ z`pol#3UPUSVezwG(mA`{pJ~cpS|Y%|ggtrTdXnC)cyF#C2K}4q`drmXqNq0-6rZL3 z4(sY@9cY`1t-tHCx%d96=R5~PaQpn->=tSgsWYbGZD#P8T>B(xkV12A0u|IzkN!by z+Z9y8;Mm&lhZ}XB24b`1U;10yu+2crG)KFgK@cKf%otj5{47brL8KrmUY20NmKq^* zD}M*tm`G=`c?{8kwVWnD@{Y6!I@c1+#Oxj%8B$(&^i!#lBZ~29?_MiK<;E%AH0v)f z;5>YDwI|YdpcWcbree-}SIZoBk?X<>-cVG~&sG(Y{(aN`o_@l+V-Ink+2e5^fgbu1EoiM-xY;c(5OAUaX;n9#2`|sN{zv!fa!#BwTJV4u ztF$#X!{mJk!%P0WyFBmP_=nvz0$CMSz}eAr8j(O7;J;Chu-vmP{qNZR&XnrUmdpPo zT9I%LiH#rmrmiEHUJQ_y>PV-Ph6_ff#VOKPdc?Z6y(4J7x zdD9gpy&p)nM&<;&8@I>L+-KlB)KZny%NM3(_SJBna1vT@8?T|Hi_nqZYm2Y=+L&9T z#p(AA2%pEt)IBR?mQXGTFOOz{$;r#%FRXl05zC#~0X_`Ao3Ic^Q67tCp1VDT@V_n`Zg z6Pmzc%9;PO4F^RPB6aTDqnV>2D&+6<_LVvvqoRA6$7LM@RzZKflLa;Ue`H<^g+TG# z_6V?2tpP(X+2#8);)6g<=ouNm(IUU%{S?hnu3rs1dK78Q$#oM~+BpQU|d zAY2q^wZ*?r{q! z##b0Azo#i?2rQpbjo{uj!0|zU&(;;Mdw{45G*NGW&J~SNaMGN z(en_(@tqt&C6F4(4KpNs7yLNeanmi@@~x^JIIgN}!-t=WCzo;C6JP>R)9bVj8W?bJ zZOcdYirR)6EySes@cXl_xopUomO$EmilN{RoQethdVA zbA*GM+KNhW{fQj2V8{z5IhjI4`TeZx)E6*za>RM~vDe*(>RpKf(tPVaLGsurD~ofi zePrJ1a6^Mj!)j>})XPOs3Kyxzb*#keyA<;q@)t9l;RDw9hYv(0ENagsVZwU7V{O|_ zktV!FXx;Z%qn2kWQI0tbG0Zo+gt*$u!rN~!e7OINF6t!ua2w2HlQ}{FfbZ%>n8`ve zybS7QWQ8wq?y@I8+$@<=x;n&Vz7K4!zV1orw9z{|-09I4+jB0}J?C zvhx_u>$C0UN#HId`;hVvihg`^Tl+MNPRE1azCd41k)+a4kx33xIR3la+^2sff#$pn zKId6oXKXqIW(s8r47w!9nzUmiuP>K5JzL|IVA)E#nacf*Ps*PIdkkHA=V}THP0={* zfM3GfKYtRrSZ7A9q;=#M!g3Xi_6^_y5+=}?WA=mB_qH6%A*+&wK%2%$FyigwLlIbB^7=H6TB9J6E&$_WI$TX(b0*F#Y}apK4@eQv9hInA{D) z9v0jO<>iVmO%GEGLNj4_Lw9d}D=Ue}&w4-_7Qgkn7K6=70i2b=#=!OJv5?ic;%m_K zj7#wTXY(zY;D%s)F%()O*Dez~qKAxS zH98H<5D%-`8qw^&E* z@5z@O!C+#aJm&L^-5Vxf$L(GZcyp(hN%Gri0mRS$qeXqe0q0ZpYrhAWcPMNm00Ra>&OxX z!zb)Pi*(@*^`0~D7iCc0M2q8A++Ur5@qF=LbWTE1amj6VMR)TdZaNE-JA_>+N`w+c z${im+Mi32&B|;B(=Bre$tpt{diwXu2?^f%xIGXG5$lVAVETT|Ly87N3ze30S)bAL&j$C~hy!@j zBA{xet}=`r5eNmYo5Ab%!D9a9_b>MO^U~4& zGoD!3XFh`N6}OD*Sa=PFoBu<=;jKU3&bpwd=@s`HIf3Yr<@B554#tdlN@PlA7h8Cz z5G^cJ5#wH=c8ZG2#LqV!_OL2p+y{R}ESsPO3k_vWe|zRblZIz#bwhzr=g@}I0+imB z2)o$xjA_nUfVs`qUg(9eZwHmi6$HVN?oKz3KG<50s?^oKG>nG?^$yf`5OJo%6G>4_ zEIo1|N|EaRvZW`ya-rwUJQg66End%+d)gIWU{iE9hFmQb{^7?&-zj>m#eBr=?y?L~ z)xNL)FVBPbZgjB^7q3Xuv$zWdZHlvu&mQYFU$;E8Ad;wi^csZSO`2t$vaj7|Fe_@7^5;vZ9m-&;;PclXa`c(T1o^Qs+AWgu zkZ0)YK09YT`G~-;c`sD`tae8{T9-MQC-;dDG5@6)y<0UNx3@p3(2!kc=<&FhAw9F- zm`Molq(r~7Fu6xvyqRu8lxw%JkX(ze-|0(X97?$E(K}FpS@_r=5MTDIRct6coBv& zEypVGO*S6>t^)B}74Rvqbkr1}ne-K1vs3P``}oQpPtyR`;zlaH8K&Fwo|})x&z|$u0`&3e$=CeK!arf< z-u2X@FF4vv{T;fk*eQf|y;N|&N0P6-{Z@?dd>Y+nCNC*VdREhMS_*GaQ_oIwL@Ul{xMW4pS@>D3mo6w{#UZa9EMPOP zvx{`0*90h~M)Bm^nG|_QP4!qK>kk#o!~Erj*NYdx8tT>WUWtKocl#1A2eN^I)Ccfe z3@jY*6DZZMW+6{LRuP|8JQYG4c>|Tu`OU{*66+8VZbZ+T8+SJPYa!W=m{Aik*s(Rt1#b%6@&G`EG26|+dNy&9~8EVmF0 zvZjKn0)FyFT+J*8Z+s$m+u^GN(183!e7@=GvD%p<1z2Gt3k2nSf*$vi>-+B*81{-} zYQ%{*eY~B?X+5NSxOf#=uF0x%6l_FNlk?Im3ttJ zO7;B#hLzo5>~W8IOiZSzK2P&(!_}a)>yPFApt0`GxMZBUwArY5C1JCFZ|V5r-rJCv zUP7H(Ac&%u=(%i&7quTZK`(+^2p*>0IC53vIdaN4$*^Mec;1}Nc!9;rG+(^m0vGb( zj+HvbW*9`UXpVZ%hS-s(#egI`0;`Z=M+u|ZIdUreCYzhsUDA5wb z11cIMbnYdYUReL6{_>IGMl3W!?l9yYfuJg~E?1SAd<)2*NN0+q&rY_|>+eCn5l3=! z{*|7I+YcCTA*O30W3JmWm0}X!K|stxAuJ2tc-W6D2Qfz7&}qSU!^XO$Sj!fR^t=(x zRW6|m!B*KL=Edbk$0}?WU-CbUx@y(b)Uwy`kuq&y(Q?-DO^T7UNDO<=UZS>TNX(k5 z1XfkCG?}~aiRF>(2B-4P4Z#kkR`sfc3wvAB*I9H`RgtkKsB2SkneMl!pRC(hiuJ|+ z{is;!8Knee7}qR!Att@*?wo0v|2E&m(CI^H*=RC4CU{xoJ0Z7-J1Czi9(OuOW zq-*zInI-FIUy3#$?&n=*PqXUxzNe#inpCL*9)ii$Df}h<`F6amxY#>YO}dWZMI_*W zI*#M5fZ`Q_TJ5BaKjUTVj_vpJu{Sl#N}4sPSFzOZ)P)5PT3WCQHD>^~zhoK9W||Ze zyQ4+QkXqtQ7Fd$ZEp9$Zxs}7~VlqXk>NN117^%a~L4W?0D#l@e4!UYE##z>Amw4&b zl{5X7Nw8yQye}bKKYTLNca0Q!K73kV#vVs&SY{!Ogw%E$L>j4hlB^QdyR5kpQI=Hp zw~CE~;>>2PX4u9|5EbCRDp^;(9A4nr_!=e1M{D|Q7bP#69V|vap|2z7peJD=y3=^F z2t^SdoQOyHwo;dcBT27o4P_U3?j$&IJ_ljjC(dxQeBKAaPF%|;v$op(zdgG5 zh43Nt^De#G?D1z}5TN*IV~fOMDi#yAPHG zh=r$8z6_PVqRa^%-|wH^eDEQ1>D8<6A7|J5B zrbw)TpYj?f@PwHl;n@nc$J3wzX%V5ebhJ)VwkAGbM-d9G$BZ9S?_{ z>oZn{T#@6wZ-*1!eB_Wq;p|6nw$|Zow$}cdU%+wmK0xWUeIeGf!u8*|hTlWZxzc~_ zhfiu72-*#luChVjBv!`)#?=|t`#8tZ)1B%k`|)Cn5^|jf57a&EJ4L2H=?$G0CtbW5 zk31D}F-OM;y$0f4O>MztQkG#tFQB(`Jn!VXQ*_}qpz-v6zs<^>jbf6J21e*eo)$Zy zq}#kqn3hSS?mBx!u-1t`$qro|8K6tz0h85YAH#|NAn0q?yLPo`$e+xbyrALO5I(JJ zS_y7Usca3jeK;)eDFX^&n4mt=V|pBoMVTwW&Hb_-rh994pZt*xmk^Ij|GTR{gy$tT z6@Xw7C9N?3W2jJvqWz{9qF6^s-rd?*-7NSbMM#V&yt25(Iuw-5ntZqdj9OAFkWmKR zy;Q|*?bWSX;(uFS^V=xdXxg!?o1e= zaB@lQ=~qAJ17PjfM`Y1=;k1**)fmA*P1P?vbOz*6i>NF}`144T$-EzbJjGi8T##Z= zpMKVqa>3)=%0YDd!S^55y$8aCGHDS)tMTAsrfIL+Wr6`fQibUKq#QI{{i(W+OWteSK!Pj(*Sw1BEptP=e-@B^Ev)WR&xyA|7X=T~hGJnDTI z9zUtu9QfESVb8CmPK_E$W<{FrO-VO1J?MWZL*Rn;RUxru_d2E}j-fXsIh=Fr=ld{xJ(pi{u%Ng;n^5^T z?r2PV{9+KGI^7=Q6<=RgRaGT!^=Ws5;peEc`(S4A=l$}(D;}0_nyn}aF4%-|E7x?= zWnSqfiq_b=kSWoIW)t>amJ3^=(|-pQK7tbu6<&YPd*PIfCPwGP_~e0!mPmD|`dy+gkYG;@tCQqEG))O^y{d$+?Rp{n?jWD2+)0rB)FBnGLzZxiOS;+WT$w-_Sm#NMcx&$AwQ_DC_ z+z*S7olDk*81uvi!AwweaBhkXx;=H`J=cZXj}&M+a6W*h@}8O6i>P~Pt}-=sq7PKT zOQUaRu{YUnu@2=6(*zt-0xE^$d%37v@`T%5?5{_%Ipp!tEWYTshw;tSY>zmfBuW9n z0yfDQh7zwH0Qf$E2X@?1ne_dU0^N}c|1yHwo?v0lL11QGpLt}sOFRgT15%|h5jfe+ zkSn#xU}g29uV9&PJ=_N56}iqj^3p={U7Rl5Y^+R)v3jyhxhX`9r^0N#)^d<;lT}?+ zJwU-Ked1J>YD-JqPnX{R-Qxa)Ln7}e4%;VkLb|Ntf0)!jx7oY-69?;U8#aWKxhJJ-# zE|?0Yn0sLZE!qnsm4S{pm`5A16*tx?L!r`T_lTUU!oCgn5o|^rCgT)XC|Py{${UAr zWX9(d=fA%PzhO>y1W2@YXC7_#ajtqJp0Mutb-x_J5kFP@+5DS>X6l@jN1CS=QDdWn z{pRZN;{zbzd#piCd}izkioWivT}S*k&F=$x&US8}B{6u&Y78d@%ZD=?c-F?`XbH=Y zy8@AW|715_J-0&MKMk7bNa^yjqyaBiTM)ILsl2etp%q3PSIJg5j~`S{J!!`ijzbkG z-@R1eep6d0x98jazXkG`*jQT)@AaAHncIQ|vJUpqdk`{3rhzc%c+@n#&Ngu4W0klf zPNezltY!g6;AJOt>6CCvz|LA-2yP7=mt6yF9SN7j1B@YpGD%sJ4>Zwgu11LP&V5x| z=gc@qJzDXXiBjk_v3;I`exP^jK@W4Kuk0(D2kkc3@#-oiDu?-syBYUlfgl@rm5lAP ziPk`SuYK#@jgzAAnw+a`tvF(gQdWs7;vghqFd?10dtK4a|Pe!A^suIWHOm*l1eY z{}h6W4UuktVfK`)sP|&8TG?CK*s%JYb@M0*+PuJ{sGbT8Sar;0Kxh>n?lkC*D}XL# zNDL!^cmoQvG2G&?Vdye<)d?Z{Pftk27 z26{6iD-Ls_U2E7~QchsQ{QH%09D#DO2hrpE>~=IV?oOuG#{MZ#Snv~Ct^z4(CS$m) zzSL;lr8Ip$xAV>8Cl7w7eg+)Uz6WsSYpNXPbWsCx*8gsgQv`UH-EsqoC6o00a`*{O z6SE0oqF^u_TzKxRtv_ z46M&Zd#3;QG1Oq-KqdCxTu1RCD&Y-g70*{Le^?>_`V^ z@9ozGON99&7%9-40e$g?Bh-+mqq`5&ru1EFK7F$uWWja%!ReVGnjHG^%Ysw)sRcn- zm@x^=$r;NQ9FtF!>AwT0a{PdfQB0-lrE1o9=%~+>TW++nOu&^R1dz*l-3d{BXKJCm zVUG0M?@APtOe1+T*E%_vho&xPdYm0Cf)Pe8uy)P>!4Y;I&eLh0>WfI^{Q#KpGgkY2 z2w9n=qj}lUw*x(XEqML&Y9Vi?phs5yU{*ySINBIKKH44=*nXS-UEPI{O2Z#oqTvZw z_(>i4EC8lHF=m%Tw>La+V&nrnAqt>xub2#*$jr@j4BZ?gAY=zu-le*0<{xc2||_t0*f zr5eB`y*&&=R7lDSw|W-4{~me=hvn7|Nz@3kOO~L;K5qCPf$!Cs+?t&PaCgSYmx=#> zUYv@^+z}$09YG^(FlJJZdZ(ZN+lGfxOnEFbXi;BBR@Y#Cg2B?82?3OlXVFOr0-RI* z;MX_C{UjG>#*vS1l!OI<{bk|N*#T(!>Mqb}r;Q*Z74>#jyRx0`_p&hkT5FGI({Z4U ze&1{G;f7DMrzkV1pM&Ym=Ngerpy+7SqX<^X3O}Lc`?)B(5X;L*N!S>;vk*^gO15C2 zTx90ed*6)4EVz1?obwIE28~>Ah1Yw`WawmYJ5+S^@^-&C+l6Y-42P`TY{!^v3`FFbgNYxkd3P+ycA+2>_${#SO}L!kO&A8$DaTQ^q5W+EHWKz#irb^T``MLu(sV!MoHs#$dd~b+N=kjP71R~m zfvzsEeqNFyB!}<^cTuwab)#hZQsD8?u2nw_*)awTB&4qVa?@qEE2b*0H6MHug>U~= zzjh7V*%D1Cm$V*c;-G;L4^Lq!E6u&fG!t4o@hQQ2fO z+(Ygl!=1Yyps?Mjc*&&O9cpjFVKXI`xS8QXRw@DNkiCa3FXXC z2>QDNA9-mVFgqGn)-%76$@tmWa*O=mql-)Sy-pkDL%NPO-i1r{2c&?@KQM^v8y+y* zFG*cXhalo+;L-f!4I=2E$Dlhb2UYg(b4{OD%yJtQWr7J!p?~Md!&*2zK4FV^gtXrY zz}`e)JiJeZ6?2BdaS9cEp{WU!6bH*y4%yX*4rT*0+c0<0b01`IH68>@WsnG3x(?-Z zJ+r)c+T5}@iPz!X|MuPu-jIzg(q{kMKG~=pI2(Kt_td?>u!k~7;8wDt-l_lnTy_YuYQEoARbBe(Af>ADz$cek zvR;>Lm7oEw1P}v=y#wzLHJKyOmh|)+69Ro-VA<|MRU4uxcNT&?lC^ZO((%qnR zgY>z1-sgSKIp1}Cf8piuo8O&#uf5jVgsQ7PB_^aJ#KOWNex@j=iG>A4V_`v9Z{UId zq1}V5U}5=VJ(H8s@-W^=BWP4!zUoqIL2p}f7*sRg`?w+YpfZf}f&BL}?HuiASp!)T zniERlC4cYk>MF8QK2WMI4i&D<{C(A!u^Zu%k>uSsB_?qEBW=5D{fz&2>hDxhm#tox zncrt`GPXze<(Oj>?~#Z8-+r)fJ$^pvSIO|1E4sQ-(jw{5J}>RRzyGlW`aJpw`b9r~ z{vZgM{ALE>v~StRggi0oaj#UdDbMQQ=t~gxtL=Wvc3~$4Zzy!oZ6)$AkuLf73)ttO z(z{=%^N&@VI=SL&JaP_$MkXg5Y>J{x@eN9CPP8j{Ql<^+OqTh*uHK|${qHdusQ7-` z-q?dG!B*9m4RxDed0V~Y?3&6Cf3OiHPw5oH%gK#fpK$PU{5!3%lp8GULw^<(E+)^% ztTKr5lFD`L418Yf2P9WDNqf9)E&lI-a?zh~5ch-*pNL-D#(`sjeL#6C|szE3vI8hF01fMEBPtn_vUk{vA57CXcFGU$hv`Jk#M#?7Y~`h ze@9Plsqdk%Kk8Yn+E6W3eIZ8NemSP#3Lor{E;eDhIEY!RE=;k#c(SexLH2Cx`z}-M zCt?NB=v|LBYb;+n0BUgP_gq#5r3X}@iq&%zO!B`uD~iKm1WB_q|R<)(daySyPN>gzMczD|y! z3T2K>5R;Dobg`)aW^#duM(`c%%(W9{SLM+E*ma*&q)5k3U;ZW-gw&$d#pTI#>_7X+ z{^Ea+3Y*kzEw9=B5ucN_sszuyJZ2uYcFhP`uukE!5!TIk;;i5&Ddejq8~lHzB){PCgm@}wT}=33D-x#{4N9@!_M#7 zO^VK*dR#r8&?osCB2Wb0WPQbWc)s#myFq)CJ%o(<<$6Tf;2_ab9MwOQv-@|1=P)J4 zQFLF6!(|-NmvSh)216&?_)4g) zHVRsmwGr!ItVo&EI0Zp#>zCM8jpL4a1Z)(mRA}wz^bNkJNtHZ2;7j)}W-mwY5PIA) zZ~KE|Gspf@V+VC>i-@ct!FGp$~3F3+eMpzlB8Wh0;USLuJ#7unlWp%zS9gxYh;9JOsr zX(4BkMRY%2<|lI@bM?#Y(%2NLNB-zzA9_;mE-Bm(Yxx@m(ZSN0AIMQkSe3Z2+GB#>@Z!mkemx&kpCfkdRSiK8LIkUGy z7w$vG+a?;^%gpmv^D=y2iR66zgQ_KY{Wq)apB=7SBq$j_Pg$`u3hBFv;U2G-b4?r3 zPCNOPR5-q1Rk(c2)yH>ktk*K^lfzw5^W95xT#3?T*9bq$zd%zZMHu;dIZl^xs@B=! z#+%TN5xkqUJ9a(sTs%8aipRS_N+AL4&EzNv&I>_;;(Q{W#-Gz4HNEBoX?k60MPFq% zJjhvQmBKKKe_FPaGVp#+l=RD=Gqx_sM_5@XbwpjrXh^HdaD30nW`eh?L%#%h=soWh zXyEnXi4LX7$rHjvExp}z@2#Z6jf(yt=>)xv%{2EJ(Vw56M!Pq*V%wRiHKMaTl%$Wo z;2^NcQN%nv?*7FDJU?sV@xY~S{t>8xjh;o^L=TRrzSz7PH5N*r)vMC;WhaS0&{w4m zu*++HwWfD5qb>eGjU%jV1Ba)vJf|w{&3Z}A<=(h;M&R`uk>hB~LX#HXltWjkUql|3 zCrw0{uz!{uyiieExbgZ%PA%DEfz}R5=^5TqXtlrh`#%tDZ)SP;mL8MHj4)v>S z`&Yj+{L-z&1g37&Hn2^{{BCZ=*`)ZkW^@@;L_?@DM>#C~kff$$gjH*(@~uZPD9 z{_jjeQl9f6UDsNSt~Lc>4F!>Fm07U`7|RYssdGr(A zLodj7#MDo@UCJ3L*_Sss^0PN1W}3Ws#EuX1%&s%R_@|Qk%j;$^4dKk5{u}-y)UbISbOg)*iSXPrDaUsEPC8h+l1A zU8<#dt|Wau(ks#_8PYZJiOXf^*^qME&=a!irFA{u?aC9)5Sj5{QSq*{=pso^)t+he zRA~_R+{^FbX)%zbR~oh9YA+q@wc;w)%=axZGC^7p&s8!S1jw#kskCS)A!;u z*DpiD+s#RW;^lVTZ^prvC`O5i;vOU{{P52&Y*a~JNh-}w#D9-k7&T%yN~g?tdSkH8 z#TpwGEqR*%c=_Xt-g*OvI#!i4_ZiQp&Q0OeT!mYW`>KZv;XH-luq0LIJdfkQDuY+B zjrk5_KU+(*h|-V`qtpNz8-lWZ4jhecSSKo(!?KiF?tt^N{tX{ABcg|OR17NQ z-fg(_OIV-&Jf8KFLeP&?+PoMph70UJmO$mG-Cvp;)-};KsJ15%#jA62j`(Q>0@2!} zV~a|~#bUISj@0?iyA!|jzq@A9w|K;G(8P_>FY#l=a1rvmvHlxo@y0#AlM8u2Xoh*a`#rYMP(O#Bb5d>lP+GS>w+TmCK( zEy|Z@7sV6Ym8M3NgWrLvc&|fh*9wc?t}}Z5xm!UJU2FnQ7XMtYFl4-P?-dP(*@3gY zO#A1^M&+nlim8RwZhi7jfJ#g-+24}kHJui%TJ$$AV=VLT2i=j%_nyDUf-kh5%xI5} zi2s6lkHD>yVtCz~gi>KgRYd3p_iY^-qt`Lcim7fBHiggQ9u|7+F65fjoc)~5aQa5j z36aIft`6i3|9Z;AaIk0IDAhI3*uU$HuKoSbQsj9DG~=QyaTKL>D47T_j5>m_vr!Yj z0w^wFJ~``iT1D56SpKflZNDqKc7hyy+7feN=+IaA({> zX8f&v+GE$$c*u?=y|G165HWqSs{=cB{d^ET4x$ay;{yxdP|47%7Eo@`3+<5zg`)2)msla54ppE%NG%epZPJty#Rcd7}4F7HaW!1FD zfp_Tbeq{xYt3JX;!+I!cIU0-Y+m!rw7RX7%gCC{d2*_;mx7YWqqd?pep=IlGTC~n} zPO*JbBr$+6i`^DVWOOnUO0Ci#T#FXSP2($Dg0q&5oQdo~W9>sCW1XNH^e*Ur5~9nSaS!jGCx*NO%!A*Q$ISt9(G1BqyY-jmPyV;OGp!zQcj zMp4H~?*W7)e+cq=7#^Y|_)t;jvjXv8I<0QJiQk3mZ$${7S;Qta!uxQI>Q%9mmD%81 z&I%W!662-``wCdkd+c~M$rD7LrL@aR?=u&B4Qb;oTzI=m=gQ2z7*8%F7oj%CP*G=_ zP`V>;`PZ%{skJ6sOzPc+pkAiE;LEGuGgs>u$m!8F)e^xk1H6$%X|87iP0}ZDa|%}X z>^~uNElypi1RDF^;sip(v65KGcmp?QAkGUp2lAmoD79pponPd<#Edu0VXIWp+RPZ@Wz)M2_-K` z|3h`}`pd1T#Rjv@B9I-?W$hBrL5jB007 za%;|GYpU++7va=9m%=`$2e(jEIk`9pQVu$l{E|zKgixbVOmrOb^}Ux@mlswZA@SwJkTeBhzdZMXx%Y_1KdoPYrp8LKKGh^TEr!~*L#Ja@t)h=g+zudhh~F535Y z{xGS<@n4zvwFs1Zpg1R=TBON&pk ze`P(%+J{+lRw#$^unIuBz8WZf#o=(c%+{JO@SJN6SPQ^sR0q(hdG(|H_abnk@FoWd z#`ir}a}pwGj;7sbg=}i{`~a-Qn^Yh|w_F^h6dKl{;r(@Q_PX!q##*v*W`rI>(KgFD z+!(sPL_UiUCIsAVGDPkdyCy1<+|~sLLw@Ai#o&%}=4Q9Fee^rRRfd|(@?MlyWVXrD zWox^kpQ`>I%HSz}l1oTz)n|{X`!88w9M5lqFdUCN&XRQamf0$L;v3ZWGu+7kf-C5?>2g4?w>K@;95+_GJ9Q0w1mU#PN_#9OVJ+B}%O;{tBw z-AVK$4nm$F4kXCU=>`!5zxJauuv$|_D!-ruI!%Wo2DZ!JI`EuHM|TBl@qg}RvAR;OE)zLD~VTNKu~mLLSKAifdSM2KM<`OnhWOTWkEea)oCk|gx?%$Qd19?#t0-Nh$I-2`le7zz{>N`>4~ z=twZB&wnG8*zT#S-lJmY;8GQF0xrece`9z1T7ro$U#r*IW=)FIJB`l@@{}()zWe@X zX_#pcCj903pZE&Lk>wFF!_{g`+f{rOB9%w4ej>{LyC59o@@#6-I?}?=mfmvqIHaUz zqV{_~ZvM4Be~ZNK>c0s5{)+vnC6}T+7!j-1E)-s<&DW4Ie$e~&w_iNzokykv&qL+9 z|NRO|XhSuY2XUzQxY$Q~E|ZHV1!F8Q)4QJL4_OtCk2mf3>1iy1e2lI?!d zbz}<@!a%?Huj`7nXnq!n(y1wHFfyu|e<<|w0w(loQSos1D0;Ze@7#7koZx5Jhi8C* z@VEcKjzi``gyEi&JkG%t^NP-BU{qI88z)3(Yi9o;j=NJb&MaWhQuV1p%}XKY>8lSf z;^Qr!55KzeJ);5X^5J^*3iSdw)x$ffdo?MjwCSCkQ z75YKue{YMWN7O`RwD>I521;qW9IHJYCqY|h__$%b2xryDV+N|Wst<1RluG(t^F=Hj zP{i)H4|7+mu4+YYDU$`lQq>wr;cC9C2D0^aB_7T-i9qk1v)9FyKst%3|?# zOCK%cP9C>Znx1`3`0XeqlEz`J6auxxQv(Wp_0+t!4Q=_7rOjxf!V z<(>r6-14m0+LM)(Hl3ENpu@f8p6Oxu2uL8-kC`;K;;-XG$~{6z`#lJp_={b>!qLQi zv1s>6g->^g&|C)9T0*u%yk&JyL7}Nn#jf7^kR+$XWU^#e6i@oYoT>KTuWtA8@@ zzBL7(2GzmZR>QUq!{gVyQm=g*C##V})w5{J@Q1pksa^-ap87oPuD`L-pCVFrIv>n5 zrIKa%-#Y^}C&7ou3frCMP3qT83KZPIM`N+iXm8cjOuY(+9}m4yE4Z%pSe4>&CN&le zGs+&w|9Iu~3Ac5pGm^fqUb{%A;9DROJw8cKTQI5abuo3U82{`F+|g)nsb`_Ph0+b~N`0OeycHGcLlVMH~W$jNj8h`)`Er*Q9PJrBHEL ziebEh6>b={t(rqz26I)`D*7drDtL@vOpMcx9Z1LX;#~QvBnxUJ7`_ViRH<{lBVGw_ za6@8FSifDzG;JN}_}BV_BWg<6IsO}MCXyS%Li#6X&s{G%*V}^Vr&`v0DYD24bmQ+E zLw^sZa0WfC)+y0n5t^Av60lAt!NRf{$@gpVIXfyi+5erQ$1GmlOX(^fajW2k{l+c% zn{FFpX6bK5x4<39s&<%O+hY4JzlVdsMa0T=L($Hf0H~~}HFe09IX$RgQ%f)QI$X<9 zmAZJX-RR*QyD6Pf<^}R`?-7`Xcih#Z_nd~Wf61>19kcr&82zZ0RB zzJvBsY=_w$cJpN9&(M425s3UbdLnYT-!GL%lv`Tbd}_PT!us<sleM2c0Q`xUco+rP>8^Sr z61WVk{6E&}Kfckf{Og)dtMs|LIDXfKh3Lk`#B!(g0&e3j<2YsPe=ajQs_z6AP7~j) zf9ZN&dT>IAPtyp}g z!RC^N&wQItU1Gz9H6hvJeJcR#{-Ij#t^ga&mJ@0+Z;rS<@`=k?&X)_|*~;ZEM_dfQ zz>tJgXp9QOzo`r|o=S>-q)t0;fu`;Oj8k19ydt+Q1M72fo6NVpkXtMfi>%}*R^fPW z=DSXu6yZJIe4@#{5?h|_ZU644+u6}(Vb>aC65e>htg3d&N|k2GXpQh0_la+40U>qC zPOb0X`Cu#Im(%sG@6?r|B#NA1>ogR7f7El8ld?+dR_F%f^Yl5S<9~F=`P;Ako1h6W zxwvqvjr)WP%((E@D$ShdE0;3%_JGhEu6172I$RrmCr@#shGh{8S^s*K{1)azPNrIh znGTllwjmsQlRe|?J3ZTK;2EPvEk79jXPtYNVPZA|*$Z^C$D&`7Z=bDR)3Xy2 z&Fs#A9DQrAjZ^`Vu6{Ga_tfUb>(Gvw+8<3`hx!F&-ag3XN~&G3`@32oEb;o|a?s?v zNmVP+AV@Fi6Hi(ej~Q&|h5`z|w&N9cTdQalX_pKjxI9*htcM(1E~qsEd3-r)nE)JehbymAkWml&iz?%IX;FP)+-yn2BMV6VYHrF+Y0ZV`+i5zjLi5m% zn=EpzD>)tEO5O`EOX!5{Uw$J!r)o`XRhW^OnDIT^{Cc<=P+StI!l(}tbOID625Pi; zvsS@}DSQ?RV#l>v?a!r0+7bNOeLvkU-kj{Y)-8l_9PxU7$K@#>8=tCkAwAd_cS&fT z*#!KwJpEk-+$ug~0r{Yuh=!)?hy= z#6FR~ib2>_-O=x|dZNkOy}g5s%vg(``cJfJv0k}3+mwI(Fee4?cE5tOcM4B6qWc5e zkUu<)lL@FVYk)Tvsk0Cz=~{jSxMkw43`Wd^xL@{4mO?fA@pmN%YM5!Cow%aN=uzai zd&Mw(_6`|p({I=z_rDa=U=`|sOtEJ=-G9ZxOV5-dVErS&xXEjCaP&mMr-|M(;4gx0 zif=b6m?(x_@;f1hSr(GWDr)(Qa@a=Y{vr}tQ<+wOyzV^=5AP>j52zZs>^fQt#Z^n3 z+fg*PXtSCB7HA79?X~m$evt|M+q^uLXBan)nPP= zGJe-Z*w&xHy#DQasaZ8n>#V)P6`jRXXNK+C#V84&jExzA^KNkH>QJ<)g&K5PHI}tUDS}DAnDn?RLhbLqjM}){K&AUiG#52 zO>}O=8@Moo9fknqK=jE267&rxXlCL|xl}7+q)Mgh_t^XWIiP0rSsqa0na=#=mVw8+ zmmX&M?LcU1w8{IpDw0mf>j99dBn}RN){Umx*-;-L5?5AyQ_S8RhKpe~1u29>w^Zx% z?wew9=106h&fM(Gwxp6+>GEs8GSnVt+ujKBR) zj-D^VvCWARCNB&uc(4p;USc<%zFaTbBt+`2+*|huJKl-hY0PH*p!sZrpFBAZjPqlwJw>EV0`ewosz?wwTJf;_7@q zx}Y{NA)Z!0rT6wvT+fzkf(5yjzXu{gPY?CjSFWUS0SdgjcCxXuvpg zf|9Dm)<&$4Xh{q?huaw1J`iSUZ+O3yW;Bx0KsmQ)4cFW}X-d1DNV@nvWeE9a51{CN zq+iYf|nRgSXcA4nTJKUDr`niga5k{ zA1Vz*6d~gLtDt}pr}&3vxW0d(s9Lk%kG#!hqK}*Zu2Ne@TGptL@RwRNeu`h*Gxo5C z=$l)2J3bHN77w9qn>UY1YO*qvDrFg^@Lvx2dMP2F)y^IdBg%vpwzmM1X>iEX_={;k zvV?c_1KJ(H+b3xmyr;bZ%0d<6umH{h|HmRXD}(e1-&6hl8kZs@f+Ujj_{8h*NAz2I z^5q4nzRPq+^xP&971vtz;$vuHs6Xt?{osnL#F+%V`>K9CIL6~@Q!Z;Kj0!_eL)2Po z(vrT$xCT;;W?t&6um_s{+NFkYpdJh^*e$hcS}>HIRG3 zrSh@7aR_I8hPyJTe2P(L?sx@a94O|x_FAXLVVceGRW~dB^hY`KTa&YZvb+J!i#BNLVhMpj|Bu`-jmf}}|%fF6--YdG_X&;(FPscW+>ExYHr zg$j{$RK-p@RkqshF7*rZZ-Ys~WDwc&ZNd0V>H`(Ki(M(zYT~=^;WJ;%o=m*EBlG?f zke=M9<{iGPQ+AoQ^!n!Ue@J)>D}q${;|))n%?&%&iGoulNM^Ud(ev@a3w`V{1Hj33 zlsN*XXT^1WguyAcJzU;uN+6!g;HXRDc&efbpdbT-YleyFrom#t@~6AEcvCELIz7Cr zE{cqWoST3fLc)>?vD-dyw=Y$6(8KKF3!(bKnzrV}(WJ)OfRYlvM8(K;wtHv;srcn( z1=h6?s4ZoCD}8p)yEHx5FVD7hLFO%geER2eobNZ0%oJPb+)2tF?{2R^e`29U%=1~T zo9B|?)2&>=dQj1-Gyn}VWuSR}<8!nmKXSWaTXN71$N@hz_^Hc>H=cG>zP#3{lP@sI zx9mJ0+(0Y7TN^Z+6M9+qsJNB1T%M5Xp_T&nM%FDBg>(6g<+n+CE0H?_KFF)JiK=y0 z<4ii5nemT-aG{~IXs?;|Pcm*_8dUC)i-OF<|3>8zgmn$b&~<{SFzrIEXFfYJzQpJ& zjf^)RcyJKq0{!AIe0Do%*m_~fiEwep(}Q8K%u_0OGh+&M6IvAIm^Vj2m!Ft^EeF`s z^XXT~I0%cf)xo?`m-%7qI-z11al0*t%VyPR^BVwJ7%K~KI?U}%d{0<;&(wgtgxRz; z)6skcY(fzLhjfI8;a^`a?Ywj^+Z);GzFwkLPG-i_cExmu79jmHY|Kuk3yqSXpTchQ z>KsFg2A8zS=J-2DSz_`WJT4&%~6(WBO&6d17zcj?6 z2v6%v5s9ANDFbX~(FX1SVm$lw+WusmgbQ!XYb7u}0=J*ek%LjMMdCo6PsmOO3sHkS ziv}F-SmJZpn_0WxjoqhR@$?uymtsPWZu28TY_>aX^|!gy5%P!S6IFI8haKTGB3Iab zzOC4q_3qma)qq}6qvF*2*(kZ)xIcikcwIpNl+joHfmJE_>ZB3j^d;*8Zk1U_$x;m32+wEqObfHNq^u;t_TQajrS_)hGjG2HRq>TC59)UuJ^>?pI|p#A zedDNrh2Q^3X#hTHd<+~tLk-*1TC;u`PqFo9GP(3nx|?HPcO@*85^|?i&q67P=rRGA z_7>W3P#SGpBV-2#$Kn9Wqbr~u7WK~?UHFPk?oX5Z{bhUVd=mRLU$*wds% z+*e7~GJLl#iH~q`(Stmhkf!XOQDYSM*eQ$nQ2P_Cp~b+LO9sEPGH=%HFS^347MAkN z8aUrMF;I$|MJ)#dN_ce1f)7fB9VPX#jj;4t%E85oetfp^q0qb|46hRl=KfcV1=8#v zC1nR0$=6^Z#!w7aMp7aI9>?!C|LyQqR`mvslL(RcVk~91SFV6{D5Q66{ME=-34!Ih z9Ib=h6WI<3zGdWhacGr9hSh>4zm81hvk0}-D3e6!!6>@~BDu*Cj00O0(5KY7kh zc7_1Iyvtc}{&z9@%>Bh+o|;HT20j5oCVufm==C4<3SS@`+l)MA;Rytlk&};5$2Y=6 z88zI`^{3t*D1uz>*YbAamAh%g*5XU`n-pemxM!H|`!{fjMeKvP)i3EYtu~zQVuY#`y+XQu6f zucltgi!TBAZ!VtI%F?!d`ndoE*ZX5^nkd$3iXLvQ)4;rFVemu#^u8<>)@%A>+sL~P zKX%^|aq}YULY*1`m6Q0|ycK;oqJL|hkW!#B3O_Xh$HT^ml^n4v-jG4u_QE!f5u=(e zE;@!cZ)A0GO~b|;p;$L?wgpB@KtYS=G5r?~mScUHh7`BBYcdw@2{84k_XI!gH$t+X za*{6^1Mb_3eRkiTSrPjqt6SO09w}*DuW&_0WE$0p;r-@K@o>qZhh*{b@y7VRiH~Yk zRovmVY31s{E#u7e;~yFpP5o7e?lmB4^Ma$oFW0lg?EhVL!aSr!<1@PcN$=;Cekp}I ztZ?MS0TVG-7wsQh-;1Q1`8e@$pG-KS+MEL<#d;YYU_Pw+TRt8-5VRS%H@LD{GwUXT zD{s$%`a}CgqU!=WHAAO)V=d3B@ZS zoBJLCM=gu2o2dP{MIp2rjZboi7HuLP8SKV*U_acEY6^-REQH#i+glp;cgg(YL_@UO z1jzcqy`b7jIc5!7KtMng%tg6E%(3qAHh4HQF3WNPcJNoB^CJ3dsIglMpw1IXgve1H z6w3DZoRZV+rwRfEiO{8a!*9WL73+=GZI4U4>lpm?WTVucUJ`$|dzCK~*QZ(y(rg9yia(A8pO8Vvj)RUbB#rk82$7=tqOoLfwWF@I837Pc@ zwh;K9tp>8A_PHob{kkb}vEW;rjQRvzdtDXeYjRA_t0_+DPubA*W1Cv)*=2}(@6@?Z z&+SUpH^K9{f+{bmx40?y!yMODjIM*U7W~?5}rPiLHzV{MFZ`tIf|m>4Q~=Qpj@7wLPdy=7Jl!4SBXPXjIX9x4G)#`>Q2wmg#P$9+NBIolI|wpjXMJz zinTkQXsR_psN&M=&fI;Acz_qYD z*>t&+(t%scx*kT%klC{IDfP84=a~$38E5&QnrSzKojZ^49^kCf=;e}TZD+PvBn8`v zcLN+2`Rop#+YN-;sLod+<@#7kLx9;E`H9fN(VWulWL3DDScic$gzKB>0iz0$Q37h4 zT}&qW?unkmvwq%d4cmJ!F`V1`b0fkO2|HwRA1J6H?l();qsatQ{HWTz=XlKh^F})} z7t-=gTAFtq#@~R*KBLo&4 zQDzC)+P>d483Z0x&%!qAcassdN{^*%8YfI?v0HPu0sqP6o#;)6N086- zK=KhPo9;F~AUf!&=IUzYllFT)t1yd^)4$rK<(sFKM*I0#sQ^nexqNZ&TTUojXh9YQ z%WbJNrt-4cH?dvq-}pZfIYM?67}flbwi<|vn!Ka=J8l*0#+y}N`w;d&E3k-Dw)QV4 zm^efX>3XP4&%cqQg~krPe9FnmAi`*v*L&)z)-hlJ9-|Sn{!pKfmU` zL>du7X}Lec&l!jfepb*dBD#^k)3#({>e-4hQiPQ3KQR)DjjlHk7j;Mr$o1$&6h>A= z8HH@MoETyy;a%?@lh&2;dB*;AhmH9#*@-`*pq|^Z39x6z8w1?u&8f$ms*=iDj`C$`$0n7?d{O!GR|`3D zg_*Q4wR(yZinTZlm@02>$Z?1nZU<5S>?eOL-Esna<0-<~EBiH~fYVaZBaMQJmpQOu zqkXZ`8%gldcUqK__}QZ3dGDWkj8Mde<0sx3xLo9e9{hYl+F}1qw=kgCYsSu*eR)Jd zNGnV#L{8&D5iHzaJ$++UIaKCe%fkx&X?r}{yEi=OcIF102W|%wVUvZvN^Yctj052` zdTXd)kcs-?jc0d#1yXN3HKUd|i41^?SDcbjO%%=MTYu^%od|LqL zyn?jQCLS@}#})AhBwzUm&didYl{ZSIn>4m>{r(=2a|aW3XloOaRv2*P;GUv*@9|r6 z2-t*;bO~?er%D^tnctON9=~9_huX=2pS)i3piF$z`l8vxT)vx`M@YI_7MPBYWAsTg zGvCtfPP8jp-IESFs^9#YB_GaxK#s$p;cqXfp27tSAAjwiy<~Cwck6?^RP#*or&tvF zNnZ#KCVUk8y3VoL@&Qq7O3jLE_&VBH%7FG1xd@IKZU6YBzxPJ0#%_JFghD9f616&b=_29@f@n_#!QnPZmarI6>+bYT49CYT+M`?W(iM94V^Pi=e7H@M*K$ zYs@0-%cs3e`56B`@k>2hqVS@Spp=fD4*b z9IiQd1E57nCDvL5FblwxsAB>AKc~Z^jQw^aAQ^=I{<6ls?{>i2dSMBaX-6(tir#;Q zrX(%wEkC2nrpWu?$;XQ294yRAckJ)XG{N_lc!=ADk}HW8B(?sDoOl?`tmMC!&WoK4 zfVUURB>*lUO$cIGuPlM?x3XZ;BTw}I87CY0|-SRzceKFuRMQ7rSm_7Zq6HIMNdH601`h6$KS6E}=49DEe@P5%-E^mQ?`n~Pd%+zwU;?10n|BWZha{L0*}f9ONt#Mu=WY~p7K4rnnaa?bGBXix%pR9n z3a`wFytnd(#I`BcxQj=UV)L74DcrG*O7U~9Sw|!3oHA>c7V7%QWl9Hx0S-vYbRVMt zMc-So{upqykr!RwMTDg|1;FX>*+tfspVjHX>fw}y*EkOPfHZroe*cGb+iCuONze}$ZP)zAoCO={y z3LD;+jvK9HNgpPSkMZZUWExK}jJ{3qD2IWd`&PO^Jjh+^m0E0YV9d{OFrIarM1JiL za4rqukL7&fe(~pXv<|?2IjQ*t%yMx;MV3ABNp7H7;H47-G#lF?1!AW%jv<6F<>?Wy%JL02us>TDnbt9K`ih&2MYwtBZjpgE-Zcdxb`sWj z-GtXVe#QA#`J3nLm=E{kFC%7I0&(-R6sou{nhUSZ5__o)YHsxN`r;oO)-8Z30sv2Q z%lnv9F8%x}7*WVP*Xuqei)2O&)T>ujL0R8+FgFsew#@fFFI2dd+1QZdga05&e}VQr zn3B!YBbIIt1?ZiEIg4nT2be6UPq@?wrMQQdY;W&M8i2JR9)o@Xo=kaieN<6g8E}eE zIy9fGm|B)OEr{W?>;L^p`W!!uilaL9Vj8DJo~9VCnEq@s1meM$tu@|-(nn-sQd^yrv-fbGgC>(^C+s4Z%HL7$LK>Ix(DiJBOz(s2v?uMhVFE2-p z+|%IHs6IX8HUDDW3ah?FKx)-9^mEQ;0NXKLf5YtG%f--T_g6EXzb{;-oV$GT+_{z+ zInuvlA&%`*vNosc=6ilxWxo&L94`M$Jma-qa(D6zXdp@%sCW+$q%;cMx zTSy%@Y#+ycIte;l+LW7#eh*tp$>t{7)0MuZA>H0?xoY;hI2={++n8m8(Wec0l-1I$ z_i0)*3QQxxmW6|Id6lefik-eQDfL@l0KiYyUl<>kD6ec&lE_NLz z*+254SQ&MgOn?RAF@he?UZ00cVM_e7-07#U=We&_?%w$t>hmt=`T4zWViSt~^$dFhd*WlY=$3Gd z;zxOTC|Y!!<(f#D>EdDIDxV=mD{nBXP_LH*A}i^xrvvoY+YPRoDf1|q>4S*(B7rSL zNkrDPs=WXCl^|Jan|E zH0J)j70b>51!grR0}gj@wm4qY^1P18AZQqf@C^u_1kyO}JoO_kV0o(t#d{wb7d{uu z%RF-3pku{|C0YpYv`7KIYJmwvw19d0jaaV0%cP4j)gY<{aJGEN{d>^<_OCS;o6hOX zgA1&iV*j_t77t8Ea7PvAhs)&rIT`gz)qrAs6SfeD{uXzB}`gs?uF&mt~l`5c|-uuq?T@@8cZG7<@2Qvc5$RC5S$^_zh10l~8v0*D%S*$KmFsgc;y*vJowW5dCx*WC`0zwX2TP+wyuQH4;v z@eK@13LI5+cJe|C5^bI48V}#b$0$lu$GnRh6L26@R$TP>Q`U0Hzw4;H2mLTjX_Vc| zT>RCFp;hU7->?L!X`JhO{4v8CYJ}ZL@$L5(4%BZ*92Bk_6xJW%&%En5s}LmnJX&cp zNQSEFYTsX98R{$f$Jl0JuRJ!;B|;j$C2SA+Wv!NigKb~{`ODr4QR#g5-1z0Ii+b4E zN{VByXcQBoJ6%@s!pXVnv)nuT;*U2_9b(VVlS(Q(h;gx4 zGpxX&ju3hOq2f9ew{n_(_cjx@z854iLM^)!KHf3)h<7HK)<_omh(-#d*$Xl&bVctR zdAvDE^Zp0$W~AJe54uYb*_xsRb!(yhkX@p3)sZdy3J(41i?V!0FdA5`{P-E}KV~yN zVFmfWCA;)4HD==Wdj@$t3pIuP9q-vsCa;^MR?K2Y!M?}V|6w^FCkY8$7P$mO*TaF* z-7hNa@2+V5IVo&BxnMy5cop%13X$|tI`6w&B@2Oc6$3AGV}PZfgI;^NUO(an$HMd7 zH>jQ%djCE?yJ(w5)w=Rv?4Jj6iC+PDF9vQ@NmtN5mr^UZFuN0$dtZE9`T<$Lw}2;6 z=DnsUlT<0`=fxZ+>|B^qy>i(mpo!Xo<`^pmktU~aJpu>}nSdyAZ>igg;mQU3Fr3zW zVG|>iO!&_(Et(!3dv>!XB+fFnz!}}(Ru}mipOwYF;p+JUji8tRv#6U1qZOQn05cGc z)t`NYcK)J_!;l|=3Kx{-yt=vZ>8c`{506vpl@;8v=Zs@6SNOj-L|=l6G{N*q_FbG zr}`6tgWzlZsBt^RJRHT`SnhWAo`6C*2uC54meu?q@YZdj=3N~4wOvlp0mZOBZ9agE zJhZC2W`QGs+wBav`{}_J7C_NgzZ3{27b`*6Tch9AB|fHYLsplQSl#lyB>+>o1E0hy z9f`}hkUQyUWibPsuheoo!NjJ(B`JhjH+eb&CFIztLA?I%!_=C%Ki9Zd@E(P|ks?pI4N~C2a)dAGG=O5^#^`G{29K;JirL&3q zdqCBG>KGWL462H4mU5KVF8H_Fzfpd&(E?mPGwz^&Wj4Re-GYZ~M8*T(j8WVW{OJOX z{QnJu4l~h2|6DJt^Fp2x@D4j zCcoW`Va5KT#t6<_w4O5sACc4^1)wJXCllemQ8KZ$d_~-45dOPQr%-CzL3_II%8#IGj_VS(H>!M*p z61r!Q;dPDY8IrtJax!TJptg@4th}!|w*n>ul#zD~>vBKFjTgiL(3>+G( zc8A^bs{JMoB9+i4*VoA%UOrlTz44T9E}Yo%oloGHAqz6$BU9wiZ!@cNDfD zQ;eE^9Px|_gISIunHxlUscHrcOSGz+rU2I5SjmS>@4>ZEDIhg8yY0rMWBOaw@nMySrswMV~$iuBi5AMa`CSM;9x0nPj#49yKBwnGE znFXf5+{~h|{u#Z>(5%8e5{Ko7k_MArW_aywNTCt~dcN)3crCvIU2?fS_Y2gl5$gqD~=a~{1>C?GxUde zGP?IYT6L>L+I^HN{9I+ui z0fFFMAaE*eGgNv(FgyJ9_08TB-667q=F^jVni&$qm7lK8sxSnbdp`H#lX{coyO;XN z0|?bjEy_=0YG(Z;Yh{zXV%S&T{7yCV-PQBBd;5hCkvsRz&SiO=uy=XBiNvDEyXX(% z*}*@ac2n^wupWC4K(sZh@ip6I3CJH-U&hVuHV4>^JoY`BpD6Q#v}6^^>NiTon~ke% zQ%B*VRvnZn08+B1QXFw^fKhhD_;0izVkoa$p@00`AF7A1Gg3Ou6s~%6?eCvzMcQU-OEvye-1%?C`9S85G|Ufs>MjQjnhIr zy1<{|IUjyz9w#guF@4-C{N2A8YMnN$oSG1b^n1E9?zLaf$U?;On$}=?X%1nAW-G8Ficnpt7;(_h3_yvWw%rIIw#Ecs+Mg zvhC-}E4LUQQt)!&o469NAjs*B@vs9Wz@m~5`+o2%?l$nBETkOS5q2D}iN(!v?9EyN z3~GqLG~m6kRQNw~o6F_8OoB2vM7$yIID5)BjCYCRRrynouv;Tl2C|b>I?Ozoh7BQ5 zHOJty*#*$^|JYBrA;NgN9ecwn=s9o}Iw3QF)aYU_gGT1O>*b zJxX=31n{l=4F42=h*0x40HfKkOVxiR>LlWTi&Z`DhRK}#u^QY1$XK+y9B&-B3&gFH z5!9LMPOO|n0PPT=2TA9sBQrRvhJMeu*+zLJdAED6z=ucDl3@w5dF?s7@Fr9g&WCyU z0ud|fCFO;;Cl5g@UqbHKM~V&)-t9jBSr)`mt@flNU&NQ0D>fiYRjIguka+Ngc^8Pf zufiXCq8~l5^5nsONE{@!Zb@9B7s#vJ7%eqV+x4RwRcB%%kB^r*+P*oMTy_Sib{xv% zv{})|ICgmj3h~M$P5iOVxpRg4HWrVM5Izsb9jxs4*2k@<79thv^e$O?q%dRpQasJ! z6jXt49KMHbs_-m0usq&cEtnmQJto>q!CusoTY6iNX)BfCK7U&oVP|#gJ!GubBQ%6+ zSLMViu8?@LGTnG+F<}LwZT=FR+UhRuRr64s{{$wCB1lkHtv zCleTJ^|alRLZmyO25+GfIumjQgab0Q(J2NoRN8T$7c}ZaSI~FM2r5%Gl*9-yh&2*b z^i4`6{y0dLbB&%~6=^+TW;KelR(NTS(~n~hDX`zq{%_tqgc2g%1S!!j^xf&>UIZff z(uc1_B;`dedG1nty$)GEzRDft(8OM$ddtt`6+NdY*+1n#xQB|eHTixE|su&PlP^wEYE zzJRJk88A}W$Tb;_9Ln$E$SrwJguvZ1}A0QxMeLs(TKiX zmiOcsP}1Kui(7vn6CoO1X2-qoffWm|H>xNKbW%cS!xVGUkrZWKyT^HBq4Z{A*?`Ga zc<=o9$>#O_b58X!$iq4#pr#)4b$^|vL5^IZC7Fci;CMZ798x=!l05#em)_5_`<;ND zrAG6LtQJII!nMAT@2&))EG0ip+jHsDm9m$1zF+O*cLu|!)ZG9lfLeO(Paq`a`9W1( zM#mSYq~ZGM=BgRtI^+?7Q|ery4T~C=GDg785i0?}MDJ?Ea@Ah%Obb zg;Oc>`yMW(7YET8Yc9}5;_mG}Ed7wY?yH{L? zlm2TJZQBtstLIi{BG;?klT}-BRkMhI^(aQ6m{GY8vS)Ky`q_)YDAp?Z$}>gN9dyEGbm+Ul$PPda z+?MzpIz+1RkzA3ROSs)Gf5U7yXcXe=E;=B-ypFjnnK=nEM{~F^d|HSF%8QxUMl~c@ zMeN6p&9c#=dWY0oskCvlO4sqnr*M2$4>H1{TY_ZQDf7~Aw9Qz%Vq<F@@v)9rYF(mR3vPGJeqn zgPY%U^bL@hg2)s!S_q2e142ZoGRW`Gq2c zo<09|(0`2K{>x|=fbY)%q?3Ll@<3FXBCF!k+k^?N5yWAsk2JM41i(fr4T8!|d%zz{ zb=};Q@nh5D(370rWn_FSqxyWML_61|cXzq?_4^^*@aEBpwCGNGwNPHyY8&jHCtKdlgTZt66`VQLaEtsv5zCLXb=XRBa0RSGvhe6vkJX|vtF(6|H$w3~ z;@)S$^!PVP30s>7QBm_Z;TTfI9w?^y`8PQgFdr~&*HFgws%%VD37Nlu6!62VfgdrF zoBSJoM?Y_Q+@^UGkg3VI2ij67GQ{XB3q8~2@b{(UD(G=*2-#oJYn39wC&%v_m- z>c)d=>7(sWS0)QTu9Q5E{-|}4)^&6l5y$Zu-=7eFoQ?ZV+*0>Pny&!5PiZn1K}=c% z80)634tck_PF#kJueUV4nJ>(#bJpq?3;I8zL1`pqTo7 zX~yC>TRwOQR07!$hBHr*sQ50%-_lU^ITjV(fDC|kXVo2aqAyzt7gbw zx#VVi|HvsajQ{3==5hJ%gWbLv*=bE37+7yH!s#uTjB(Xw>`4u8FMZpE`byB`$;qM9@1+I^=ZAJj%}a4S z@hU)f=G-eSS_y<*<`vz*u0{C%MN44{~x5jcCZMTb9fBJP!#)ZN%-JdeK5a_TeJ32~RBv-tB+y4>^ss!G76on|ny z*-N^rqW~vF&(qXD$g*j_D=AXSR~3M368+N~6!w)B8m|}kSzMj=T1l&079j@i9JNBra~MeI1ZZ53 z+;MqitO5Ja2*2Mor@*uw#<^DvaP~tv#aom5{y&KJk;TX*mLc#W7|~FualkiHICFIP zoY08*!HLMI$>ZoExB#5NdyU}ucZUq&YojXjQAe^s!%<}5L{HHAXL|Eu*aTu#pgXc) zl1mcNhH*Qa)_x_Jw@Gyf>llvUL#=&*;BihuE_tB}j#GwL>H#9=wgXN_kfyd)=Pbs* z{0MaV+9uHZ6nXe-3Xt}WjuX&w0Kc0*g2MTFKyoVVC z5~E&!j#9M8a6}owfa&@~)%Dsh#N$v-eYJ3wQINg%3r?KJi8skI7_<(k*+3uzk@2SH_hGe_*1kby%V0|8`@?MoPs`z)+2UZRF=qm%j6^&e~i%oa?Cw9sNVVl zSkUX5Ddp8eA9nt^Gob-5RtBz78`=3g&(2>?YX`F?f(i$S(evLEkK;r{wX(F-X)H?J7^tbBN|~wfFEcU2FjjK zNL|4@+krzUhgOH*-TZRpU9vsm-PS2d)#b6jyA!cHr!S9pHfjPMv8#E3&sWM;p3jk@ zaSX}0Az6whVOjTu<`b_a?<$WDM>qbUd1BB;w3QWV8nlX>eRvFm2y!rq%d^UvCgV!C zn78@Fc=<9oVYTr$heh9)Hh0ze)fp*`H4a$n&@#1EJJ2~7dLHl1-7h+OP$8K4q}WbI z!`T1?XndPergk@?%HN*PUyGbvF1lKxb`eWWuAJp4ZL%{R!bB-c5dgr-u#K!A1}odLB$)M_+vp(8|QI5`MW&(wLm*7bizG8LJ9SF z1md0PgHx}A@6J{LgT1Z)LKs9m@yDYmrjSIs2VNl&V)0*TC5NoV=(0DwGKA?Ek-8S3Tye9g>F9Ca4j_Ih1H-N{u^*`d|L`yl1++TWUSdvU~QKvx*?^xHV_GP~Y<{mJ0@( zhwLBkP^0}#n|ni0XysIVBSGq~soOU;B2YxuT`$OZ3CmlGhang3bpfkRN|Ohl={q>N zfWlCB*KA#G#QQ#eagGCQP+uSeIIs$$v87M+pBhY`S3tQ=Hh5K}K?pe;Omg9*{6Sx) z?CRR&6vfn>=R?XAO-oP~9w#=E61IHmY9RHW1fBt-GoBck09!2AZ?-YI^JqZK(rivo z!H(uvBraE*D@TL?MI4@njs9Vf+6!r z2ae|&G{}vd<8h8w+zrXWZ}4==0^>+MT-{TCBxBtTN9~oTBYdISF_tY)Sh1zbm2vU0 zwlVJ+qh_9&a{J+IKF+>(b7WYXcX?;A?P_%B!HTt#`Y$*`s~!RzK4S!wD{h+KU3R~) zj^h{(&m$5RPsF0(*+a_Py%Mhd)C+BP5(t7_uqlG&SR9O!eTX2}wl4?qmBH#{%@(g? zzTuehmgl`IM2x0!BEaZG zH26LtT48Mc67~&|49R%uTvP638i-56y>b>1URC!pDEd3UP3K9Zn0q>R%JJI{U8R|v zFC~A5mB#uQm%gXX?(v?_QS9X6TSHJt0bZtSbk5*HG=so=z$9bX=Na&${E{W%vHA3Q z)24`xh`{CItNC5Lam0cUm$c6b3RJA$A|+T$v1=7{i4>EH!2w#_CBH$hLDUyKFCM~B zyOl+&&Jj2L0i9%gIxcGaw}WDM%0u=j($j0-JM8l)E_!C><+DSq?Y9%$O)3Su0Zm7| zX2Yi%!ClP+VM9^c==37KuMxWHLPQQX9AL~i66?Zx5t+z@XF zi$#=#roJGIadlb^r2A+JNA!cMEa4-uX!h`BX6)OQ|B<95Y9$+e$*ZE>K@S)Va05ic z$U`5rj_;6lveOGz!G0Chflj0Ly~bre`;Ncm<}dvXo32h3V97+PE+tKaQ3&;tvzHNx z5%muJsJ_u;Dj1ha1oe!8cCCk!BfRPu(fyU9+*d;v5>7v?-_IMCt>Rp-o(pj?h>G}X z6?g|ST^4O3gUx=?3*raD7AnGXGmivTU^Fp=Ap%wzZQ{JMmz+58m*)uHgHiPcHLpXah? z1JbrHo?0Xe3paKrU4LL>eJ{nDPSp1nocz54g*357h`r}@V=+^jJc_(O9)A(5NYY5B2bY3yFkx-vA^*TvuO6Rg z)F2&dc_64)#`1=IswY*b*PWTfU0MXZ1|U(H&AcrzLeG7NU32FCceSzkOOXD29s&&# zD>y^lz#m72J$(;m-lC!o@mI}$Va{MQP&sMzLU!5%BghfNBt-fajeo%7_VbfuIeQ2x zHPfz42yzD^5%v`{y;wVqANYEahMfC?Z=W5l1TfH9P2apAjsC@+_}lfz*VnBZJs+>om>v60*r>8e3;?>dr%|N73Y;nHZtt7qG zK;|3;EU6}w)oDcKd%~p6u?=E#Py{!LaoV<46FQr0P}j3odwJs2lm`C4$EIMG*`Sw zJl4kqeuyFZ%0i9paAuAy#`Vm+l>rNs`PQR4h2d^dW#v6#jBF-5Z&APffZ(Y$_BGTq zHNc)uQNt9-Q@zozQl#Urvix!t!yeqENai)Ql`8dA2$!x}>WAMy=PY;T_{r3m7_DU5%nV!z6SF>gUwm5S}vTZqG62|8K3l`ARUl z-88^Q6X6C>C}T%!06t+1DaLVxfF3QN#txk1-TWfv$pGU`!cFnE?gSDv{e^QW!~1;P zRhx~Uy2ZaAcbl1hC&W5wVO)BR{73}bGV z5QtJPXcw7mrDkby%G`R@JdG3oh49M_vpB5|y=~oiT9X?0wbWcz*y|U%!gr$b(W4j_ zDDS67c$$lT~86` z6K}r(udI_5vri^Pxp+q3S@FunW{%eGQ_Y)hxK<(}Z^oXCWz9#5O@Pk15DE_=>9-nC zUUDPDPId$~RX_CeMEsw4ihn_}lz}$k%=!JzX}e50z=Y>TgyuPmWifSE5);D0`JcYU z$s#P6IJ2B9c+47VAKiS=BJ<>|egN;!tLy3-NE*FuatOmZJ>M7q3F?2g|7p07KG8}i z>u|0$IKLNX@8-4b=lOzc%m&2eZ|^*c;Q(hwRZ>g<_pJKrr^);IfS54Eu7b_D!?RjX zgw>hi(A&k}3&a`Rg3Hpl&ON2R)MD528|(^hq@Lx}NU>lU@!Vdh*V5p{<@e7%V>RR? z>2t&DKT~M1D1Sr-nE8o%(%JVI=xhFGz0U*~ZU!HjF$8{ltvh>bZ%ut9=&yILb8ef09J968qz$QT>A+<;2yHD1#5B7<{ zzD7i6&*ZSVuXSu(njHDKtmBl}u_tgvJ|OY740a`Ug2)<1Ye9$h%m?^?=uz7^WxE)%te(F3Fvj{7J!dH*os_f2=FzA3c&~1; z`s!|3DUx}z4Zpu+|lJ2P7UTlx9Vhh{Cf$@n+bcW-E*5UyUn= z5)3pqEDLnZvD+|h%7-g{i5~N&e;fYf>*!8hq8|G1Oyto6dqt&@?{l#wK2lON}VvM@Jp8h*LBErT-PnhGZJ;zqh-8`GRJa%>DM}tf#Bf ze5{#G>xa*6N;F>GkQBDERQSBQ<052WW0JDF!N?khJrfJO=QUzwYF$fwqj@1ZucDls z@`R$sT>J@N4yx4bQt-#Fy0v>uTyS!sEB!#0+Y(vt7_sIjJvx)d2h3?69)EG-nrr8x z+7o`K(Ok4&7EAP|JS$||{eA>|$BE9BsdFYme_A!piKT4!m@G?;#6 zq_l9hosS8#Hz7evx_oa2{#nW6g5w9TBp2SWP8+=&m>Pe(63%dILB~c3mKV1xm`tK? zpr|}2(Q{ZHPW1|zRwM9dpgwkm@m zx71orz7w3F*Vxcn$n_>0Y@T*&9?X-!vmA@N({h#fP1(gK2BtaB*BuN)gBxTbDhAsn zI1(|;xKPog6nZ4+<8}}wI^+D8i9V-;RriIij*ika;2t$=KwdlOO1gew zGK-k{TQnfT=o!~;o<~J}e0sj-x0FKfp3)y>DP|Ui7x%u-D5>9Ton_rJTlnBq^XIsn zB+)0r(}tvG|B+Rf&6Sr}zNPn+_vKvcGPK?BuTk*hM|K+73lV7CyGtFJYbz%sE=o&! z^)GR*1pnX%fN~}L>En!TeElJQJP>&EPC1=RE4{EL{zb1<7kz4jp>isB9+f?jQ5Xwu z;oQnu#(q)LH0MMz`I(uO*H5Gm?O0XFe5vi4;ktM&>L|(iDUEoa&g-V2SJ8C`pzpOto1IQ++I15#lJ+gxX-K;FP)zfTeH7EIoa8!_53HO`i zI{9((iA(XsYKn+Fu&eL4u3p!x4sdw!Dd(I6_e-j?iivt{4+~CIg1%P>N_2;z97rQr zNrFe!RL@V`rull$M?dUbx){CD%wdE1TT_(@idH4s$V+1mpQw(`l^efo9CD~sP}Elx znJSD8WgmWdPkVQTSCubJg0nHZVS$O!J}2iU0Q@Ysv)t;Txlif|R5v!r^gE1^mDyV_ z=#Ql=+rpk4Kmj;^U$W`QzRR(HdB^u#9<5wMcrikef-6QT*|_~h0NZFi5Usq4d4fzF zc8#BCRr_klTLH`ZU}`aM@-T-Ai9uq%*^I1K?#;*~?F1ECDO>+7exI9Dy-+_r-30oF zX((wNKZRVcS(l*td7o5x1Bve~)`6Er+VyXn8cme$(k@Fh9ib1Jww0~q74<0E|JCS?}#EloioVfOY{U`^Q+)1mTZ!#@BF!Yh2CL@+c&b!^_yJQ;C`s+B?=@a zi1LzFdIXANnjze}|GZBY*{@0?s`mP5jz@2uG`w2~FG$Tn+EHV)mnhiMC5WMN0kv_i`RWnW> zk$9zlBRy;&>Qg0ED4uJ3i%q-63Z$mI$=Aj96YjH6LGNq|{sw&$4cLXZya@3DI1%Era zvWD~|)*mav)uV*|^m%HyK5ddvjF~Wud{QC~n?Ah-`XuVMU#- ztpAw#94AJFji8eN|0#Z6ZtjoCNEEL{p9O_S*;os>eyqW5t^2Yl=SvZ`n36)woNA7p&FaLWzErup!?=Dt-_PlLH(EFpbu+j z|I}{+8HsXLXARHuyGA1e7H&&^z-o}-`*PwMrh9wx7wGEx-zY?pGNlUh+tveU%S^8{ zSG}AjY`5M^9OPXNZMHC?6lDKC@2~FFzdMW9e6qs9BK)rs-B0Vv5l11b_Ore$y!_F* zGhm2);PerDt;3oN!wJoxHgVh!M>11$iCGbbiM0*lK0`Eu)WvSMR@5 zV2yz+5o_K?*Q%JztapdZFf%Ef5wMpFf9`}m*|y#X$T!9(6nzQvSM6V$QkByxLcNWN>Gtw_ynD3kEm=!;a#$u*0-o6J~Q8lIz)l7k* z@{cTtz4Evmz4nDVBNu9YK3SFG#1J1Hz)&1~1dRQCWULIOW0%r4MlXg_#?!{1BdNF} zLXS_{ILix(diZ_#ZJ!fM}7^+6& zC9i4Pk_Uenmi${A?o4E~NxrSj>{R>h%s!Z!jnwRNhq^(Xb9KKeHTUzZ8GPs|sHW8e zq%(5;iHpu#vx?-q6Sun}JIxk*T|E}Tn8CeIa!V?MP2HBjp#iDBDY-&^B#rDUcJ~06 zz8|9%zy}N%W%{2%8x-(eK$hTNSs@O(t>URPl1uAc4>S>qBK~Ikjk&tc4l7-{RGZwf zTzZE1rN{~(GjBqdoulUGaEg<1X~A5iBNG-=f2#gX=&rrJ;A_{s#YStAekbA`B%2bY zNq3B}xSnTk2dx_%1_uUqrelCnuo6M?Vgg6|JUUEGQ57cQj4wY0-%mGs9^=Ish}SkD z0C0N+b~xIxJIHdW?@p=ICQ)ah{J-*nfS_ZnRESz$_FW$h?l2}0u-Yy0F51$X7`TLD zZ+tz29mn zho`p(#uHjZ2d+Fa%zIt{d!DOi*bP68k=acmv)ltPJu>nZY{wvyy7iNY2pt%9P~q8-nj)8`D&mQh-c7Wy?8l2DAHcFqlTc%>)J#Nlr9RA zt{a?b*y8xey6W^Z_h521`=GHdVl@VL&a$LdPVwX)Y!o0qraAl@Bf)t1ICYt)vaW6aslz)+|3qElc|m_mt=OA4ueWo6=;G0w0~2;8n+r~GEsLuA{d z7%Og>Zp-8yG=@hM#W;y8Q5ju9+mvc-*+$wr{#%ZuV@SJebO=n3LJWMxqDP9!st@yB z0}arD0}4`{PJI@U_HZ6nns~os#jCPqly{hIYV?kAu&8q6s(h3oDv23bq(eCZGgO%CXzhsXZsz>l zve@9Qlsp?<8Gy4u+wV5!=gtEr^1*{UWMZOy5AFgNu^B5!t}Yqz@o|)B3gZ_U8xQzO z1#`%5QUqII6lrGZ{4dZmM{PnO&1u!wZ@}+V{i0MtVxs@b@Vn8{b4(&f6{}mxF-{q7 z1Ck7vV`mZ~bmSC8P8%95J*vdtu5<*2*_PlwALads2rR+UM->5!eBtI`1GFktw)FB@ zWdPN7H5})rcGSy~+OThhk=;>tU&g`Ktp+qL^1-SW3jHnIwOB#HPa&n`F?@{y;kPp2 zz!BAN>&|Hx3eLkS%k zm(nQVo6b}C`dKbLsX_?18j^zZa{!0q#t?!2Wd+{g{#;cWo)!yRn>#^RT*TrRZ@t7n zp_wZ9*_Pv?QhHE03ZX?hv~sOTtjQbmUf1Mqj$-%>TyUAgP)Xuh^*w#p_@qMd$LoWw zmT1wL+P9Ec3h6e_6d&x9)As77ul-TBs!LHRtR$d}?`2)pmQ~#y)xUT9H)Vnuf;2w2 zFdWq!tSVqZoos+M($1VneL?pddjP-;~)YTi3leHB%Dq;Hr38_@glA9eLZk*oaBp9ZA|_t1AHE=GPdm^by5w zi0GUhG}yVvM=P!SM8~CWA<^&-xnWe$P)rC@G%?lqk$|0>@gc%BtsriPKt2qiq=|0L zWhk4yjtRT!g~9bhsK5W|Ok=b}6|O0e*7fYGQrpbT&vWlQPWHS1s2A4D!*9F#Jbxx< zPx7;#k47K{{loY>(m13-a{})=#}g-B?=D0LsyCsQYSSc|`iGO4!8bE z6Ec9-Jsi{!fs#7j8N^3YgmJr>jX%f%A{xH1IW)g`YryiWn$7ezXjF|9la~w9>EATZ zRAYbopB|d`F@}0}ki}vNkk;trr<&}M$YVFX8&96rrN0PQaO8XPlr2Ih7TjWGJ50%G zq^c(s1%7ZHMEcz{V_Z?TVBCfFF7bx!)hY!S8+KHclORr@3I1F>WZI4CqKze-{A;!Q zMS1TpP4sy8e#YB_YlC!yPeX94Fqf1QGb4e4lY6-P(?kN}%AB~Dqtjm=r^`lk$m|(A z_wD*J)+<%tq>3kSZVW%D#w`**oJEn#bMpupcazIY)ttK?3o%?Ru)GG3lLy5^|Fn^1 zVS`kKkyi>`|Sn0#tB`_`ERg=Jd3$33vT!zQeRsRVxM|t?5kVrO*p2P$_woFfSeO`cMtPoQLyNrp_F}m;QT&{{r$*bm(xwAZh{)&4 zff9TFAnN3%*@`w%GQ~3_U-=nFD-xjY8q2Cy zmW;IA4YtdCjXMcu;gJm^KuTGo(pGyIjwSE^NY;$K6!n!_-I^u{&GeKlpdtRY(ifH01XW%BuGrYheRj95VztCBH2*PNggPdDR z4&TmtY%@DG{mqvIeQ8EtS0VqS^SPJe_7KSHkfypK*N9glI#sl^GP8q}&S+?qO|}`b zv)@^DCxXg1g%;I;nn=p1F&m=u#pg>uR zOVVj6aAvT-O;kNBDh*w=Lmz&-7=vv`adUGo;J9R?xGk$-e>;08Xn18|{Wn=FRXlA7 zL(6qcOBh$pHX}YqBVN2om2J|=Jd$q{_=2NvDu@#EKGLRdRgIbrzA2xo2JYqsH(NrQ z>IPa0MKnAh3>$%MC;O|(XThkSY*p3AMRe=GL)P@hpT|1*ar%~9;MM#|UFo~Jg6n(( z{GL!@F|J=-i@aTa@gv)?QCG?FbD8-sU4KNZa04(fCG2Fep@;qtpxI!r1M0gkP;Q@%1IEuDMRtLsGz93Nz0?!$@|;k z_2Q%1ekGZe31$p0g;4(Ib?J<@yHFgZah(vci>kMt!ouq)9DL6fk`u#*i{@`FvNg^XsCJtc$&y|{BCnGQ z$nnP$vsI|DE2vA>f0SbnUS6p4I#=EHQP04X7SYUUcxewZqlyb;jMs#5(&&@lE+vr1 zNp(MlHNj5zFO*@9AKeKOe>ccl-FIa%Dy$gR@HpHVahy3s?inW{|QsE z#_eMoHz;r>B>D8%Q5| zUU~3u-C|YIjfywXk3WW?yc$GMwB1eM_}MW-OAS4p^H_#=;r61f0hXgtHCcG*zc+pm zl5SQe;alfh94Gm2Viq~0o_SImt$xA8hBBXhah{3aB7jA6S0R+B`tE9EDE*&0h>SPE z7Nx{rLoUH>hyfT@svN^RsJE;8~hK5N4OA?}RwE-{}|p|*E5pK+y% zfpvd<(k(nZHbzxNd0jabT)W55Nm-gNuIhYzulqLPB$dpZ-~Z%kM$qkd`aC%62?>rs zoO|`4o98)b+2aD}&-*?jXq+v|&8_Nczd#8ORunnkDcy*$+G2X=k8)t;T7)@+8LA_D zb46b%xnEPrwyO_pkVjp`UFO?R8#k$pZbFOJX)rJLF|L!?!U?(dW%H#B!Rd9no3|bn zsZl|FNf4Y%oKHpIGQmmv{4^X)uADgk+X-n@_pD?4!8UIIeMn|+~F3Ji@=X4Zxm?Km{wGGcxHbpmM@wB(B) z?*KhPPYtigxJ1-qPY!2K9dn7?EYFwsT*nl^{r&`H`k^wy*YAoqI?F6hS(WC z<_D23{EFzvGg?&i}%e9L}gFk$$ptpp5P7H%9KDePc58xfE9e)&F_a0vbS?@&P) zBM)JXul5@x`*Qq3md7Pxas8V&p+;UXNYQf#gL9sD#4%}64&d36!58oQyH|AA<%0B1 zTtSi(RXCJ%4P|A!4}-$&AyA!1Qm82`6H^T~v_Cm)P}m{U;8S_^poZ$#f7SrJ7-%p) zfE1|fWm^!{IOGJg88;p!$Zj?rI+|`J`GO2`ujW?zxbh>^H46KghH*G_e2!__eqF=B zVtmZ^;Rmt?y4HHn8yFj>neBEjeu-fc{W7bsSp9I0Jpjwe#Z_|wneP<=DZ{(<-{k!r zT6`&067L(Qm9b3!nOJo+l{6g+8;g6qML(E?c|gT_6FjRh%r{kel^88P*kUMe-jLt-F(!dKKkPE%F0shMz1dmdLA#PC^-Z>;OI>VH1~2Nsy- zUz4S#$UR#oku18dS07Xk#3&D7fO>}{-w1%WT(uGs5;}GetEqWH&+kIvat>6lk~`vm zrS~=_A8d^XKQMC82y;p&qBOcKD8U<+{p?bL{+t-8rAB*Cl4L=jankoM##O&d_nH`@ zQMFPI zXz~yxl4_7Vss(Azq5I;Fj`HV~Yh4);LY5r1!?t(6t@t~n+d0L?^B*hC_CMd@@Ku{_ z&;1Iin!;JiBKSLJfjtg4O&;fvMRiI!d9(;UWs7cI;OD!-pG{~oHAWwN=G;MO#8qmq zSWx~ROE}N9obLVTUuXih$L-kK;)sNTg9%ax4G2X@1p;8WALo2E%jz~b`}oF zQKMZq;*OWDl>hG!Sp1s@ZL-x)1OOt`9PjbG6vpa?O`8Bjl!i9au1|oTjZe)@?yMF;6g*xG=(Q#qL1knKp6^}Cb3n&vuyaozer>?&OzIq|-D-VHFD4-|AL z=U8TOOIA)&f!IU~*nziSlEjY$sAN|XC=;aKH!s1-mCjsXX)sW>WMhS6P^Q1syg9FE z_TAuq3?HBP>KnMHAXEuaM_*u-S&v~9YRBC&lJ;Z#9-!0n&buxXa-LaiuH;^gR_S-Q z-C=`zaHw<^b)0&bh13RizUHW7FL&YWCEmia7F!GAP~hhqlnlKKET!`@?!*3+?qUa)I_iYxNek%9t{PZ2_e+-Le{ zbl07n$Wsa!pvn{SYnZ4uWI65}^PelTq<>Q;5_TylvZo0I6u{DVn}&M9WUs=f=@IbVjt3(C2nF?S4SaC3+XoiAcYT=s`ZxA$Y!LPEgJA4C zS!&e#fGI=H%fpZWZ1ENUc|h?}5p4;DF)pXNrR0sGtvdS`Po&Hil=Ie8_zKx_8o z3zr-das3YqE}%&WM#1WO+7I4l)BNGmZyr_tVhztN{Zz|F|$RK(1 z?ZcilVRc!$_-N^LBHHoA#l`Q{4c^H30rEf6b$PzY5zkhC&$aP2A5kMr;v;avltz%# z2DLACCK668Uqt2gX58@cDVq~|wfqNYvV?oIHvB*OffoM;26|Vg|EH-gV66%{cPZoZ z^pWD_HtoELb$I2yWE1@?Z{I;1-FmxG-g?!NMLl$UC(sy%8bO}x7QvjSVC*MNvOpd}KvxeEn$b7)Q6aN%-ybOC znAEv?6QttTOd^phpwXoVkleON@y zEaiFobd7dg_IO46!!)kF1?#dhVDL|T9G62Qcra5lY{G$^mNN~OT^ZoL+zZ`j9#7-0 zTZf|)=I)2@8C_&t=0hfdkcx|pV}}UL(UtWemN;G}JkcIM0b&VyJoASb845!|&ntB| z+%BI31G^v3EZ!QUQ(;JF^qtiCepf~+L?wOA8IrQ#+tGY-$Rg^PUjJm}&Z$fhhF`2z z02h6hTx@YK#THS}H)hrAXpB^4i4M4^q5BM6sv#XAC4hZ~^RO5s?7@8mcYr0l7x_yU z^{Xr(9671hD6>=?dA9suF)7`Y9|^|Ax8E&oA-jJggBRb0s=;30_4+ON@loVDRP1-G z2CmqjfJ$P`_bGQEm67Dq9IjF^sR@liTZ4DEs8Ll5&~s>L0Cg0T*aFvs$uh@7V|<4A zVOk2^8?k!vOF|KSZWFE~MWAwU#KGP~Qy@|Oq06>=u=^mV^ZnA}JfO54h!1V$@qMp* z^+~Ce%4mS9_My#oK)nKJMEa8q*Oz0_hRE(~=5Ue3{eYK)>~3XqyrSduN+N6gQc>20 zuMO0;w)kwRl}ykbrBOY&Oh+0&3Y(yA7mWQC+Tv#k%rT=qe`pPZ|K_8zduPW|N`tOW znbJs9&QrK>^wrIki1u)^c~DMebT2*Lry4Ya%LfA77mv)Mh9=}U1u2X?ABWLg=4w?E z5f`uX4a%pL(+EQaljL3-4|E=Q_S9o{VhU7Waq=u}G5V{<5rYH@C|R44(;U!)3n01G-tVO^yR_PscC<2BXQ2RCYa zS%9e*uT8Fu#(74(OVUP@Exwri0}F4M+7TS&M2`~eg8C`v^qFIU^kV9NXd$)TLUoBSOAuMC6@|-rZVY0^)r-7-)k-5z-CYXWea>1_r{dWuChM|ooq(6qNAvRh zGN3C^hTxGSF;4^NZrs{~1OFv1U7FN%h4)ZuV-RoJ{IIre>RtI0Omap9DeA)4dqro9 z{l7=1yF=eD%LMujM)A(`j(_{VPuP_X$2!F4RWinQ`c~Zkd}A+_dG5ASGM|X!g$cGA zO8a{d-qm7*ytiW2TPg{{$l`ndPjA=#PxT+RWfaNR$}HRQ$m4nEbUL>{@yq>s{xw zqD6S!M$QhG*=r{)>-;-wQ^D-bj47#++)x{a`+xYe@ZA)4ZELC8?gt~%O}TR8P~?|c zJ&5XTJuxCQx~zsy$3-N>kC1oxl1^y2F0~wox#?b}LG< zwavK(Yn(z;4tnu}Xl^Dh!F3H*waf`6LP#rP+c+#I3y+O9b#KFU}=20f3dtFiB&vf-)Dn)aq+nzBMlH`^{2-oL{| zDPL#My2fOHtsOm>RXvdJT(_j=eK)3yfeCy{K|Dy@{^|7*v8eUQB{Q6i6tOc09Rg2D z1BCed3+mz+D>-+xdbyF+7MIECS?izGx_W3G|W>6z2hi<_xLd&a?~!!$QD6Lpug zW@{yw`1a4VIkef;ooyIu@&EN7eQudOabZfXN!<2i3O&h2Apbb60J-^D4m{np2wvHj z?)rwJ)wJ*Wai$qIxesV~APX%Ip!HCX6d^Y^u{!2PMGi*g51~Z=eE^Y6agEa`Z7l3&c3C=@bEIPU&t2u z?3W0kc<;+?U=2d5cFdzsC;@ za|A~opNd(extR3Dg@?Qgt&@L?vs(-+dY+0am#xALqm0E1K$N%j8K&i$>1#_4jz`rr zHYkDwLs=64;uApIHSDPP^pFVMS#Dj7pbMyg@Ledj7Sn#r>Gy`U`x!Z&OSMU{J^ zi}m}C8vmVV*)TuEM4fyqutY^aC+SH<*0mE#k5pP*F3oHS z+8&(+Qp8Hk+-9f|w*3m!O_Rrp9she@BN;8H;k_8QPv=V-OlF{lq<*;C6Zeg^3mzHP z#{=#NX_WqH`M7E5Yc182LjVKg;GqX}r&jzYT}@>cQ2MIn3Mg9R6z8Fef*TMVI9y$M zn&%8wyUbqqjHw~nV*noW@LephF%T`gZdiCWRt~auj)WOQ#nbs-iX#%vSMro%+(3qB zNb#FTe*;JUPm@@IC4>g4$m5Y8EK%V$0P4Oje~&Y z=M4)HpX1X}eN8i+`kyE;liwtW;D|*q_uUjO2k<}<>8>DcR#IHEXJ?;~!h)GZvVolP z-O~nGNGp~L_mOVciy*T$7rQbw+QU>;H1`wg{pyf}2`Ncy{8C)q4X~4+=o(lx*3c_K zSO=>n-f1Hl-;(&A_S%164P*w5kA+(>ARQz0M z$hZ1!`asp?CHuy{!hU%S7QqjigCVN3|KfVSd$HWw>jcwh)G+8N8s|=^4x@IU!O+6i zeee)pG#&D#=4PaI@*{pIm zJ;AA84+8m)=Tc6FZ(O6Wuuj7m{z5{`%_s{*0C^RRq)R_WVq;jPN0|l5+x{(4ld?7<2cgxH=_+_oYJ(Yy_J&^w<>pRyQ z@|C0Ga5zIi&UE_P!5qCL4NcS%zmU+pqTv37e$zBa3FCLRS66$U2yoe~O+>Fiy2oe3 zWF|)us(eqbqj4%$%5R2(p8%POod%0Tw=KKjFb+N46c$IrTKvCEHA%#hI5D@oP zXog1KCy0U()OJP8%qS#Sdp_=BH}(E8MoSk2Kw!C6a+L{W3;9=1AYK{DLqm`SH;zXx zf!|^Lj1q({eJwrE49p9zp;y`gH)E6li|Jme^IIgp;dFS(QK~U8(TXA{uzra}^=n)< zn+XCJ z*8BxzcZNlQi9j_FdMitV<)b|+I|lkfH;+`cBV7(LAE#I_%#T)3y$0+#C)roIss>B= zOpr4LMkk8Odcz^HeZ?5%I}({|=7{ft$*iF}l|BRbwT)j`10`yA*i#o=o}8RJ)Djx` z%f`Mn<5X{6u6#y%X~~cb@fUe}p7ajnPseLgCT^WW>Bk~RI$HH6`o zQG=thtQU26Yp%}d`8n7dP`re57PB)v~2I|isXcXhOHTx z3qI{&jU)YSJ`YobcUMhAT$h)gE4g#5RxjJi!wcvQdn9Fcg@i2%?f*STX zQ7mv)@=}LAz3zHtpJkB~!rut&wc;KsC1#K4PI@iM= zz17BIRs#&UuFvFk?9SG_Pqw%~Y=fOk!_e?@ii~?2tHCA-LT(>`0*f>gaJsZ9vYzSt z2QU0Z_$zjC_`nHedgglS)jPLwUg^+*!?{DWtMB?B^Qfg;2up@c_tB>5&Rv+q18xQ1 zx$3GbL$+E@_`y7VeM)Lq|CUK=BPHW&PZk_yk1x`>Bmx!WUmoZ_E4QA=f444rK{yR@ z=^~SVS>>gxaW)u&k@$t6a*Llq{47rLO`NTN-}y>-Uwk8?CZ7i6t+^^f@;YxeZr5H~ zG{36!$4QH7)=m?<^Z6-2QPcwkf|FMfdL)Z4elhtLHmm2xk90i^8PEdJ`>u}d+4pbL zaUs_NrJ4>kDNYP&mJ`t3-rg=#`Q}vQ5@~&A^BKQBxD-`B)$oVzQ`!jlJdEt&t6YNw z;lh{BBUzUo5)ltb`@?4jnPmDXV0;BSs-YC z{wJC^CSE`_j>DOUZz{ zWccl2T4-AE3XtL5MerG5;PS;Nq1fHkymGAtgWz+Gm#>Q%zy2R}ffO{$V|zU||ID69!*?@a@ z`Yp*Mbg!H_To2K5_Xd*}#u|4bz!+@=2XSmh=}eq>PT9e(6UTNteq7+^obhGEUqxG6{~(L`ni-e&x#jn*3%Xt3g&ZRe@EahB@&*g4q zBichP`%{W4e2*Shkb|0BpfQsW9Vl#GP=l=HC-h)!f{Pvpm?n*froBimtZ4%NEeP<1ARV}ISx`tn8lAXEM_Okv5$>Xj@ z6O&FpC*nF?Zsc-$Ern9(E~FIAQvo01+YC(#>_PeR$(JaITbJQ<6^H)t5NbBQ4$Rh& zCJQkdh-gs-9~ZZQ4_pD=-vCZ2_C05V&`~W%Mp2I-DTPk=wF|;^g>x^m>os1hsgAy! z3}ktZw){@I@K2gtQ(3>lxZIQUoZ_^*uI!M+JOvftP5*j;!tluqXO ze^$4(o#bPEQl>bf&`fu|f!!ZZ5Jn%Dw|y^9&i*8)?8c)mZ`(H~0;iwtb{~xuJE*Rm zs^>ENM>I4+7t6E7$R;mp`tQ|sZI)U2rWi_>_XLIr9Z2Ee#m$d?cvUk2NHEtryb3po zsJj0htfb94^BKQgIWxd&?xWNP-k$-$RuDk}yj2$W?L3!tZLy@`u6|KVyGV82??(3L z4ouh4M8T!VOEzfv;zr+*MibNA(ncoM3saV*~%{SZx^3wuP zE3ddd42b?Xp=vTf&>&@E9|{$SNS^k4L4HV4CCb56l>6HH2iiy$yVzbyJ0L7MqKrMy zJfb~H-jUd@VxZdR)L>L2Zc}k8G|y8&@NmJ0i||snQ~Z9;^^l%tpM+@gJmKM2V114P zlR>59V%P`a24J?Ue$9aXZ`f8_!R=)*`8`P@$F1GUm?Mhr0i(Ib^WYiv7D~ypc%R!l zG5a|@G>q4g)0}}oWo$$F$m097pg&rDXA-y?efM9A?L~qPoYDbeVDThc zyxVDCl~G8if3tWB5{mr*fapKV5oN#6lM~G@MByv5MapC%lQmi{Azw_%XJ+7TYC@O7 z_wn4qPw+EbfB`Bs1Gl+tr1ES#2q4bpMEW|x2f%4O|g!?QsjfiHF zQBjtUe#B*8>0Y0aN4-at{_n@K!g?j+K7^mjO=2lZG5+W*`szGmf>z-aDLk3u$Mg`Y zg)kX+_yb`Kehem3{Nw30SfehyuKeH6|Ns1tXgN4`a+rNf#9_{c4E}UA4K-e?+l2iO D$>`yV