From 6622724eb1d42abd32f43d4a240899fd96338842 Mon Sep 17 00:00:00 2001 From: Ahmed Ebrahim <36835765+ahmeddesokyebrahim@users.noreply.github.com> Date: Mon, 13 May 2024 10:19:53 +0300 Subject: [PATCH] feat: add autoware_remaining_distance_time_calculator and overlay (#6855) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: AhmedEbrahim Signed-off-by: M. Fatih Cırıt --- .../CMakeLists.txt | 108 +++++++ .../LICENSE | 12 + .../README.md | 35 +++ .../assets/av_timer.png | Bin 0 -> 2010 bytes .../assets/font/Quicksand/LICENSE | 93 ++++++ .../font/Quicksand/static/Quicksand-Bold.ttf | Bin 0 -> 78596 bytes .../Quicksand/static/Quicksand-Regular.ttf | Bin 0 -> 78936 bytes .../assets/path.png | Bin 0 -> 1461 bytes ...n_details_overlay_rviz_plugin-extras.cmake | 31 ++ .../include/mission_details_display.hpp | 83 ++++++ .../include/overlay_utils.hpp | 131 +++++++++ .../remaining_distance_time_display.hpp | 57 ++++ .../package.xml | 28 ++ .../plugins_description.xml | 5 + .../src/mission_details_display.cpp | 212 ++++++++++++++ .../src/overlay_utils.cpp | 267 ++++++++++++++++++ .../src/remaining_distance_time_display.cpp | 157 ++++++++++ .../launch/planning.launch.xml | 5 + launch/tier4_planning_launch/package.xml | 1 + .../CMakeLists.txt | 21 ++ .../README.md | 39 +++ ...aining_distance_time_calculator.param.yaml | 3 + ...aining_distance_time_calculator.launch.xml | 20 ++ .../package.xml | 35 +++ ...ining_distance_time_calculator.schema.json | 31 ++ ...emaining_distance_time_calculator_node.cpp | 188 ++++++++++++ ...emaining_distance_time_calculator_node.hpp | 110 ++++++++ 27 files changed, 1672 insertions(+) create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/LICENSE create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Bold.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/path.png create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin-extras.cmake create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/mission_details_display.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp create mode 100644 common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp create mode 100644 planning/autoware_remaining_distance_time_calculator/CMakeLists.txt create mode 100644 planning/autoware_remaining_distance_time_calculator/README.md create mode 100644 planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml create mode 100644 planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml create mode 100644 planning/autoware_remaining_distance_time_calculator/package.xml create mode 100644 planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json create mode 100644 planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp create mode 100644 planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt new file mode 100644 index 0000000000000..8692ea1bb152a --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/CMakeLists.txt @@ -0,0 +1,108 @@ +cmake_minimum_required(VERSION 3.8) +project(autoware_mission_details_overlay_rviz_plugin) + +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +set( + headers_to_moc + include/mission_details_display.hpp +) + +set( + headers_to_not_moc + include/remaining_distance_time_display.hpp +) + +foreach(header "${headers_to_moc}") + qt5_wrap_cpp(display_moc_files "${header}") +endforeach() + +set( + display_source_files + src/overlay_utils.cpp + src/mission_details_display.cpp + src/remaining_distance_time_display.cpp +) + +add_library( + ${PROJECT_NAME} SHARED + ${display_moc_files} + ${headers_to_not_moc} + ${display_source_files} +) + +set_property(TARGET ${PROJECT_NAME} PROPERTY CXX_STANDARD 17) +target_compile_options(${PROJECT_NAME} PRIVATE -Wall -Wextra -Wpedantic) + +target_include_directories( + ${PROJECT_NAME} PUBLIC + $ + $ + ${Qt5Widgets_INCLUDE_DIRS} + ${OpenCV_INCLUDE_DIRS} +) + +target_link_libraries( + ${PROJECT_NAME} PUBLIC + rviz_ogre_vendor::OgreMain + rviz_ogre_vendor::OgreOverlay +) + +target_compile_definitions(${PROJECT_NAME} PRIVATE "${PROJECT_NAME}_BUILDING_LIBRARY") + +# prevent pluginlib from using boost +target_compile_definitions(${PROJECT_NAME} PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS") + +pluginlib_export_plugin_description_file(rviz_common plugins_description.xml) + +ament_target_dependencies( + ${PROJECT_NAME} + PUBLIC + rviz_common + rviz_rendering + autoware_internal_msgs +) + +ament_export_include_directories(include) +ament_export_targets(${PROJECT_NAME} HAS_LIBRARY_TARGET) +ament_export_dependencies( + rviz_common + rviz_ogre_vendor +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +install( + TARGETS ${PROJECT_NAME} + EXPORT ${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + INCLUDES DESTINATION include +) + +install( + DIRECTORY include/ + DESTINATION include +) + +install( + TARGETS + DESTINATION lib/${PROJECT_NAME} +) + +# Copy the assets directory to the installation directory +install( + DIRECTORY assets/ + DESTINATION share/${PROJECT_NAME}/assets +) + +add_definitions(-DQT_NO_KEYWORDS) + +ament_package( + CONFIG_EXTRAS "autoware_mission_details_overlay_rviz_plugin-extras.cmake" +) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE new file mode 100644 index 0000000000000..a2fe2d3d1c7ed --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/LICENSE @@ -0,0 +1,12 @@ +Copyright (c) 2022, Team Spatzenhirn +Copyright (c) 2014, JSK Lab + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md new file mode 100644 index 0000000000000..3a4040a7065d0 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/README.md @@ -0,0 +1,35 @@ +# autoware_mission_details_overlay_rviz_plugin + +This RViz plugin displays the remaining distance and time for the current mission. + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| ------------------------------------------- | ----------------------------------------------------------- | ---------------------------------------------------- | +| `/planning/mission_remaining_distance_time` | `autoware_planning_msgs::msg::MissionRemainingDistanceTime` | The topic is for mission remaining distance and time | + +## Overlay Parameters + +| Name | Type | Default Value | Description | +| -------- | ---- | ------------- | --------------------------------- | +| `Width` | int | 170 | Width of the overlay [px] | +| `Height` | int | 100 | Height of the overlay [px] | +| `Right` | int | 10 | Margin from the right border [px] | +| `Top` | int | 10 | Margin from the top border [px] | + +The mission details display is aligned with top right corner of the screen. + +## Usage + +Similar to [autoware_overlay_rviz_plugin](../autoware_overlay_rviz_plugin/README.md) + +## Credits + +Based on the [jsk_visualization](https://github.com/jsk-ros-pkg/jsk_visualization) package. + +### Icons + +- +- diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/av_timer.png new file mode 100644 index 0000000000000000000000000000000000000000..f7f5db12495113f6b0afacbc182658bb519a9059 GIT binary patch literal 2010 zcmV<02POE4P)Px+lu1NERCr$PoZC+0I2eF`r)agicO#%fuC_eMlqaEm65vT-o@BaDLPlDt(1N&H zt+Y$y#Yqz!C;!2*LyOej%pp!}fBw&QqTuigBA|lqKHLlkfPq4A0C)fxNFea`y_CS^ z@?~PrD^0&-f%6>f_PqnRTs_ScsN0SiZz1YTfhzubNATd!1hDXUx;?2( z0W5X}bMFBn&@kD^0Cc9cTBKi(Zv+Aq++^E&6 zU@_2JKP^CC7z*Gn-y}D&J^JSZ=xG!k(3##O7cn751GrqRX6bkw98wTrjIYq4jz(*^ zi{)gZ0DM?I{Qyu?t>HR!U=%>}d{Fvl0_vLvm;yi};PxRLW2~mXV1O08YVe^0BLRY* z+g`QESd#owDVX(xnJ>=9rx!lp-L^phU3f7d)&M(fopu1)lPT|mOQQ)sK#X(wIzFEJ z++(-x4X_2znQ&i8BqcD>^YnyH-HcSKQT_v$NR!Jnr`>m~y;XSm_(YzmTf37+{F>*)TbXLjm+tXT3NZpNQf^5y16&J>3W#hY^1b zMNmurD2Q%3-+oYx99HTCrBWyYD3QJj%8(%rw=mM{!ZBuN!nlS?V%*@WC1>|o^Ls|>=Jk3D#Oko67g)6R3)GnW5yP;03TM* z9s4-%Yfrg-A;c_ZdC5mA1*VBrV-ldGHpdxT6r!CwYsfUjtI&{bcz zKq3+GB7BhL&O4DrUJB`uh6Ko|uf)jK*}$GcEQ=S339vE2CDjFTl&#)woM17G#Qqg&+0kpU@#7}v5)%Ocy&X&4_v=x{nVIF&(@f=X3vX58uERIr zBnq}hkpLTYKeuF0R4kB4zg4hAAvXK+g4k8M;x^UoaHeA`#_&QN2?dZ0pf%w@2$hgS zY?^ctM8+YY5Crj{A3%|3LI5^))hY;$rD!{!SnABBotQU8=WB`M+4#6q*gF4H0uXy3 zHwjD~#1M&+JGb3{dDF&xyL8x?#@FtUEjmDnhsEG?5IM)i0i?Vsn=~LA*BhYT{C=LM zzqQUTbM}PWbHE^S@Qk(K!V&BlAsQ$5!cLq{+Y`Lj#wF)P?(CeCmcX-0_DEKN2maim zn`e93K+$S4Va)c-N?lZat0`vSvF}#^YzpB zRg!chl|&|=jTSm_wy!v_qBMKVjRj~+AyTb1O`=GLL@Hv0PLh744pIcrjR~=`cc>~$ zlKL0`x&0m^5z>A{0EM=&kVMImun@aMZ6!#|M8ia&Dka~t6$9LE6y4LIqXq>k=*1P< zHpwT}1(T~6R`*DyPvnK|f$)a6Y#mZ)z|Zc5!Q(0})jWM2qF4e=2R^6W!yx`MfzjVn z^HO1M;y|;n9PkRibm9A$ATNLxL^4ONrPdr<%j3SEE3tD`8|g{ZKB{X;tk00jwo-N2 zJ~?WjEgh|ow)l8mw|{R5tXG$>7utQ5pC%dLm3wzW_sf^bujMPS*F@afxGluo^af}~ z&}CbgK^G?sAWy!>&TFlAhuOpJP3U3HDF|TyK|`h>S>&(@`tnfKe-Tay-X3kMe;7RP zFb1o-Jg?Pmr_p#7l2u_$%h zeLPHR`un!q7B&$3;r_Qzpv;XZ8bB+=A>J0}hBNr}C`FG!B+!n%+)Z^kmiB%`<6go; z*_XPTh1Pt*;FVt{UfH z64(N1oJFn%TSp_6)f+7I|34{bgSVd$I6_-KB!DSQ` z71wb<9Y+yyM+Z@HLq)~~5D^h~L`6xz-#K^b4xr=rfA9OhbgJ&Tr%s(Zb?Vf9Z(SjU z5Rvd~LJX;`tFL~!>TMxZ7O+Q#j2Yc9?bq<*LJaFKMCD^c8pcM&bk?!dBU^-6bxeqd!ke2KXC}?F6(js=gqJk~5jZB`LEIyKk<~n}bIDbkF9QFJ zF+zmi*4jR!G4#28o4~452>aN1jZ5Zh11Uo?1)jUDabD9+x4d$d5E{}9m^r_FLFbNn zAx{cX@Qo18Ve>nh<~Q4~z7+JKpm%JM-b){{{Ta7Hdc7h7SE2O~?ZP3h5rK5)_h%<6 zgdg_W!Mnj*+La$rcnXcsa+ykx8_S_7LM@)%+{w(8PA>!0Hs(x7O*d4n|0!RG|E3BSQiZ4}$PuUF0H>)m z`1h#$;6I=qfd3D*8U8=jNJ}0s9gqZ6DjHu0}c>Qb&~yADT2i&16Cp&rOR=p2AXvSY(t5yHsAnXUZh>P#4H2v5E-J@ zfCGhFWEpS}AS3TGnDceESSVV=3^7+M5RIZu%oM#vgJ=@-fUQRDX$9s?G-rWkCTJFd z@=W1l5k4ECt>D^mMv9S$JzF%xW=>7dpLcgYzBm)X-;7T@I>mhCps(nI-vZ>P1EKSQ zT>v{@0Js&`c3@{Ce6*++BgHtR-GVST?%I*_PCyNSW&v8vQa1skQ?%kb11YwFp7QNR z&PZ2H;OGW@Ga!mR41C?-Kc8v+Ig{i*4!uA%fn$?wl)76KK|*qFKgqhMYf9577C}DB zQ=^y;pVD58dy>Nq9HmC|M8b{q%U0*AB#;gYX&9zZ;rZ$Yn$JNA}j^ zwDOp3l-@#=r>Va_tW8scz0auYK4(b39`UI5wnFv-ln&WNPeB&vvk|IQWXT<{B;B5U zbzl_7r@UpHfqMqpk5aT2i_yyeRoo^1DP9n7i;u+@;ujf$);?eMlS5>KJYUY0i{&M9 zt^8CCRwLCUwC0bf6WRc6m^NN()Gp92(yq{+)Lzlv)edN1X+PTnY*DsUTW{M8Tf6N- z+vT$IXs=91lC5a_n%t?Kt50((zNE78nue49pHZFR(fA zhQK=mHw7LJJQfrelpfS8s3NE)Xmrq&pxHr-gH{DS8FV7p9^5y$K6q^K)ZjV6i-K1L zuMOT6{88|c;Nv0XA@f3(hFlu*mylaS{t@z2$ZH`VhI|?Fb7(+lTxfP^QRslsVWHzg zn?e_cUK)CR=-r_Yhdveha_IY^pNG|l-57RP*ygZj!d?&iIJ{^0)bPKC{~R$YVsgZ+ zh>nOA5m!ds5OHV3&yfLywqQj$|(K*qc=z-D0qbEeqie40bS@aFj_e4Ju{dDxs=)EyTF#}?T z#hep!S} z$6XtDOWXr-PsHtrdoS)#+;?$Z@nP|)@x9{v#gB-e5Z@R-FMetKrSaFs-;!WUh)i%N zg3es)CH+4Qm;r|pL%cVx2eCn z9Ikv|j2B(cko02vw?Qdzv+``?@J;XiMJ=NXfUg-Xl z`_Jy(?t|{H-6zrqrC*SKQTm$nb?F<@H>W?7zAOEs^smx?&ah>~WMpRa$>^6cB%>i? zM#h4SOEUhNac9P+j3+X-XS|(pAhU1g>db31Z^?Wh^NGwInY*)6vu0&&&f1rCH0#G~ zEjv6rDLX5>PxhtRf62Zh`@!rdvtP=7GyB8r&$EBX3CLNLvpHvL&PzFO=6sNIIOkZ7 zH#a!9ICoI)@Z9ma({ktLF3Me%yEgac+tH%dgBInm;jrdj7op<@s0T-<*Gc{+9d~@^|I$&Hpt2oBUsT*?V2t>-t_B zdu{HW)H|zppWc0Y*Y!TT_qn~BdoS;OQ}6qFKim6_-X9b=3+fA&7i=on-6x?>Tc6wd zd|lYTaAx7tMZrb!MO8(!ita8t=1KRodhYYQS?n%8x45aet$1@?vC5O4gLzRC0gG z){>ni|0y|I^6RO;()iM<()Q9#rB9b0DN87uQ}$HZdu893Pbq)6{H^jI%1>4VRD@N; zRiswrR1B=Bub5h~sA5IMWff~H?y1;R@mR&v6-O(bm93S}RUYme**CGTyKj%ag?%gf z4(>a&@3_9x`nLAHvG4PJclF)dPxQ;}H@e@fejWW*^t-Iz+J5i$pWc7>fP?{e42&AM zdf>i6p@U)v^%^vB(5gZE2d55h9sKd&&#H!0-C6CdzP0-Pn%J6UHJ8@>rRI~`3v2&V zmsU5w?(zEU`X%)ThBOa(V`$#c!9yE|UOn{gp?il#4;wJ-Ps1J_c3^ns@R`H!7@HSBHpwBgH!9~w@M3mBI?ZsfQ{*|bnCLW|atwJfcNR-hGWrP{NuAXkJd!IkPtcV(kh z=;JDP4RAHMrnp*M7q~7&`*4lxudW+ix4C|Hhqxo%ac-yE<<4;DxC`CI?!N9?_k8zK z_Z99t+#B8Zy6<=Y!~KZ+U+%5$r_y86Y%p@NL2j1YWX%yxZJKRSDvc?EnHt$wQI6#s;kwt#I@43)^#1{WP{s*oJ6}5-6?Lj zk&{Z!NvC@ya&njZ9^~Zj?uU_+C*0foaxw)u2|!Mwkdq`UCo_=~%&=7rW>}vhKf>Eb zs;>P6>3?1Q^s6_c>tnCPILPnM`?2>U@4MdDy}P_Sy*s=wc8&83{7vwaj00&DcwmM} za-i(My$9wTXgFZozYD(y4#0{IgdM<2fe`z@WqcF#E0PyUL_DOf&PFrYiqQ%#Et&6tF^V-wc2{^9&MA3 z@%Od+vB5m)})4sB6>`wN%YePoY-K!|1C? zO;%IXcJ-WkL7lIzM;%MWd@&ofs$LAiIJp61b$zV32qU|D#r@&|@rZav{2ODted1Gb zNPMG~t6AzI^@{3LC&dpkN=C~hnU1-AUs)yVI#`#mlcriP(l3xDIpV z%f+2yt$Idm5U-;hc}2V?J`?xJN2Eg>7hN)32FOquA>(AB%#b;(=8l_TU?(kU0o z%jHtJT;3=zQO{znV!M1wJ}aM>AE4#=NW^3Atcf2*f(#L9GDc*|1d$~Zg&QklJ!G=T zlc}Og7KEhkG1mjlF5*-wm=gTx3qP@FAm#b{YAX2^-6QH~cAM0g~v|LSU3hjN47NCAbTN$i5lvjPC4q|oa3w2a|t`4aE>PvM*eX0(N z3>h!-rAzdZX`(0A8f#>!sFo$7SZ0f}B)Mof{T#C(Z4lAJB($?0MtT8QQH z0&x*mu~y23Vwr3gcgdT?M)@~!8`iXLmDh>Qa-(=y-Xpfk&EiSu{b6_7tvVBiIss^UGs`CtO$im zB_e1A2;HJh{Dj`{1lBZv!J6i;ST+1v43K@qAXy~pu+mm4b49uADJo>1sFeAlO!g4x z%dz4-IY#_NUMBu3*N8RpB5|d>SX?DnimTM@V*Ycn`TQ#T&YOI>5E>P`i zKKkJ`>I$`5U8XKqm#PiwPBk4Xcn_(+s|VF)^)IzaJ+2!)NiP_(9b=o-bP>d zBHA)!Qv}P8u=c2G>qm~0n_3$?+n|LNBB*L|om)<>sT${&Wi?~rM~|qQ>=s|0HF~65 z>>M?+)-CQCJNhiQScS!Gx0pI^>F!jCjg76H z(leuRL6ht?W5&Gs(#?M4%+{9KGI(ZN`#foz)zLUZoB*Ox9K$|AtN4oj!|Wem{{!~l zW&aKKce1~o{ioX&&g&3c+B;^piH8=nw9OI^ELc!jBsMNsIDLV*ZNb9%3&c&!nmXFi zPmo>YuurSu64pR|F8igN3c)(ArclvKJ7(F)LrtU*binu8@`6# zDh2&6g*n;Jf=@dESjR={Nsj8cc~5kiz$m8e;jr6>2HX~a=}LgGy@X$X?IUfc^?L}T zk4|ltHVG^Af$AIl4yfIzQ;)!(qt3<8C4WUvT!0q%CG_oM!JSeF1plET9ple0#WS*KQ0;mOqR7=!FA`qjRKZ|g6Jw{y7=z~5LG3b-N7K!RxbzG#Y zpRl8ni(KilO0-70Zft5Ja^QU*= zXs?IjrNdX^63|cx?aXu!k>UrY(^DSkJ!%EBSd0l zl}d+vfu2Ol^XZ;_!7`X}sfJU!k7LyJAjVz(ISb-AWZ5S5C{Xu8+SrdmI*}q+eE|FV zLj4E+mufHkPt^PH5BgE;V~UTN;v=T`kSU-C*xTpeXmWR<#w>?L&Bw@XCPvJY&<>2m z9AGf|Nou_?szXS-xPZrWZaGVKsz|PxsE1T1Wj*}4&@JjJ`$-rRDzS)Q@SO?2h2a*} zN-$%xnI>C&XXRaC*EartRO56DPcf`A3!E?yVtx+TB0*2XQQ7Nls^nckokF*lGLeY2 z>2v-^sVZT|+@>CECLvdn>oDo`YvJHJ9LaTl^r@mJ|sN+OOd!S60fiPVI#8p{b zzd;WJTcBB*K}q)P##+QfVxz#QT3iOJ=)k_jRP1aF$L>gfk_s&Y?fX)_gWbdOL(tka z!Ag`Gs#>u7Ived?E2Qs<^_Kx^2%sLyqxvh@v&vOPs-LO@l!G;mzN!{bw(6rQRSlpl zRiG+VHK0ta-ju55nKqZ+dBN6H{>Cgm&-= z%n<%x_FZzcoUCHxCbn_y;JWWS>A_rM)ll3dX zmUHQ_R%hUricGB-a>1#Op+kp$CHQpb{Y?AL5C1*jACdO|ZTAV%BzH=>+P{ID0-4Bt z4|p@Kzvsq-=8w7~&`}`hJA~_Z-E&Cuf79I~T-s(4d8$L1_g3RX)E{zdM5a2`bs}&7 zo335wuiYkkkV9HkiuCzgj$|1Qx1DLb$!41b+^GLuhcz#kT7fiv%MFM8!@XZZM!J4Z zS8-I7!}Zmjcb7Qo{SxjQxXa+)(H+x(&ig*-B(ASvm4xnJfg}1SP^XXjJ5>prG8|g` z5$w*UtJe$IiPadw4MiVExDVitYB!52aJ=LjF=qfjM`Z(-1zZJSqPqlf z2jkj`_3{~5JAVxDg(&~?fj>|5#u~7P;s2lL@Qh!qHWKYzKe!RXqvhZ_9oGwR9SYg7 zf~0aVuA7BHJ7#orPYyc|`rpr3_m06@c$BD@IikP10QVtSeTKs-MlxKg_y{Z0=V3i& zuE=OjTMaUbm(tRUV zn@#*Rz+VIW3gA}&PqIFOIR6Ij-+<|!+#%e53w*4IVYdmh_ubeFG4a6&4@UTBB1WTj z{zcfu60`+_Ac~wE|mFtTvv)7*!>#8@o8+RA^rmB zq6W`bqHmYfek}0*tUTTmJTAM&`xV-n5VaI`NB#82-lJ-Y_Y2)&{?Zfl2&ev)`cmlJ zqsk#yHSlwxryp>StL4G~hlwQgrvup$T`h1aa1X%EfxA%TXs}Dnaw627pnVH#I{R=9 z6S?Xsgik}9sbY*)h&pmB(wc>*D@8Zw!M(rh;df7Kj3sbIaP&+x(a}BeAlRgJ118#D zaKFF}hckJa@v;n@8P|hd3XeE|d~4Wc2oNRMV=2O}0NW9l|h`G(Fzy; zdDnAV`i-BjQEFM($5K+0Htg@&r2{)D|CT{A7*D5#$}se%(`5v9#UgqCG6s8Zv3TP4 zS{Wy@k%yDmbD1gQWddq#E}mch9D9MuGDW6JmrRpxXuL_L%M6(*cE~K5ja|cB*#rA6 zJ7u2C7q7@(*hMUmeXyfgBt2Ne$`e1yVp$?fWf^v7@?{0@mi9vp?~fg>0oVh4O%B3N z%V2RrR*BbTwXBh~vJUGFy|Gd;6gzCgL?1aEyOJZZFF6Xc)G^ql9E)-*#GYA^94E)i z334K4hv&%2atd}}&%>@Eo*c){&G~W~_URh&)b$KGQ#N6jZnm5)n`H}jaOTLlvQ^H* z&SATpFE5ZCasi&pUMLq~muN9|v6f)>a~akKip7_(f>L=Q_Chbhvlkc3mDn*VldI5D zA4F^Xi@a1`hP~1?@(Ot+_KeEq)$-4H=IyIFmbYM!_*UK}-hgL0?v!`Qjo9_8M0~{VKyTBjHkL1U4pWKfT$uQXS&+-#_P=1Q1I6lKj?XdiuR@1Sr_MYgZ zHFd0xeI*v_>+0A?^jlfSjw7$Fi&3*4M=+VvGt9XZu#!Rfq~zVJaMb#S*NQ zj}=Q*6xKm5#F}s{R%+r^f=U$2Rg!Y5WU)-8;OznzucD-PU)2zIphdh0Yb*Jxmv~q- zh_A5nGahR(1z4jg#M+HV6^jX2Unmuysxt8_)@UlQcGFk&6IY0dSmPO>24Y`+u&Pqk zXp<+26{;5P;7Y9h{0U=*i?Kp9Oby3={YZ6|8l^_7G1w&>i+#dz*#Dm(&JmNbTR2Ib zgXig|h;s$nYOxi26z8d_cs^ko)|$@4n#N~p2A*iZ3cIy}kM$-s56=nEF5?BNLoLA5 z2>O~nJ@2p#&lfDmGYbCe`>U}7N&AqrBYCBGRy-$e6}O37{PzA5(aJb!ZwAj8T&@0$ zrzozmb_Ld9#pDJ&g>Vy|QMg&%f@c$M#ZwHoV^8xA>}uYnHmbYvWb3`^K0M9v0Pk=9 z1G}4>vDZoaoBzam`!TGc9aoQH*Yh##dTyb&7u1tj_t=JKGoHpC5%u{l@pr8H+=W%} zJMld2Ra1gmjV#WXwv zF&KNPuc=+?b?m6Vi8l>i6pxC3iO0m_{4B@Qc$OmoBd@ox&$?T^BksY@Qjl1Kb-$~` zmEvk~iF#L@FAj@U>OJwi+Jm<%_F~0(HP)V=!b<0d>Lc-^`dID5%FzMdS^rcW!uru+ zaVb`pZ@|v_7g+WDT6}{y8Qgf^CLL|}^>}09uXvKAQEbF0`>421tjGHGS6FTQo48xt zgq6-f>_a_)eJXt|^BAvY{;02K;+c?N)k!=7;>8ZX#O}U^{rv#!?K`wUEeJdO-S%q4 zTJeFX5r4+BDtl<(M(o#O#ec+y;(f6f{l~uF+Qq>$1Q}W;o+8M`vje$!O01`rr{!zC z@QhV~)<-MUitJU>JDL_XITp6H6xCJL>DTHq<63B3J;t?!u7yQ4wfcP(-y>d)ac{({ zsxa=WnBG%p@ToGd%&*W>=y6odYn;*1-sY%kpWWWpG&i`aqor+j*N%QYD(<2Ga88zQx|z~+tJ?0p+$9thJ1yb zzrvz=J^iAZQhOa|-(Ke**`TgAv{7T^s>YDM#?VHMt_@FNNpM{^af<4y4Fy!23Mg~b z85z~(GguatIO_C_>vC7u*oUwrAwztb)pO|a1P?hS6;GjU==8=8J*uZFWN7y|MRlGM zHEg(jm{r0kxq9a2DKrH1n0aJDi|T3^kCLf!3^N2CrVD5v*4ffJvnhlOps=K>u(+@& zWO(-k3yX?5Ur46hK9UR1KGILI#jIFRRog})E4tiP6hoq7Ly{7+jH>LTbXKGMSe59C zEh;J1xs-5O6xEd&0#vevLXc`Byh5vMn{6NMr;6GlJ*d_w)>=b=TBCSt4VJY!OOI|u zg&vPlrp2Z?80Jz_7cjcHy~D7;S|b~ECO3ns)=+p|Vc6*Ag)sGwh4We)7qT*-_BzLC ze>*8PVwZASg{WyEqZhO`E@<|v86^hi65Y5xo*MgDU14J_g%uW+8o4Mkq%JjbQDml2 zXK(OhT4rRvtSqGAltT6t8Hy@1Sd|$p$_#v^E=W;Dy=@%K(>~5m43oB8&yc6cP*a(a ziLyHTc>gjgrZOt@pq_BOsWY!-0poqTt}_y@Hw3CPb#E}Os|y={x~_}L9OM0UU0&rF zubXquZH3aiye)Ik{XQ`y3yA{H#Yg1Okrin3}5zxXIL4r z&$JAnsIJHmw9pW!P;ZcmYRc?QoKJg`Kea(sZDhN~5WmI{v&P_7qi5SwSQ^}9rE6%& z$Z55i({e|Xf3X)CEQ?AVP2HMey#?`-;mN%AJkGnPx#=;E?s`J1*>5SP*$s!IgS=13oS^^tz}aldDzzq5 zz;=H{88yXfwGAO^4GX9>Sk@XWb^AhVZ4`U4X)%UH)zk;H`&y7%BP(?#H-oCyu)DgV zu=dki5ZG?JzbTa(u}e8EwAR%j?WeWY2Imsp?meDbJDvr@aL3+ZDGaT(k&7Zj>QW;Y zX6-4hw=eLkdSyoD%gRF*oKo7JB12JS2CFhd$g)aXC$-LX14VBeb+Ltl= z;AN*&`^sW_V*x#Y7t+WC2FyBQIF!4us(Qbh>T>^^BLACW|C>_lhMIN0iEQ-czzRj@ z;3LINt$&DrT2+<)A=TCm^#Xho-e_vf3IjhqEToYYrPlafIX@Jl8NWZq25u{&gkohLU*D70qXnFMvXtU0r6##dB zi=F*BeA8+JVone}F0na}PF2te+gc2UWP2Eh^PmM+t`@j*Lx(FH9j;utaOFycD-RuTW#hz^2S2!0 z>N3-Vp)4~4Br^eq%mnH(>k!GzbR;v==`u5@%glrZ4|-);OU zF{xk1v)RdKMl%Nz213*Z&uW>y5UF9PuFI#lji_OTA4bqX0C zFP;rrLl!1ul#k55plL>X+f2@BQBiSF(}GS6P&%7TOqrum&xo#z>e8?o?XB%?^HBJm zjU7vEGuzu{+v*l}v>V|@6{xDUwYGFL8c3s{t9guo32K>re$xWPH-e4oQ_Z~zMoC8b z>jPbn(GB8S8rU>%e& z{_FGvoAd;m^aOLg#+B;;uH`}8qRwcaH$8|u4}wTGgjE~-Y6|dBxq;K`TCp)5g=_}C zDu|m;zt|;V&F$@T8>hD~Lh)EU^?^sRKC~z-)+d0tR)?Zfo8HvgzSu|X;fh>XtSbpu zy+Sl}Z^A9@_=lD7O>{Rs`G?p0-4qr1-{_J=`RmLt*rPMnGwAUb$D`-g z2=Uj0r_PT-v7Q*0tw*={LXSCzG1^^^J}m-XSHDLeKSRwGv}Z)m-vwhwXPn^oOhmZ; zo(a}r@rU;quyGF>CA7Is9c?0KUSr2x;hHyh-dsV?`(s%WlmUR~$xhmrB7XMV3fpA$ z0oLXFV?ET4r+4W@7otePkDkrMvy(Z?a+XnyoKAL#&8P2})btGTqj)Pz;vJ<>k&Rs| zJ6NBv4#IzcX;x_$0$#=N1==Nm z-_}+^vdLO6!0%vHSBj6Zk}JjKnhpMk3a9#DzhFQ7JF(MCG}pp^N*#g!4Ev8V{VMh^ zz|(TzsdmBNuU>_})u1GvUgp1t{dcfFP29f5KAp(k0`~~qgK+o2Z7|%;xUPd+3%3St z72I;TMR4=s=D^K_n+i7xZY0^91Gg>W}w8PBu}spV0)7ETtRN|-huuyPJ|_BA+M#@NfS^N$*YeJ^^S27Anz zTj3ss+XQzX+?|G7kLwL^W}a39UIDiRt^=+WZWi1$xXEzi;6}j>g(G~mkeOw0g>ZRr zS#UVpDico~XNDpi$!DB^I|la^++nx_a3ARLGu{RK2HZ~EgKx%mI6RYX^32#GWX2-~ zze426;eXl|>pg+b*hg5C-4_o8-06n) z+yxfY!-6s_2sn2N)5Tl3NDB(KAlvCs8tQ|Q210c%X{aAME)BKBfKXQq2sOrl_L&e# zYQ)`Z;?j0o&@KzwVM4yVr9E%r(zaR9V?v}ogaQ$14_MGfK({gOCP3FQbhQP+nhYF; zuCzjR$QQcIqU!|I2G>lq^q1D0X5rGNo1u(5_mohgn_%I_5Tx_y4y6speQnx6_!Sle z8#i#hEQoM9Oy|S7tx&=_IW*S7g8`axue6}mfL6dQadp6Ng`4Ff z+%(2bhOdVbZXDxA!5`|XhTk8q%vA_K&%$L{kn0RkqJ@jLpim34TM(roD2>z;CNA}u z1$|{fhfT<3NtJrQ#HD_K`0rBAQ{S+lohFpF5jwq%LJ3OU&U8P=ZqLAv%UOn2;WqaW|jBg<`B@y0!4vFmHlZF|-`eB8KK$&>Rb*(3uw9RE8#X z3mwb2k-*hkbb}e{YtfaY7Nqt_%}7m2jklmk3kp61Wb?Dm+r65M~agJeyGVU9~B_HWVchJNo>(ED_ z*aP=gvJZN-8}215^jQnqYC(@$&?biNOTIICeew-}ueG2nEok)_pcNKwi3Jgt4(8Ho z;bvLTwB$QoD>!tr1rcr>R?0Lpv#MrX}rsjGNHs@E$FxfePcmKEa;#G zeT0L4_rSfC*d2P6aW8cXeU@=s;Xj(V3I2U>cQUlzf^M*&Yc1$X3tDYKD=cV<1rcYR zA3+_=xz)nWvY=@uM7ak{vP?E{eo~FIaH9YXW!h>B>Tf}17E}l*kLd`?V#sBVK@t-a zqZ31cwT_lSifx(BTo_b{}fTj|Q_9iS(Sd=i|g63GzObeQ7 zL6a;9xP-AB*N5}P7-`YfThL$&>T5wICPcCr{0dB5LJt#4bS11xt>@G-Oo(s^DU6FZ zaX4|(qzkqnpL{lxUwoGZ{bWJknb4W^5`WYTjXz{Tmj2@RTDaW_tKxS-*Nc+&LBo4V z&+$9po+ro|No_3SwgLATLl0Td0~SP~8#(m0Zn&EmhnB{OOLSK=?lM3t8CqsRofgz) zLCqFKF{X2jbGzXtFm6mY+;9u0L$&b(<10YniT^FAmlc|0L2ibe-Qvbtq2UY##;dqr zp!F7Xg9TlS+1*ysY21~ljVMn*t1W1S1)-fZLOU#| z6|}P`MtmTkX#~Z6V?iHT&|4NX*@QU8IF9j>iHm#If;L&udJ7r_Xeh@(D{4UfEvU?b zh^~<7@-X&pi_5~j%YqUu2S?-|AP})tV9mFoj{UQqS;b;b=&zW4$>K5j|!r~iyry{OCQ}>(a zb&~XO%|4u!?tI@!-#2c@y8mjNPbQ_JvwLKoIuCvs-p7;DhByDne};SwtJpF`?PZMa zuLK+n?g*9N!;hpL0$Ht5Xe8|u0E3+aiBsH!6o+YV02ta8_>SRl+8dAwv^M~}?jJ?y zFT6K!lJ*8WN0? z@Vaz8<6&P2Jw~B&63eraWRsUOhewEmT*;wHIt|`2BMy|u9L`;iwwy7P#~hLwKIJiy z^V`L6j*%{L4rEMk=AUEul%q+UBVJ#ZIh?O0$RBZ|-0kPRf&HAvhqW<;;a!3Kyic&7 z_X%D^=>gAi7vViMDIQjr!vB_Ieao8pmSg=y=>ku?3*TyVYR$JSNv3uyQp{w%(Mg+x zr_`5m>hE)jEMsm@QZB?Y=Jr0v4dGbJIM(~DD_AhNIms&2OoG)+##d<90AHa!2!9Ui zvx4;*$*IrLE~ZennF`itFAjB)K4FKX+g_~Csa!gFjE`h|g?16e$~lDQ4x zTu7oeUf+PF6T16oan^~re8yQc(NCB zOXbx0)G?XLq1TZN*pnm6zlt&Ua@?!9^cPVs#3J6wTg0W=%vL&zbRsTh8Sc~8GY!>H zt`T^Xh|OMIWg?j7D}B77fCtBg4~ zm|Gu)8`%aN%%KlcRxn(_@Ou=hozJP<&G@?+U(EJ4OM3;Ji@BW{VBo2p$!41mVfl+W zcX13Caqfy4?#rnc8$Pv5{aHVC+@cO(4Gc0kP=1>@zaEx>&-s$YoMJ8Kx0ZH@Wi9O@ z%f+;FENhvv7T=+;tR7E#s1EWJwOGmnjwIQ%O6!vXVLUr=4BE z)Fwo;B~&t>O1!;E=hu-fRdTF+rq5^H7H}*Z)92er{(O!#)rP%GIhAFmH*kUHxRW@= zNu0+?%x4nIJcap8;<#6FtVvAIEwfz4a3u4IBpC0AQJarZ82KD}kl}+2FSiW@ez|Q5 z{LQTM<*d)UnR5qIb};2|+eoIt&Z=C_mav>pNXA+|K;pVwzayc01EtO>&B>`B{ytNmpV8*PY3vC2=*Sf>6{Q@rzHyir?^^d1s^_3Qzmg-50^zc!-6fO$wn69VV)kgkSw+h z!M5SyR6J}I9vx%DzP-${-41`9Ef2nna-kA5)IRYe*B1}V<6(K4SkL#fZD7_yX>sZU zx$FkA1_pAum#_{mprhI6sdRzfi6dLhYxcXd(X=rQS;l{jc85i-%&yAttK$0D5jw?wP}v{L*@T!?eY zwuy`QOJ0xDm%L;&-d~@F_uKI$FT8cW5SGzQU-H5m;P{dk-r&ZUyySCu3pq~yf_IM7 z58_ZZwm za1X$3gu4yyCOFuZg#F6P;8wz+4P$&Ka@mGcD}p>I-hps-2w zv=TjCRsqfj$r7sW6~Ca$JNwTl1)2vK9?kxv>|enC+w5<{`QmsQNaxA^R`O*C zr+5itu3-Od_Ag*xaBn@Cd~uTf>)HR1{ZHAyll^zte~SGr>_5u>7#i(VA0{bt+_kT|61b<`BjkksIO*Wyzr$KfVoJG&NguWEA0%u83-Sqpz z$x7Cr_YLpo-fz9%c&RM9{dwsO48eHJIdP387^g4^oNdZ~-e5^W#~tg#CzlVhX#6zhpEC;Y9@|e=zc?lzre|I2QhGo0anNZDZpbr- z7+UNuk$0c>J!s_}GcE5Slw|G4WRE~O~<_-nfy=#zW2VY z^D%K0k0{}+7LD`xBX}J5wJym0NowbOX%YvHYuT$GPi}(|pRLOKDbrf~bvin$%KSqO z|Js7P*+6%DFlqd+XQt@Z#-jd0mTs2i&*6Ur(~SH~e>6AxKl&r9B|YK~V-D-DKSn|x z{#hsnG?W01JJ6q?Opc=FuwKd6ZPGuVMq9#mqK9^8cKY3!>d@&_I_6Z4r^O98Jtk`N z5mQ1)Z}d%PpySdqDa~-R6j7c&tx=g}00F zzuEsD()DG=#nmS<+mt%@r%Tp0@*lUhrS3KjWg7WaN=m#&Z7AMDbtsfaGDanr$eWS9>qH% z-{3cZznL&l;(JPB627REBqn37m5lGtq~px6bLqq|oIO>A^T8JKSkAS0&BbShF_Ptc^8mW6j#2B^Pu)1iv8GR0wM) z2zt367}859>m`i!62N*1V7&yeUIJJz0j!q*)=L2N@-fP6AAS+g&Zj83L(q|fb>v_j zMX`<~bQC25F$;~x9E&uiSVwd!eI-sJ>nMjhr^)}{=yD=+u%6Fik-nyqJCeGWTAMw2frY;&;Yj30JhKow$K2!&;Yj30JhKoSZJLH!1-nM zuyiVea4v%gw$@0t)+nPq$XcU~Qh5M28^dK2%ViVCWn<^Ev2)qjxoqrQHg+x>JC}`} z%O;-7CV|T)k;^8K%O;S^CdnupDitS}N($R=2$v0gzoQbT2vXU&xNL&iiqp7+++0HG zTtXRKLLuEsh)N}sOC^g-C7Vknhf76qspN90^x#tI$))1pQpsbx4&w4iMp-PUK2%iV zt8ClxjkYz~3T=rtN-M!hQcE-&&boRP=W5-DlfF9DRBby>GV6g(WaX6Q698UD};MBifGDF6)3&x3m_;wfl@U<-RC0Z+LL+%y# zp*)@uAM=@l^wqRRKL73!oME?H?uEQ`b{n7DW}Mnar=uCCp{eO=2A_jAk54}9#F_5? z=bF(OWjIX?r-jj3VLNEeS;eCdv!VR3n&CZ8t14=CU zS=c6E6|kTAI8kh@nJ^F3JeJGgcz~&}HwdZmmKmiD$s9;~E2NFb>F7z6LluvJ6z>6? zcf3cPgPcg5&?!)>C|5(^E`hrrXMx7!EKbT}GShAa?E&U<6sOW63lyKYA=GJbH1tAu zps*92dJ67oxM$&Zz`cwRXWHflHznvTvTjkdPZqX zMuLnlD~&42l(E3(${c%Kk4*VUW@gu@%yNfKZcw&>u3-W4R)?*t5$lkD%gj7^WoD+j z(0=lMoEfSn1f0Ayz^*0&hOGxfqJ`>ttdF{csM75A%#57UlJc0cvII|jLQH&IEMamr ztvo$Jj@;u&jY@WEKL@7AM5j592V}-Yrv|>azFdaKsI)FyOq?q|C|FI1#bZG+Cm#z7 zNp{D_$RD~^FIYhDn{ry(CH5RxyATd7T+lqt#9wLQqj8Sq6DHo)-@xZ;j5p%x;q%l& z&5W0;ImMgIw|o4-r^OEwYyJ2yIxRdNr>AyU>7O1y7N9m|EsiRn2=Nx-t5(lr9D%j=Kr& z!i$DvRSZrJDElOpY}yrX`%$-PJX;YO*}Gp%aA;6ak^|rFF6~;D1@nHrq`YT&RzhH2 zsEV|cr6(nYg{TJI($@zD1;+=3Fv6^a2g60#gntH<-N|r1K&7IJ^zi1=TUX`G&Dt1IANNzN8$|drd z&T7w0FOSRBOCU27povBKl_sRWcrZGy>&fV(m`sJQmfjSS8Yv5$nVHV6UxI_)BVbQ( zunb_#i_XlXuD$r6olLiPxe`;7V&l}Xh>&z=Qd-a}F?5Oe(3zQ#`E ztmg%%%~BgX0>(5OGCMJLDMGpE){$B6ajCf2aFt07VN^+3aRP~p0}xP3nh(s8tEWvZ zm|Sg38#AIPzkW>i&m`TEN5VoMO)bbzek>^X>4LH>?72;z)MrR;@2LE<`d5!Dh{|-T zYG>x6$bSXpWaZ~}eHHk2a8Xh39<)Q*1AX3Poa@~Svc$*3ZgX>B7U2-arI37iS$smg z-2uTe3KZEql&MOcK`~)H;}T0#%f|Ol%N#haD7h>tu4i~`NRqR>B6aAWn);SDt{&BE zoVq!zA|cuq91@x_XhO+=$^BDL6TR?53p3W4DUnrmVt+=%ALTN=& ze^|w3gucowqZm&a%BKK@Rvwir7Z06(R&M>JjbBrdd^%`Mc3iL8KAVH>YFk<3#X}o! zpQ@L_$;Yea4(c<$DkrEb9-kuhQW^n;+DcmvEJ9!u_zg~7zI*Pb^o4euNVy=!y<8qVQ zX2^;ef!b-||E7+Zc>tdCpbl#g4pxSo;1uO;nE8tavkv}d&4l@{k)yfV9S#aSLcnJM zfii(H55rg6sKQ0P5J;E6ok4oNBNI3Dsbbj%`mkog#V4kWz*E1i8tx<|2Y=YcQTG^I!V?LU~W zfBaZmxD{^355qk0a--y9ZMUBm9*-~O-eQIKI4wLDCn4N{@B%6e?r-({CWwiC`l0?- z$A{qDVxK;#Zs_<>@tmO_8J zjG*sOdyM|zDm>3qK{~RU{DgRONKU;24{k8JDJyrBCh*9;te84kec&UnAGvyFW#!D( zBl}Fsj)-t41x5uXRivTS8#K4dH8de8s-1+`=*)--EtnTvF=N$;5vyiY#Ks0DhbQLP zY$2gl^Qx=bszQTZe~-v;Ix{kzyJMY!De2G$wbNH|9Uj7UCR%J}8`AMqr*wRjc$RJG zRD7g((P;1c;!N_FEcz4~>PJtuuJZ|%F@AWmMI9f9RR^;-r>AeiFwUYG6O<6eQy1#P z$)tRDGCeN+s>JM^q?C*-`Cdv!W-4yFrpTwe@W@D}^W@W{6l%l#;jRxCU^GYbvXe$C zJ?U!>4JdPr5e%En?v~E!sZNPcO^sLW2`MQFCy$<40(m4gJ`Uk=DR22F?+=qGWRc!F ztdLM|G>S_g4QG*?^>Q`0YC1j=HI91L5$Iw3>7Dq#yJ5jtBPGp=#g@j%h<31sQWCQV z_!NTi_Xw1{VETOIzgvtL%oJH4m^#LjS<*a}$KBAreV56vrgC~(Xl_hIYG`b35(cw` zAKWVYQ8KcY^}e_uKRPNYBRVuX0z+82k&s>I4rm^1}YDykc{%duIRxzDJfaOk-Z1RgoZ@MM$kmaoB|EXQ0H+WZKO$0PEvGqL^E9ZHZ2Ahv{;Cm-!(rC%`>a2RFM13~p>+rnr#I)$H z^8)19gswSgJ5o~8u@+N!Uf1@R_>@fbTyAV!bXWT|@~niDgZvv1F7>_&X`*aqvy3U? zd0h3;81)`8LNrn8cC7H|vkpo+SH8w}|D-cB3)L`wAx2s07Uxf+D3_>>wg?^vwh(8m zieaaY@Mx)mSu2D`9VxM}>Kn+x)asD=DOyZZ5bop)b9tOIYo{ME>?fgJ$QscC3Y!`}&eA!_xx4_xv2= zO3cYfNy*H8H7GeeEIH^IryH_ltEVDDyRKBSGdUyq*^ z?sCYBqVO=TJMrWb&di`d`F&(pR-)UTsD?N*LqfWoq4JGHw_XazZQHn17g6cJl0LRd zdmUR6<1uupuS5lA=Xm3=1NRUawf(G80v^mPfEn< z0ISL6>Q#{WqD)UnOK~_{J>u0YKdt!b?Bs#+Aw8mOx?KIW``MaFUb1HBiLKeJOU>Qn zc4Kty%je~$UbI+oCFKV-xB~k!+pycJuV$4|eo7N$g3rpV0_LpoBG!*7S?Nh}DdG06 ziz0P9jz|iYYof`}OU~Yrl9-q-Wq4ZBFqoX|8o_pkAx&s_S9+k_PPZrjIe5re6s6*p z@^y?fW2nwm(b|VK-gGHPNwugPzkk(*L7)4olniJ~yXpHM7oL;7Ys%=z#BoxO#jR#Ik1zE6B#1lw@Go23_9n8lCrkT(we zXq3VF;W;YB%hf`S{80G6IUM=r@wLvE^J~V_$QpHg820$B^mxpnxgCZ`s(j*GG}OuuB6Lhy3pXx5T(ZRZd`BaBN!W$-Ry^HRX2&O-qf7 zj!^dm2c_V8axxZvFZw+RS@)2T+msEkL26SneP!lnI!p<90{TCHA?X zNcmNC)}V2H2DRYJ@;n|ahD>oHgV(xgu!;54avF0QLr#4W6|Ft3a?93|DHRn{O11>k zNG8*HFeWQ8F)LFmqW_S6CAXnPfH|aWikJyYN@y5vU(1#OBp!4FwYf}kerC|;p>y1 zugokhEKX0(4v$I>{aw>d$xKM->5fiFO$ZCiiO&r?D}HEtoHH&uBrHxY`#mG3S@lWv z7nDx{?GgE{B(aVhJl#D#sfWokgc+CtW)K(=7?3C^U|iFpt_ekdy8c{O*~L{+46HfJnsHZ# z(HSHz21J?H|L>`~@4nYP4eR>z^XJ3de)rtEbx)l-byA(GS{QaKuJ+DIC?7UCx_u6l z$!IN1_jzIgoAT3ehFzE%N>@gb^E^RTH zLV=o|MqC0+Sm@BJ6LAVrIg=T?4RdylA2 z&y9M|Ma{RyRA`={{GHF}j`Md8;}k@SxruLCuo6mpi`zy5?$*6Ti_x`~kK%N@W_gNm zi1Kz=S^|FQiu%K?aBk^Sd5X8Ayo#5wg#Uo-o*(J9@*YE&Ky;ZFOX7XT=e}x6hh)k_ zcj|@s@`?E{-j6g#h9I%r=)zxS&sva~D;73~%*uQ^U6I=-GO4kAc6cte5UC7xXJ-eJ zQZ5$FN~NVM=4a1OO+?F~L~lG?4aY|M5>pphefg-A@GB*=CDiVU`4X9s)7d`R-8)|i z>PKCE8)I_ETvz=zl2dHY%$2*l{mxKNz-uy@UGbQl3R`|y0BV`(g%8Qa>~ zb#~cT_4@Vl@J(Bx1!@EPZ?u-TUbPs?<*vz3bYi>Hy`xim2gAX%%kAm&^%NS$Ib=1W z)_kp=StnB@1fhpscpZ9jwzZ%p8;oXe$^D79?Xz@+*qA+yU()(yIGmt=;3>5xLqYlz z#&KCPA`gssfx|gZ;U0bM(Oo6rm^a+crGkK4bbqJ92V3Fr9&b|N!>w?5kN={=FI@o- zt9EQ0^JcB}C+Wm$?rr^9x*9%yf@?wY6G>4tV=iDEE>X#w9t|hwuRrUo8|Jf7C0Cv= zmKQtX(&wOx@7#9t!otnlm{3f2_N*@!*Z0sJwRi(EYOdz;@vFSWPRtfH;pE{6xEE_u z$-@!lX#@+nr{OR1dYW)IPR6Aq{Vr?%%X}ujcwh&?`u5gthk1 zYvluC-d6OJK~doacwn#O{Y!Li%xMv4jdSTGBCY8cWG*#Gp$e-N`6-_k_Wk8nzm@Y| zG%0v5Er*kVuJ%+_UOAQ3KG~HtA7E=TBr$7Y&z6W>DXf~$;@tHOt(89b$<5X`xx$Y% zvKpM*%%T@KocFR9HZSAj{0{7n6B6UfZ=zHd=vaM2@A^!>0SQ9M_^c)6amUTi>ZOt| z@A-M=>mKR;RLJ2xeZSwwd|qkR=rG0-h0~{z3`m(`Zf;F~p65kymjgAMC?$<&%kWQd z&5mp}1ndSBJC*fYYcIa5oF_Q7hmyItARu+FHsJy#?IC5bcE5RYm`t4|-ZaQP|N_qUD9!K&}V* zf5Kd0B&IRvLiu`%$tabSl;i8Op9s{?jrrN9>_vafUte$(9CFh2&FO#jOP|a7eV+QW z=R6jZ!l(bu9f&5w(t5W)oH;$3@*`2tci?wXl93*0g?0EgWHe5{{rXl8)A&H86b~6y#sw z6#O+>40(ZkY~nNlCkhI<8yOEI_XM0MNN}UxwyRm1Y!Fe}uKTp8W%(u41`Qt8-H+Lc zMlD2dQQkpON)1j@PrzlI?n}}|e3hhu_-bHNvvi{tquxJDbVENOgPG5Ai2h=&LF&F5 zQz*I*%_?Q(va|jQJKIdesjm;`o$O{y{rhx>P;JELtNRTJ1p9Nc&&QrLsydd}&nfn_ zO0nN_+y$H{Cg2|3%`I@Ejey&A4+=Om0`Sz}VSOVj$Af0f5TSDxNx!E=~xd(a;CDevuk6evazdkV+GU~82uTTqNRwkozOjkwNVZD zcT~7hdh}fC6<%8Z1{Io@9z9~@?>wcuia*_t)-~QKNY6m8fsaFQv z@6c-gVDsrgKgIlXAK-Z$;=9*3pJL+GBs~UA@cPEP(r?tKCh3&QaiVQa_(@gL5`4Y> zuvXhiOb4Ll>>@tLQe381G~Q~o!h|@akkbN}n^wL32y76_@DxwCG@oAk2(^QaLAy1c z9#fwdQ0LWHcStQ+;`yZlHMsP+_RXi7JuQ7ggFe1f@NWTUxTlb7iP^71tJssvNt*p!o10aAtj&kE z#N(Djh2T+QB z!2vM!lQ$yVDYA-dB1Q=!ahsWEv7#2-rkbfJ12qISnLD>>s`#>OPaxBkcKgD8a}sY#|<-!S55csn`>v;;OWn0Gl*Gu ztD`wfzjJh(lyYUqs@IzKFDK{=ia@?Fmyj=P2d$aVO<@dfgtTc$ zLLPxETR7kgA?6GIicO@>Fg#iHDrzw6#gp1g?;nJXc zSm)4=&YO_r9yucU*Tr@MvhPW&i+2?mha9Y=9mmZlJD0{x_u-Yid+)M6V7^=y|%YOJcdXm(8}X z+g`3Mb(tsS%1l*>haxWb@VVWOQMbHPB(8$14D(B=MHbw^Eur@dxR>o38n_;(0t@J6~ z#f|aOQkura2TMQxrVA?A}#I(i9yrw?GQJXhZUXkRgbmsVym9aL{3SJIG!OOArQ$kBx^B!x^ z?#Y*fEAm}w9AgJpjY^MAt{QjnaGF|?j0FW#S~Sr@LCh641xzXC*?E0q+(}p*b7Q>z zCRv}=On_{)VFH{7z4-D?du~=0HU?g_lk4=_V!`1yS`t3e=_LE%owARkhk}@ABR^Hu ziQFA&c&mN1ijACQ)$wB6$+n>NGkEax7rh zdtIabyIKs(%Y+Lhbd%t3!ky&NFqc!0s%xx@$UYh45=p>M(d-H5_?7UJl&#W$>u0oj zo~Auf8gQpzn%m&uRUo>Ot+EQ#Vi;*R#C~8=^!l zcM0k-Lci#r%aZIElv3jtO)Tqpm+4ad$z*>@+(|q@`$xT}kPg84e?oi}xZwL3-G5rX zk0pTP)be)1Mui)tKa!kSew0eKHE+~(^kx8G3T2AC)XYs7c1n)foee`{VA=-lzBuSeH z=qa9+O1}Q{EzpzqQ`y^4ua(PXDr=IST)vk2hxXsXuG7R9qK=2})}Z>YsL;FwD3^wL z-9G`xHCjs0<^8(*wf5&FYQIr>#!2=4lv9BuxA@8<-vSiW(IG>YD_PQ-4ywSYK@P-1D&}11ae@1ihXJM ze7u$gt0oP4{7y{u$t%ofJq10)$cFGZ1fOqUDt?4I%pZ&STazxF>1ZOEiN-0r0u$io z68jJ8$ohrRgx4KbTJkLP1v%=A1^5M+ej1qebNMP-`PiEX|Hqd{b>HBv+=F%*rQ=}~ zf^4T8FlEq!gPRHko5ZnSGHkQftTl$i!Qs z_7fw-TlgmPaDEZclL!WhELjgmr~_HZDV;VW4QYz8$w;UoQ?`caW1&#v({8tm0hwl5 zB^|6k*!C-5G3@>HzJK+#Bc{d2Az9IqlJ^D!^~YZG3*YJA`2T(TzxzYs6!q_h`u8P# z54fGpdvuTPt;>5gJZSv<4e$`7tbV}@;Q@|BXZfM!OR>vn z^V`p1qF%z@1Ul?)d;)uQBpZ3WT5!b#GYJHt(1SW0W1(Q;$3~km6!bWMY_z|xL3JeW zI^(VjBz?~544N*`OCngx84DjEjiTQJ-HgAm1(X6t2NZK75frtr)-0>oz#KAXlYZlyo>0y>DT&`5#<%c@3#=GjkJqqh!oN0)Y|`OX8m4D2o_P51<=^VXUSW_N%YAx@_`rD zU$=4Nb?e3Tn)Y?2(zX6_pk9KP|j+TC~u_A|}=+l~iyukhA#`EjcDEbb~LtfyP7(IuF zJko3-*eB+OAkhwb{w@A|KWI!Nk?JH% z70(;*Q4C&%KcZ#|a4K_qOq72@2eVHtzh1&@ms%)S?;rPx8-9u_$ z?w6YHHJ?ADyRW6*1|H4lkKlZF?YkO2&F4?(-qw81Z79OG@f_o6zVY^g^o)k}ue2B> zaUMkl1f`#9;V`ls1@!TKS{*zpKu|;l_HjOfwb_UYEbyp6>r)io zW80d&^-~p^mjLD5cuMz$2G{F9y6Wk}xy{rX4z zrFnuu%o8+cOexj?YX%9L+Jw34M*MB&3F^;4_wpst=MXkgTgi2whCk-mp} zJ!@h_5r*Ct8ofx29$w8~7o%4Yqkku%@LWp_ga=C|Fsr<2MTnkTSL{6;qgKC0wH_#1 zltwfjvtIalgYarhwoIib6mL)aeF?uem+)cTm{6YQ&IEHIds<1woStld_6d;#1`Urd z5Z}I6<=a|;{lr?;3_&iLph|O$9rS(@xJ8f z-p-M$w>c|rtKJh!GE*olhrMQtoEfh4%;jCFh^yqW>+Nt?m5>tgn9Xu_sM5QTYo~Sz zT#1q&QYra9PDu{ezgvYDpmPAnXg{vINB14=J)$(d2TJqxkK(OQs?a<^`8zl3PV#pS z6J4}-et%gLgJw-9hd2~{)+|f*?8V%k75I`pEATz8S|maAT5I`dR=^wO$ribpx0AmI z2@{7Ua}7?xnW3y$kr%FdHjp%?0_Hq~Tt-k#?MQV#2_2^f321jAa5MaNu64u?0pRja zgwv_<-L={My{X=)zPz=6;M}pnS-0q0Ytoa*xl_ZrknD1V3i4n_s6FmZAEiNdZrJ5Q z7AX7lz^?IRbyHVnpx`h#2X~E69UM%_qNA-2tlRDw&05SMpFd)9#PY#x#+|6f>NChE zzdnUEn#oXztWC_kvX@A&fv;SEf5_F1*w_UgG7mR^IeUZ}!pMYZg{L_G1O;sAax0b% z_-uB+!>NpA0=?CEMsg&BN`n5~fI!TQ6RZ|iqFGa9u$z4;oIyXUUqm1M3+IhLS-z`6 z@6(T}P|S4cj_WoO9CMbyPb>X0_H`{^e9l0lmgc0bhyq2phfBf%^;ynyCv-m&Qi^|xY*B*42H)B&P2)g7PaR$h zdXkTs0bT=1E>ZSLK9m-_^5%B+pu1>10ypGFaf|Hd9c#D-v-*3LxeBQ89MZFC?n$H_nDu1rw(|q2rQpNjZ ztF(T4E|cx`AF(&9;(_C)x@q@5>+Q zzJRvIv5Lko1+k|W?Eu2_K*a*8Zqz-g2U_(?4vp32kM z6Yz)CY;RGXxLd#?dfe3;Cy6qUKszr&wGiV!=j}2~FOJwA0Owyn?jT zdmOotzuqR8kQ7W|d7$M} zyY8l)Y{{x7j)ihYERPfyi8?4W@FT1e2s)Zvb0RefI!+7Y3pj2`0LAQtkbmR|TA?MsV0@{ms%uA5r?ax;iNa3ktYu@Mj1P`+=esH2ZGT&GM{2 z%s#_ng%7Q0nIZ73vCM|RCayI3C5h9Ii~Leb@X?EjEiMkg4`2t>G>nMHSc+ZGNND<_nxQ0#3X`aOhwy zN|dJzR}RffkG6{p*NX=J#HToZxoDa{*ig`V6^y(_SwtQ9JY$Q;aCl3ue~WUl#6 zvjwg1Qr1fAyN}?kw?=NO$XZdK?i5kEuojgQSu5((Z6a%>%42d#&O>Cc&{M?Zd>XD? zW(w%Tw9gP)(8x|9C`HvkK3`#(sYW6N4xdQrlui)>3 zRObABU?qQR8Lb$p4QbfeSd`fPf8zIsns3qa4c7meNOSGz?o7IBQ}NoisyYxNv$=Xbzd6;2i|sDFXQg-D6sxkkk|JJO;kS4*$zN5++5U+afrj zU;$c2Xc#RHhZwgIAy756)TBU;NV5#7cvTI7%B1W`+mo1NPmUd)o<2M#uGdU-cTdp2 z>zu(h@7CA9bMtHV&0bgw$)U8{HJIt&)>YVf_3%EkY?ZO^soBi7j-Aurf6mw#ZKg5Z zJu=eWH8S!In`g1@{B6SrM$!W@egq$^@rJ_yu8}kyJ1(Fw? zPixShY0y*iYe7$L)S&uat?bhu(V(=Bg4av_^;>WvS>t=}(@H;H;82(jhxiQP5RDD& zjDIg58_3l$Bs6$Iz%gGkuRp@a&~g3cqTKRmoAiR^5aFhBG|yrf6z>_%((13C@t%pD zNA+`TNA;Upp3f6rkdVjOXGDF{t)f2Z-HrOBBWILH>#01|hk<#G_8i~g^BOJmr90nNp^eZ zQfFm-d187j;tB=bzxB$BCshg!mo``1OFiAG!Vvk<410BAT`6((i*hvEQd-|pT_}|n zsvYY~=VcP{bUL2MNV)2Kd;5H~W1(DL=tz~zsYH7_Yy>~rO6M%YI~VZ>zU!(m4M=Nd z(v657_9PcKuL(rju)HW5V4tL`yDb_3`vQG?q?}mD2d46yN_J*{(bx2f60-%_g&L}$MJUoq#l2dx;@ zp3wMoV&;N@soL$f%XlCo6!JY<+@9ze^Ckmsb4vCkJ)wM{|G;$Z_K`PQ2n)zS_PF$K zw9@_93eiN7J7LFRAB3hsM=qYJz=c*rtiiYjhaR;A9G=cZqLxkc#^hMUtAuQ}k4OH% zO}(B(!fE|P#8z;O?CPApW+}H2mR+gW8!ZlhVyKw!37aiR*(p2jQ-uBJ2wCq>x0%Nd z3@*N8*z2;#910vKMkj6|9?W;lJOIt*QB12=NeQQu(o9~3{VcxN#?I%&+7KwX*r++| z#%2-dj~}%?#REO*knCl*+8k=9Fx@0{xdGIGguonzXxNH%|0-4Tyu)GN5)-GeD_%3M z_TRbf5r+%yN9LiwYc8J|N+mk-zEsjIB@EaHKgAKM+aeBQu`e`pWNh|2t0LPnZcp52 zb!Wy)`GL4U5G%TW8;B4wEZ@vqy$&da4M)c?QhR`*5$o&tek$tTo_g*vQqMT`0u>S3 zJA>(C1G~mjuKeubjdq)oiv`m&L+#jftbL?d*ff!!I6Rf?jmLYF{A#UkKEE%$|H#3m zfIgU%QzmO+aK4>+3bE|Oj;_fgt7$2kEDsonrF92`N86hz;L?j zWT+CwlKonHsdk`C-6MUPU7&adCeuUb4dMTenGRRfnj0<*?i(1`H&`A{zbaA+g-VfP ze}8?)NC^qCk&aktgk+HDov&jxAIvYY(=@uIF^({2*J5j(k<}Sl)jJ)#Cc!1xcxU>+ zz{HVB^h&fh&HG0BdUf-G{`C2mUUXJKA4(`mlXL2v8gmz8Lx<-kj!ayZs-<(axagpU z{R7zujT_*)>Ht<*Q?3yr#Ox4uW8!ijy{1_)U?y5!p!q{z>R7Cl7Q4FFw^!D8#8XMg z{gkzD_dsoTU*GQ9!0x_1qt)st{Ue!zZ#>P8Hl$=fq@*ALMhz)449^FAVN<)wW0vL6 zexFs2hQj{Gg3&f($`x|f%u%KO-~KRaLZ${zg2A2uLf*pn(xhXf&Za1WT%y`BBKP~l zR?CJ+!SAsvW|P}2E2Ys$$52?#24;*e^(u-t?8DyW>%x5@Ka!x#Z6UXkmve)0rCRb2 zTNRH7Ow4qnpw0;P?rKN_p@)U}CMdI7K=SXekdObI=yJ-6w+)7Fz$51pK~K=X#h>m)Y00WKg^wIqa9Mo9&W5*&8bj z#|S%68D|XNKpwIx3v0bS0l%tYxquS1W>#Ogbi3he?d?y=i8kX0ZDBJfI5T_RrWA`& z+3Yoa!D#}~Pk`vCxoi1ZHqS1n7z&qyXSSQVlYc=aI1UeK(FyMfbbA!9--NATkXM+A zMLi*}HR_Z+davUHK1K2Uea4Y>_oQOIsg6w+yTcptcnn5^H4^m3E!LFd%~q%E_68%j z2g2b{f4OfAMhWri?{GrWb=U<9Ef>7Xr7k+WkT(WQLiDfVTdW_=hOpgHM=?|_jt_cg z%l$LO>4HBFGbt9ccW*BDo;4f~DgKDr)HyOgG(J%+PvsVq!9XGr2quXd)#YW@&n`tQ zOUShWESOgHp=iActoUYk#Gt>%{w|*^``#1AktdfKgIM!zvYS|25esqsDQu2odd7iD z^pFz2V@o)RIgS-s1C6#IaAI09{!9hUbkT;P(mEsy(}i%}V+fV9W4YXDwll!8rNUI+ z6ApX)!Jwa7ASaXdWIyb{klAG}CX;lWLo$;yJ6*joz<(QXdi;KmGw|V9z#qbC2(dNj zjNVt|fqtYLh*r}O#wc@2t@7d3MBw%@jlk6@BD<0HEC#LZVRdVa29O#4))2c& z_eqpN>~VPrkgnxU6Xd z;>#7h^)G0uLWiPuBYf$)g~GQ}|@14=+%2Auzhw}`!OK$#+YEpYxbAcXU4c|F$x=RW`fI1A z2}6{~NcW?L3^c+be7^;(?G`0Irq=O0soqitzOh8li%dMnh}RFUs^QhVh9W!Fs6oG; zm&h&uk!|GPxLYmpoQlQo^hsW#fHSqWP&=*=-}oNN(P{yv`#e@!fJVpE$vu)!qz|u- zB@!_QU05RKp})A$JJIE1*n#5;^7@WJa;oaA;eZHvgi3z8R!XsX?L1;gkU8M|i+`3>;p?Vx1Z%-iCK5=BGXHzX@ zVv>}jxs#_`nhz{v%kAt0<{CJbhtS^Us%aR6u*iTKNC5K{HZ~d{ES5k)<^KkC*ahiu zai)+O&P02B?hcvI+&?&bbWJpoBn~W7{jFGDGX26>GVC(*r0x^!*jgj-Vy*R0wzdoj z-ns|bD0@PEXNCR!vHVoNFp2*Qg~e_sO(+9#G@E=BYy z+TR6sC_*-LR26w1uzOVrT2fZg!_IrzWf>7V=c$B z1^af8|Me`}%PvEH4c95?0p3nyh9Ca%F&e4QVsK*zPNd_IrWECY!KILd^!{_~2gsam zzOTki`1>qR6+EZq^YHTe*%vG?y?sS_{yknlzK7VZxTp7Ve^kBa_&4#v{L34#77zIF zp5t?rBtOp&L?Qw9JYDaK`2G0frxkTQEP?jl$=@&X`xM&qR{lNp9^a$;qwq>7hhUNI zg#3q3wvM)h1kVnr!5J}Qf&qxnv8>C!@$kR^;xMjYI54y^m)STHh<(!Bd;49xcHMP* zuQ}^hJk`r@oSC`#^0F)BO`~oX>Yf*M3$9bM?)bpKjsQHH%VeBFg~JT`UFa!?^ZfIKw> z>uyZ_Pzom6E0MQokHKVEza=3l#jwE_iTI46f+Bf}^R;Ny=PDK*(r{1Du;eHf)4^{r zSO3P&3-etH3;X?HN$JX6m>KKJ+S+1%xW>*@HF@#yl-uB*8ooGDNx2;{55)ppu+VQu z`$rpnM~m1B2nhr*dN{g*5}XtqF_l*{9AT#ffrnjOeXjO`LmKJs9ue4h8i==tnuxpG z=W7Pj*HaE>0QhtyE*_b5W9x(Ai<9NFi|}F2ftDt)U}s)5fzi3fOUu*jR$!`njFe^2 zKm|vPsXuQfUVD%(f8S<*7yZ3I63~a~2YjW|U3U6Qed9-M)bFTmN;vdf+f$`{<6qut zrkqio^w~(@`CqH`N#7IofrsPE*Mmo&#HhapmM!I|U611ix_ldZJq&Fa+~3~s*YZDp-5Vm+>D0ZY4H$WC-Y za(s>b93I2#bU%S4G)k{~p4uD-{5XfdUiS=#zurcD?1Q9y8rc;HJHcu!pi7~wIir}c z=MZn&XM(O{7R$BHpeN%v|B$gQ*Aw`l)9JE*z#maO-dDNqFnP_P=*qfaDbnbK#^)os zhP|1&rdhwLE+lpYKIm{!Wl@<|hSQ#Kx(qC@1bY*sy@hRr+cwU~ygI@U2#Vi5ZJjZM zk!J1jr2cXK+rocKuj@*Lzn^OV0sm8?mZCo0zw!E3)P@=oQ5kO~lKRG5#3Q;}*w>`8 zO2;KmM`$Y0@fKLE1SdKY{Pi}1yRZ-A<5E9(?{&}93b8ou|IF`SZ`+I3_?G|7PJxHg zl=G}=fF2n(uWC*RQWx?_aWkH2c5GKlVV}ik^!eK6oJ(6>VP`lH_JdTJym{8SBSO&* zCeaB^ZGmK1HdMpx)(uONzAfqr#2CxA*I&6b#}3D2IU1E^inSD%&(*&hb3og42Qdo- z0~T{FYHkwbE$E9KsD%v#`>nY>0tA{k*b&MF@)v`kdFlc&i&M&BD+Snud36US=}oEO zxDjEW+H@+nuAH0N)l;4}L;_Mcl2O`TfTJkig#_v&RtOdS-6~(4FOvv7Vpk@v6aMNrkWfWk&BDHoriW0j1ElQ z;S49D&!^)Z8_(^UJ2E6hoDM2goO&34(6g$lC4x2N05~0;2;o4R z`3fjg=3hFMnXhf0>x|D1b#AC-j8Y&JjvFk!JFaDZyQgj8*uhF>IMaXr%(}~c%p486 zy>0SPzS>zC@+CHHo(VV{igo3vyqG!N`$7io_D02yR7-Ktgqy9xvl1?&8}FLNObDQ=0ws`tfzPxvK!?{((d-|OrOa+i_<{6)=decE?Iv~eP9(UAZbod?EE!*bZG3n^;FB*n}bH#xz zIPuibS+OWcmoUW;|M2;ueuu%g>#_)QguNccm^7NgiZzA!EalBV3GVY@-g-0f9~p8q z9LdI_xF=a&jor=SQcasT0W~ldHA?UfRyy6}*2Tu(k&CxfDqAid8M$an z6@NDlTsSp)XtY-K8|~Jl(-CuLN3!|Rlq=?RCaq43H`t4F_HJElYz9x&EYka<7g0SI zjZ%FJz58d7?-8_=-3|l3njTCS24m>gHix&}Vu!Xd==|`{euVbr`EDdgqH2xN2+NN5 ztKUQ(C3r8N;hX)dNe8sWzoNC7kGC^+qPo}SvRigUOPJboGNw10jTWEDj7W3A>>PIb ze9j)Dp*()k=;%e`I1XU!!tss`9rXXkYIP&K#O1i(>?kEYNwdMC*zE2$qrc6BqshZj zr`xjVaNU8UlAXqB<5Sw}sA{;nkypWMK`;8*cIi0w)OBF*g9*{brXi+>Wy|-g_JO-` zN-qy0G;$I8dqFr1fI^|y!+%hs=%`0gJP){o9_64nyf66eK*;*axtm;BcR;3;i;3r-p?DLpAc&lXs;NQD8l*=2sy6M`TDU~wmQi;8yx>&9* zRw|3t@?v$VH<9Y;$|QQp_E0rBe3dtF-)wUER^6xIgOV@AEvH60?57&*<|oPB((_za z;I$6rKgY|H1-9Z12qiKw$k2s_ie0YhY%J~-^1tjss)%{$`us!9-z0ykx?i*RNk0P? z!mgtV)anYt`%pc`k5CYa{w;Df>m)TR@tse^-s#_fN+q?b=7Ri={Z{%vn1w}r1i2sx z2%$?kI}f0*Yna&V<06&3c6xxg7D-#d2PmrN&J`DE$fKUzz0WAMNujF6qy!xyyCJo4 z`m7zrvo{&C$i=n?O4vf(AKrXHJnvBgo`A)E_HMILVn_!K;8<#Fo88FT+P4-5_m7-6 zUp;$oJ8PTF#qDON!Q<=p$SHP*(pmL~W4@&SN((r*s{1OtT>1s42_oP;Dz};{L?=+4 z;)+eKzOzB20iw}EM52eZU(#Jf`T9Y+E;oqvy2cOc3(AMvBW>op&k@x$&O?ZZ&frE` ztSZv@*Fh#9HZjUWM3A`z8Wz~(jvLplyK%?T%h$Itr>%ajL1M{G9TWTWW}C^?)^W*h z3zO2Ds~wvXdW&`G)!Vk;u{3wxSyq?%>yloIC;Eo%R-4H@J;JuZF4D7PB9YJ=-ft$U zwE>rpKwnZ+c|x}d+Dd3k4a?Q5%Nd3?KiaIxQ!9=>V=MT}@R5nblVgWQM-Pon9-g=+ z-kXSaMDag1^M8IPKMHNd*qtaRq1#2FpcKQv85JjOvd={*@{3ZRn^(BnbzlTjoeexPWl$Xrzrh#d-($KV8-~5*z|2;$uvwc>wSGLoyh3?ZQ z2Bqu&k|V*1r)Y-j3F&*le-ak%n)ri`_%@Y%-;=%ydtv!s(es>G?`eB51- zJMbP6H6d?wV4#gFAQO^qkg`fU_rM0^mY)$8IMJd8yU%27+CppF1vkrqbv=9=>>0eRLHi#uohzIgp#oS3?vcg14P`M_)YcJ}t}?Ca-OCGK{|73{?7 zPD-A@9M!ZgAUhMXW&WA@K&p3_sH(qjSMTM4 ztgK`MfvkeW5NOEa@~t>W1#3954wNDl@6pjZA%1c%`%g%oB)rCP9d_zF*21w$V<@Ux z3)_csHNA3U&K07DjE|LovMb|q? zo_~ricU3m`^lq+12MUoBw6eQ?F>!de#naz@zMS#+GqRlVdopsp-Uw()W{N3A`~j$1 zJz_0?koLkCCe4c(JG6N&&U){0y_C1?!Ij`UE zYjE=D;km7s^jRHNqc_xVM-~rk8#<>KD^xyCayF;TJyWmEBFtRjE<+ zbN-S;Uy0{z%a2KC!wRI{nWeMrU#x#j7@Vzgl6t5^Pu2^5k!8jgttc3?@@VG zkhVg9L)eNC@&=xr*TvHmf6OOIl63t)?Ms_7o(`u)u>?c;c3+P_IJY?IwMRo%kKf~s zMnnFdUhlb%fWsg1*DhLUUxzeAQT{D+p*P`?NwHdjPZ(pIxYKc$${-HGCcb(67)1A{)dD~oEZCa*Wq6_!V5rlW-^ zq$$ywvp+}^7^4xKf;A~5wrY<0$X|nD$9ovw8<7L2!HRqMMWEFR5JCPt(m`61nPQ{0 zio=+6$K!qbuKWobV_WY3E-#3LbXa8i5*UVxnzrU<=pO~QrIw_y^kLr zE9tXt>_3I$V?V6j^V4KWPl}UV$QnmH0G3UQJxz8B+Cm6xR$%L%RP5aigS&nTr_S(Q z@iQ@;Iy2W!r_QixJ`&&0@xppuc4Yfa3kx@Guk($G*%5I94c!3`+Hnh+40P5T5}wH~ zBteDkImP(E*=v}i)lBpi<`l6MH@Dj9OA{q_Z!eCC&4f4h*4Jg(pI_i~SyrZTVYSi- z!Et?WTGK?*3@DOYj{(EK1BP@)9HMwCj;h?kIn3Om7Y=KKh`z?8Ho2}vLP{#p_17eu7YXCVLj8LYE^*Ea zvrL7b0kK%F|2Y1e7i`M)O2`v*Iz2cW-tWK66AF3#eji4i)%t@MYZ_z_1Ene3+Kf1A zndXL$30czH3l{jF5Z9}`Bm9&LIn|5I_(Eu2MXlo#ighAA+wdZ|)t}caW^N%b!`1q% z@Cih$2C*V0dR9$l~R zuWss$cSV^$g~$@l%0rN*{?X=h<}c55(II&8a5xelNLO&gqHu|e#kp#Hyx-$-l{yqU zHP0M|H_JZUcn)dSl>P&{{TffH*#AwX{aJrw3D3s=wvt`a&hX(L(AuL5?1)(oqzS;4 z;47+)8ALDjTzEk$tvuUj8}-pZUfNjhrC*!I>ZTFtfxq;;A0e;&ev(&yKYQ!{^7J3{ zEwTpq2|1+MF_-ybdfmqd&zUFaKoy8aeSq^DpGL3$r1^V_PS$zIn~gYtLnTolun1( zo5HD77=u}%0imSONoe&A>;cKiBMze7Eqhwk_z6nr2=zpz!-2GiB|UKCz4c#uPt<>j zy#cVgBm_#ei=CxK_y+qh z>a5>Kb+UDsIHJ$hKWJhH?AFu*>NMlzGSq3d6arSC_A%nTaorqb#2!cp#Q(U2c!4HB z;I;T^Z^900?4YUsT8AU(cgEdpkHc(m*8VukWL11^cBE&E1lYyuz7|gi}%FQxVE(LcTgA#y4mriT-WO z!y~4tI;Z*?^!iIfd57uU_EIESw7tjV$cOD=)BA!SG=UzIdS4w|`@$wEnu33|Yb zbe48a&+IH!ig&{!D5X**zuD)$yI48s3*OycF72F|-c_m=?sogk;wkmF3;A=%=O?}b zB~|;1A`c={Q|&VzctEe+7OQ3QX|LNI47Z)-KW`>p%f{j|&WccMh9%#DyKJ#&tZME{ zuwP$&fgOV{Z;iAE>fx&|z?YEiB)uB(5BT!xIyyumN$o=sih&4vVDf>c9(Yfw;f#je zZ|cAS&Epc=I`z^W-HEP#C3HzBkqEur8@C#!*Z1w}@7vv%8m}0vaqrvd!Bt7Q)}8F$ zafS4ijz5TyLS%s9X!-;K%kW$B2bCU?>M)6=B3-< zvP;Om)JY$az65&}i>MCCm^{VF5rsU3jTITY{2;UjlQeCTKGJc+kBOKV>0E{6DO~6;;y~{ z{&FO9OMyoVr3IP@x-p!)CI7WtOnUCLDVEdQGm%g#6A7lD|6MMocRc^wSPoRDH5tE> z{(;)^GW0L9Q6R;%pkN9SUnCPXmfT*EE;8l2ZU3RLVwz3TH|kHDzu7dTwDfawO?cTI{bkdUNjOd;lSuvlBVE$vM>%b0g_I!;RL&u&jNV6e5F z{wJ>sy+dNK77_D$f)OGv(4uu{dL0ykYamp$+BASwrEj^S2GOnbN*!qHpi9+t+m+ z+SyMhb9HSjmp68)Cvz=fJO!~nUd=|*BiI5Kr=%60>_e(uSh~d4jg2}AbdK2TV+ls= z=`QDEm4vGiIF=0Qv5F-Tw;1AgC1N7V@ss>SE|BkuaR;G(jNF8n$y&{uT#oSDXdOr! zWjyG;(wF(1a~av!h?hbh)A%L?xXfvtd4{L_g3p9y*Ib|TrLM)&>XoDHTWc&Qt>3s} zB@dfib9rg~oHfB)SFQWenW#;Mn^v@G8=YPE|In_#eVf_q)*!@b$NvK%_WVWUf%aMc zBQ)>b*wG+KGvwS^=Jq(I6NN8bkfCyrzXScFu%58*yB5p0ag>#p{#rvGgW)Zb^cGwh zGly8p>2TRuDjcr=m)+%X)_>`6+-NZThhG1n!SEo&7ozc1X_DPY`wvNv>cq}Nui`ro zRi!z=uSCA*qdKvxP?_&4RFyUZ{y`2G`w30*{e-ap3j3J;dV+^_673{peSrvmmHs9T{s>Noq&g9pN)g(Rgf(R&E(K?^s_Vnuw=j@kbNUcq|i(OS_c_wyKe%-nbvXqH-XH zU!+e_r|#o8T}1Usn{^yj&jyipH&6aRd8AR}EQX)cx&iPpI!9H(uo)l|{t1Z&2ferPM^tAQLw%&UUR!0Ze>v4Z@0OyagVLW zecLLy|3+{juai>rNI(mVQB;d*xF6;wI_y?I4!LyL5KK+koFRmMt@e%yX*f`dhvGgD zqLpY*EEq52U>M@HJ($_m#++MG=$ z2QiCegB6fTcuEQW8|DP>#og=<=@U5d8sF*fL+4>3{K1}{XL>Ngs+CF=Ws*|A?l*eA z(rBBe*3jkX2esF^)+b(q!JQxIb7v!^DwyBu^gA5^i^=T5U%$nKT+>p<_nNqSC<63C0yqZJ=r4PqCq9KqjSc`NN+HK14B z5+y45>W$dtpZEisTez)ah7ZlcH?eBshxzdiyUp(pgq(su9N~a3V0Ba{q{mnBN20|0 z@z2r%`;>l$k3C@%5chJ!o2>tav-amTbMNnYq1^jL_GYG+4s+?(Pl;{Z+QHafEOdlJ z(LjDHd-K6~(woV-k<7;Xd3nF?GHR*MrsdMG3+JYTRx04u;a8hjqr(THRKPz z%$f+=H_zAXZ?grQF4y6|hni)&>~c4AW2OT3^)W88#i}5pVZ-1R%s4Lnyu)C3V}7Ca z#HcvmT5ZB+w&1{Dvl8{RoDn7VN#pnovT>Yd1&OvxbUB&{RsI)Cw4-YaG};MaJG&8Q zwt=^(rTyOiCr{1qCxyH<_dxA1{WEz;H5-W99DAoFP0Hdmq5wHYC< z*}101Du9RiN)uJf;{G_lSG6eaAK~|^PQ?8Qey{2`-2X~_pX&(RlVw3#dp-LBJTX;k zgKgDlY0IiMX?US&veW zs(5fIjeB+Fx{$88$DF9zZb(7gV-}Zl!vCH#!KO5_Xtmc025s`^yVU*t8tkbZ9YN=q z)v}7Yl|8jHB1p&lkzJ{$wS*XpFKR#aCt~qwvuXqj+C{ca>4O<0T`r#0x=F1@td zYIj@AcIyIUnRCHvH(T6xYd0SYC)jTN&D?&{c!VrIiqdHMO;PTl%AGh^yQOk3cK_P0 z9~iJ%+!mAFChE4?O%}Hw+oC|;NMq1t->0+d$l7h1I^sk4$PWj%`N+`WimWRj>>S@V zX{@^abfzDmC=z`{u+$iT^yfkQtV_RW**4*mR^_RW);eKY*m+Bb^F;(Ias z#)fpO)%MNukEN&C<@$Fvy#Ssl*fg7Ky#H4WuwyF+*nKN+rKeYoH|wf<;)x2z&W-xJ z{!05sf7jaf&0k}QTnbBs&N$@qa;4-UOXMvrf``WZ@`bQO9um^;e`SgM!&;UIC^5S{ ztos=-z_>>KzAziefPyj6-v@Rh1BY8wKg0H9AqCl09<$A9H5uUv=Huz=#d0|&V_8X? z%i*xdzM#TSTUM^O*37&^g6!VytfY2_-6lN7b%<=H;nr&QZx?edJT Jl2>2&{{USQh2;PM literal 0 HcmV?d00001 diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/assets/font/Quicksand/static/Quicksand-Regular.ttf new file mode 100644 index 0000000000000000000000000000000000000000..60323ed6abdf13d27724c20971cae30198b4bebc GIT binary patch literal 78936 zcmc${2b@$z);C;Lx5G?#PtK{QCl3P*Gd&RokcmXeNkm|PAr3P*3{eCGM0Ax^*JTZe zm_RXyH6pSui;9Y@0mCW+1`HTLMMatZ{^#7=w|fBh+2{M-eZTHs)jjvrsZ*y;oeHV{>`b{BJKCoZ*A3ki<@OA%k2{CYp5WVj2KWa>kx?Q|A(;x#)6zJv=_c*93xv>+o^}5G z)&=b^&2v60L=OZf51ilDG=G-u>dQfoJPP|$(s%j8mTPb;q|YZJa1~mOJ)-Bsr?S6JeTDOB4yfTGR>kBd|ZIUxYQYiLeC3 zPJ~MqZSdR0W$@RC9q^x*NkYmLSpmN%>`Kb15;U?M5=!}J`3U^SSNsT@Kor;36c zaVidQx=M$?Row%ByV?%_0re34$JCSXpH|PnCrLF(dJ39$LK-R&A(Et*@@xr(4idFo z1C}BhmZamA2-j=|tcgms&wwo=Q{8XCR*|f(H((p^^9?uz@K6H|4T7DbuZlGAt{^x} zW{PhNe7GnVPZ@AhKpvQlOBm@&DIDSsokj-9DK*e+H1HOb*g6BY!n#)&uuZtd6a%&g zWR@YqBl;QmP?0TC4cGxlh!J9;m@TG>xnhB66fI)9=q_qdbD9C2D{Pc#67vw_-_e{8 zn(3ff2+DKu7=o~wViv5$&*e<6!5jkA3@_ zp%6J~Ls~t=Fwr1}h|x%OHo`o(YejC`0gVDQ1JGjRzYQsP42ou4r{TT@^pqbD@!W#y!d50glqGhPDZAhfX}K-~YXa{Cd^3x)^CJhJ3nZkaiX$pN-HcN!bF3wAKQO zX~@w$NI)9W={#ciIVjI%4@jychxy;Be z$qw_+DyNx7sV+o0`}Nv`wd~hy_j8s(k8`BofOu3}n<0B4bWHZrMUW*1Y=`nr7TyL6 z)9pM^H->V2%3J0+xM!mMC??I_q%jh1NONrPjBshinnHNwzt*MYh$p z4Yr$YTW$ZcXW9$xz3dJ4$@VSw`|MBH|7L&H{*L{K{kZ+N5PL{;h&!Z9NNGrO$l{Q@ zLmmlvF65U`YiMq$H?&Xaz|hg5Q$m|VmxQhl{Zr^G4woa*F~l+6G2JoWvD~rVaf4%v z<0Hqnj$fU2=K$vl=T**)&O4kBI(ItvIS)F&adx;Iu6S3jtK3!N8tR(hn&DdHTIbs6 z+Uk13^@3}k>wVXku2W&-!tM!sJZx9k{;)$~--Y)MZwucR5f(8uq9tNk#JY&%c zcQL=khQ!9kj*PuL_PW?jvD;!Fi+w)!mDqP;kHmf*mloG0t}L!P?)2cgGjT_lX}8e_{NL_>1E&jlVMf&+%L0?@NeH@FWx^R3+?A*q@l3 zctK)Q;>C%VCSH?xQ{vr;-zJSsnwr#-v@B^|(sfCC~G-YJUMJacte305JwIOw6>ZH^;sf$uCOMNc& z<7^<-LjT2fkeT933|Y4vHt(|nfY?&TbUncp2!-Mbwk#ctoyQ_$$B~K-K-$$cmHNbc9UKj&HUBJz^+>hnhA zP0X8_*Oqr_-uk>7^0wsNm-l4ei+S(l9nJeG-J><^B>Ots7r1a zZKG*e?t_Qjv?)r7tpSx+@!n-AP+th7awp@_tcLS<+r|Y00{hKbG8Ba(l`4lE+GRl>DP)U&%Wq zhf2OEIZ^U!siicmG`=*wG{3aCv{z|u>5$SfrISi$md-C-TDrP)OXEw#D!r9em7^*z ztXxp}hsr-y-cosI<+GK4uY9HQ&7QJnkDjZ09_V?xS5B|)y~=v^=~dtB{9a>vUDRuK zuZ6uX>-9jd_j-NW>v&aS)p=Djt5#P1q3SPHw^ePcI^O%z-rx4|_IajnLEp`Ne?2en zydLNEKdzS5sE=RL$<%9<>{5Z?AozPSpLS?w9&L^&9FB zG}JfT*kAR(qW?Do1`e1!VAX*82J9a2%fRA+69;Y?_|HLVQ0<_#gZ?%+WAK>43kPo< z{QZ#ghpZX$!TDk5pLhP^^B+3@)X=^|?-^DxZ2qw2!`2VGVc3>o_YZq&*zRGk5Bp_! z)Nt?cQNuS3e`fgSBcez288Lgr<`EB%_+n)C$YCQd8F|CV`$xV#^23qekIES}a@6us z8%Av%_28%{M(rH6XVkt?2S$B6>Zeh@(T>s4qmxHxjxHG8Z}i2ZZyEjA=(k3n9MgTw z#4%Tmd1TCoVvxI4yeANTgSj`8v1 z>G2K^8gMk4=Mg(!E%uYRz9d%RxoLn1!+5TzSRq%SN4Z|!DsPt$%eUlF`IS7OQdD)RrR4}(Og=D7Okad*;>9J2;jVD^ zagTCe=$`Gq*nNrna`zwIe{%oDz1jVX$LWdm#CeiEZcnBs*Hh#v@$~Z4dFFeTdam@` z?zzje&2z8k0nekJzj~hWJeLuZ5ucHnk(*JNF)34J+A^Mi-SRW}r92@|sRC7G=HywmQ|(djYC^LiCsD{rmX@n^ zH*yk!mMz+y>h`#^-39JKce%TlyT(1iJ;~kdUgBQm-r&BTbF#%_M^2(WiJnxC$H+-f z&Plsx6>@T?XDf1YpXU+e52-p1 z6Qut-s`RTbv*RP5#5gGE=ljTa(09Q1x^JIvukR(_KRQMS1^zDhapsY93Oq8+PjaOE z$hISMj*L2DIlK@5?MLhg4LgF_3Ly?3XMe-t4TqN=zW4CLL&p!jA;h5<;I_d%bm-1Q zs}4;S;=^z|&l-q5pg$rFIW>=#35%)I8eotO+InpRaigDhwYC9cmQC7L?Li$A>}&UE z+qH+aXS5yKPHh)PHoLVw+N;_(+IJS4CDIaa@mOf=Byfc^mUk@&Ek`V$1#{40%ezc< z!16w*-nV?vnZmLkSi>3gd-battu9g<)O3uq4ycXlk7|ips-~&uP%GxC@v2Epz!+?| z`kVT@nymheXZ18ZJLaHPHHiKgGmpX;ULPwi!n6D~aj)1e9u?1v7sW>y-F+%P6W^)j zYKFR0y`tLHY4M|slF>3rX5cx$m#mfza=e@^7FRL+XlG>)8QunH7)NSfU^{cu`MPmkJuWC^@YawcrdQtUL)v80it^T4K zwNQ1Qicx=1gVaDZSWOWzXe}I=eTc#=M2g4|eNmrEG3K8n#)$D^g2=;+#Pt}TUV-Q8 z4eEKZMZAu7A>(9`%#^vZyBvX$>tK1lOqPq}6>_Ou zF8?Ces9l)1*e#!vyW|V<1GGE`MZ9#Nt@=qMNT*1bF(OMQh-{fCJeVoVmnot^rip4< zB8p{}=#BZDI$4f+ooq2k_7MYQl^7z=6N6=6F+$dfVX{U{ljB6A93#fcfnus0D<;bR zVzeABX2=W0EO`-Th33jBqD4*<&9YIn%IRW(oF$gXW^swc6N+q+^TcYoSZtEliOc0O zakKoR*eY)k_sK2d0eOeGU*0YrllO?Hs17O%>`iFf5|;%WJy*e#zDf0S#*-STE}t-M@(BR@tR z&CqgCPcads<>9$Pp}o)5tm-$kl@86WeClKM31*7EQpeO6>WDh5zE)qVPu1rlQ^t#~ z(k;5lbkPNKkF~N))W}j%B6Gy~vY!|!>&0+cD=w5n#e9ipBso*elT*b)v=GbX#o|)g zCRWLXVwr3ecgh>ZUGgTe8S`7W%In2L@-Fd++$x@t4~b{x!{TvyuXsYmTwN zu}3~D{w|*s2j!dMeawS>BHt5-qSHzo`KRzZ8i?8G%@wGf6zLlS-5o(kgt46AE>SEQZ=A$28 zudY;U)jD;Bx?F8hcc`hD&3jngr|wq|slTcR)syNG^{9FRJ@tO|2Ku>Y)tl(+{(-g( z*%S_W5c80#u3^Y%`CxNndkeI%LWEXNsQ1VTwbi3Nvb=UA{OG~e6FlOZ^M?)bh`mFH z)Op0#k;BgSh}D?f_J~QNM-KL&rxiRuOq?;V37y%Xzeuzm(P&9xMVyGojOMv$BK`xK z@c)1&>_4D!{RcG8|A5BvAJByU2Q(q)pb6*F(M%n7)}RHUq(z-7py|$3iH(iT?b17~ zaY2*pHf`Fx`O?FFCoBf?F3+J_or&`;lw}^)q%x;+>wl7#vR4ndVuyE=Ev3bG5`3uC2%bMC+(NBmw2tMLw-fNYq{Oqu6(_p95b*Z~vzsOVaSHwRpJETw1GKf-|vM8&vDZ2_$p_tDH8sh@!2P1-h z$f2LVL>@8QkNNvJJykeXS9${H;%h@t z>{O1epl_Rs0PScM#x$dW$JzsYf8NH6E^4NlrDj75&1#`qq!z0cYNcAGE>o-38g;F@ zPF=75r0&Lwf=dh2!ZFs4#ArKOi_v1WI4xdF&=R#IXf;Jk)zUOKuY(|E)u^VTaGKN% ztYOSmbFpSJPt6lnY5^hD5_PEv!KmgM5w8A>5mz+&pie~%`lN3~qB^cliVXELR#)X!98)KQt)$gb6BbB!?aQj z2;yqFXSrt-OqDf9*d3EW@ z2D2d%<#@Uz?LkA*FNpvjU1wtq?mEV={p?N>#UuZuRh=_Q6%Hp=BY4LnL}F%@N{4)b zo06U>+# zrpXZ}%)BeC;>Q24YMgH2sfJZ%gA<;En4cZCNYG9=Dto<6mApczQ|R_mE)r#bdBOiG zRV8eAwrK#H@yM0rI!rqKR@k`?M{*q|d!Uwk74%sEJE6J}TyLmNCtLXeRQ@o3z0nY6 zVZO8m`z_iJY8%3tFU^Kf4hDfHmP?3IL2f{ELVd4(R40j!)>ifyL~GXsD^Y5I znvIp%nP~T#A$=Fjzw}Z40p%;N>aAeUDo+)wDpe0C7jqiDR2`rk)kF1EwScl!p{i6h zfU+=qQ=zH>WvXtfT=fH#p}MLvbslt)j@G6?m8!mw{!69jO)t$I;zHavp&fi0PYC}X z`z|?5PEaxOLHQKY%YYmi6$U_@)Kb|w6KugjEn&~47FuI;9O7V0)LzHn(RL(t71@}ai z+!OWUo~R%9M0IQz^=xf}*xE+1wOxQVJ6~NPQvWM%J^1<^($M}QLddBJJhyQfw!rD1$t{JX9a@>hy5I9z?- z(G}zAYPj=t=le(;Kz%;o`vLCnaL07VG@$dH1YInyU&{{&=X)ED==aNT&>jysm4G(G zaF}5o!|nuKeWw8Tkfn?phKWW#BVdT(v>Ta^{LlgGn=vwRhNE;qRN4SZ| z_y0{dN_79d^tA6G3)zb9iZK&4%y133=EEhz)xg!t%Y5(1w=u8!A3E?%!<=H&|KwCp zr2pS^QD}$0JKM=mP^Wb}BU}5o4zq&Y&vYsoy8CZ9r|8*I z4G?Z|P`EKq?!_~FvFwF;<2u0cz-3{!wh(je-Jp;EpXe~&OjI`^4-df|MqBr|I8W`x z^&Q+lCrTw|d{i#Rbu%z%#}gghlf%k`{`)J|DPF)6>a(IkyePV%O)tghwVWL4xEJk3 zcky@3-j2l#bs1(1HXuC*#z;;)ncjmLUBYAL7tSe05=-BB% zge}4h@gk9o8RXc)(GO{HsDtRzXEelFJiP=C2~-fnQ$p+*K#0# z3TA{88?Ny8^x518DMWKol-Lw?637CP`%8-{K zNR#5eh8d{+SRc6oWquHPxB~V)RTNvEMt@K7X?&;32ma#teSvLOm~`aP+US)R$sS$O~I^f>#mxDlcZ^y{ZJxZn$XJ zs1tKEBaq$*^s7$Lg&A~LfyRcqG9KgDX4vCzcxJg8FJ$>^7ju9POtAki!Y$sR0UH{6qq#81x`>7Ko$%RM$5K+07Od~tq#Y|MFUnBqkWQ@jh2gnss*J#@ zSfr%&%NVS^#fk^9suYJ5b78YS%p1ka1gz%eK`UR#Wb9^6m1)u~(4{40fVqAIRxvHL-CY49IKQg zQD#Nx+lsNzZj2l&$KmPl0y#lmh!xn2uxf~1?dt`R%1r^)HE3H5uXoGE9? z*;v7ugBhG=IS(s`t#ZD+ShmRp*rUA=ZNqg~M|=p+nM>s|%ng)?uTgqs@)E3tUW&aJ zE9ENm$K`UhT!Xc%wc=NKxm<^}()IF6c@@@-D&*Dj8o2>G8?KetVLhx8D@T7qt$rKU zGYhMK2e6`gqr6GpEN{UY@vXc{yajtX?vQuNyRhol6YbSjtQ+5hb+anWL41Xk%4g+$ zc;bBk&*l$dMXe83(mul)?qi}3^GuJ+zv4OgN%@p~8mnt_<+E6CeopR`&!cr}#tPyb ztl9n@tGEBa>ggWrirj)0s$Mi;^;cjW^(FZ-*0lO#41=F~Ae_KjGq&#Pk{F=%ET^^WJ(#Za1E#|Y?*`E~KJ7_O{hL|~R3d*)p# zOogNET7tRqkz%QeLceqg=7eK0QxmTe&|@!GNh(>Th-E5Or71VhqMR|SA#PV)#HE;9 z>8iSkN3j0?4W2{CU@oQ*b2LSmyP?)_Ean%=#HVOuf5RM2CFX8=p?$qljKdsHAJrG@ z^8Hk`szEz9UaU}cnC)4Gxu4506SNXDL<6y6KUfV>=c}RE0XiJ3gd?#|I2!B!W5oqx z0#*yhV|T&?aUtGSIHoQX&tQ$>BJ2&AtfpYD=_2$1N3nxpI?b?~Gx(TqQuDA+fL0kV zR&8nlb|dI>`n2C+8TJ<}#~y{?`Tez6fuwavT9Ld;>_WS8tJo}VK@Z?x`%A>iPBN{{ zV2{Do>Kg2#_@lWha06ycHewgTjo71bv$_R)6K=&WhTE{Fc{^4$?^JiGyYbG#Hgykn zGi>Me%?Gf$`4HARX?^oC%(wr5Ikc1NajbeifmP3^=uHOoEauL3U~k4wtPw@vJb&!S6u-e+A~{Y?#M84?CH5VaLV`*t4-)L}GRHQSlg7bY4_1VP4>6?3Z{2;{X@t z7p7njL_e&hzNYr6*Ri7dPwdM5hj?84RXl+)l=J=7B$%yw#+WBuddgxHRZ;&$hdlqYbjleifili`)a;NyjtVl zh*w={+*dQbx5(gA?Y}a=B5#q`UOlgIT3c(2y}ET~YfIByM|IommYI#y7PdFptLybE zi&j+WterNyZQ8x&He zia38o#SMD;#kFO&dd|MBJ~*;LU1MmY*2q<@A$_f(japqB-l9@ReJ62>>uU@J)c6%p zZm%~os>^4vEH1Uz>lxSOuBo;4XGxs>1DVxx==D1KpOK2U$TDDRW1Ak;TkRasIZkoC zw^R)rWE*IfFiNh0xp|8W0loe_vY^HFwTwr}RNDs{0uR&$v<+;Z-8{X?Nd{0}l>xQa z+lK|)NtqG5jMFMYO>+)g(A>CSR#43-H8_{*#_jdi+D7UM8)+)6sJP6?MX@1unURZP ze+u=sQ9(@0jm(#qJ4c;S$lhW@QRN1!a)U*=f$ymcQe4?!84dHajSdpSPg|j9$Xjfv zsocm!dA)5+a2b_Q85Ma^Pq^OH`>*BJF#%oI8wocU0@eF~#= zaW|COE?^QJ-C&ePiJ`iNO4|fx@0f5#9q;M2HJS=R`E&h615=?hsxgeXh7|=o*9X|W zk#4n7KdSvLwh^zoryjqW>jwAghHd~r#wr5QQY zB`IM|!L|%pOZ;tXiLFJi8!e6WQgd7D{8>%5mLPVey6%hh))}p|ztz?`dMmgZfV00T z>!~%N0=5P#%BU%3t8EBTXIMa;!LrU^soNJ?Yopjp{1#(aRBeN`HPC|88Cj|Kb2F&w z47;l@4r@KT1%d6h2Afiu5xb1jLTg>)Y(1;BHaM5+cJKAp*{~N3!yQ|jsW7zGMlOmC zsmqL9_-jvDgKa@j)hjnLUtZx{a7Jl+iw#AU8?4F=A)c>k-w?L&Y#mee4AyZ4 zVi~RULT;rOnwDQ&U(wUHShvK*0X2j!He2b%dMmv&5U5*rrBTccWwxckt+Y`JC5Flx zdfJvTd&jafs(sHATVo+@z;iY-fdR9Q7E9_DOh1qBBLqy-1##^^M3GNb3< z8wYnE3`PWc625mfa#1pDo2jE_22_almj?KZj|^&y8A1A`2AOXn0M}DS%S@0ivoU%rs^KbKR8*t4 z-$nW;#9LHh$XsE_Tw%yuVaQxz$XwAg6x!uMJVr_-|{25Zv`X=ko;>cZycrgnxM+(a`NKDBY$ z+`w)888N9}#@_6dbEBC92?HVO95ZImT!_>#RM+Lx+eXx|BIm57=pS2jIhtCC#DM3S zaQOVjHuTR;GjtIn__mF0h{O+{iaw($5X`rM;7Gck+th9nL>Y(xN%YKxv!Q``tpTDK z6Lkg|winL?tsx7OF)Bc2ThKJEwPiZzw79q=v}r**1}N=KeoVQ&QO}63i<+{qX|2tz zE%Q+L?Tu|qEz?_DW?JeOwzV4JMir>8voz0cYc!BXLD%pY0S~Cmrw$hd;d=(b zB?gSP5ADBBPq3e!U_U*tOsv>5Q7puF)mxLZu3Q6|1*ry?t1mdBH(rPd-d@%)LcnxMzsIVffb$6 zg5NU{;re?fn1{s=`?K^Nl}c!Ho7!4L?!3mfxxzhf?!38}H>O>j`g;(xCWW1qzz{!M zex_xKI;HZlb`g#_Tsmim_9W9zX??FW_D<$a%9}(n^2W16Y(9y{PfdG>U&R|(QkG+G zHwWuXZkdR+Di>C>1a^u2fSLNwu>$k~R%7>zy_o6UiCNc2#r>Gm-GbTG8!#KXUaZD` z&NFxUO7Wz&0kZ7W*1*3^eFFbAtr-3*+H&|eYWv|or_t`{ZQ4NiTeT?oPifWg7hxxv z6brRl_!G4m@E>9SZtPa2SfqjH)zk2AXU;F-G#x4SVy+sT8S|XF7VzCzC6(eq#^0uP z0bZoGz+b5Dg+EbU4gV!|1^lp{w>z; zMDA5^YvESFErDx;Ylg#meC`yu32>v~uwt5v^~Bs7xZZGBb}Wo`i+RwHwe#!!1WSpX+=je_4~x?#G|@ z_`5Lcf98(tQmmWiV^x4`=Mmpk@c-(g_a@f(E{5NTw`&Q%4E{vlLijJT|D5jv!1wv+ zEr@oeoZ(9b{D^M}{E5CvNJ(VB1-B3GCAb&ho`8E8Zadr{I0~zS>kEgKW8Bj|<=;CM z$_ne}o$^?=k^Fh~c-qkp+x{2P%YVTxRPr0yH3;`0ma*d< zyNw^GaIB)h8nEk!Xx{{^lDB5_o_K`u+c+vo{)Bk?Nm9HboxKjSu7XYDMJeJoi?yG1wda(uW-Q0sDNfJlLU@jN@CLExfC=q4p}i(V zxZO+#+csjr!VL&^Za}bh0}60~^#|c}E?Z0->Vy$`g9!!VZZL5qsUCN|i9`J{;x0F# zMJ5!;+k6u@$AqQ>nk4Y^j5nc?fQB%x0Z>1NdYMqE2~lXF8LC71W@x4fr2>kFizHh5 zc_KX~&g1ZhGR|^FDCp8V{J8X=3DS9VhSE=f?pXR~@DG{L`zG|32@!4|(*;6b>J<6{ zhwdrLot6Iy3Nt4wH_3AF=ift!^+75+rh zMEY108g4=X9MKJ8x;itouL)HG^1^jX&xP-SOHL!E}TVVuGSn%~?f;eQAB zrTY{32Tk0&CiI301#kiARWo#t37NQbN@EwN@r)VzxCuRILid=^9e_5uH^RTx#9akw zE#=(3!i1KXP#d6T4kc&?LsM`j#Aw_Ng`2>bq3!{GoZAd#sD|hm>TNEvY8NtQlM}HN;^eR+7H2@Y2PsJbKs8<#B?7p?tq^zZGYO{ zwB2bt)1FFu)P(Lgp{*tqz-{S-yP4zOVB$8I(0UUJ#9eLTmY)M6S#*Aj%+UEJbS_E% zeT+F~-03DX$%Mw6&`1*+VnTt`8i4D^x$I>^r6ygW3FVtmrU|7&_wlUpNI(uaOKOJ@ zsXsGrFQ5|yr5=O(jG;p&^u7sE=vy4RuM-aK6YgK=gxkTmCxCmHq3tGgmkDh)p&Lzz zVqDKLuI_|e$GBCUaLY`b4z(k+1#VVq0GiqfH_;3oYeK_KXpjljG1ND;GS!>f4REdr zc}ytTgaWt#6l;bOmvH71V&aq^O8G6dGUX(NrhI2Yg!__lpP0CVCiJceyMxO&hj1;tK@CTToH73;Cgvw2*2($$p18tQ7p%F5mL=z%9Zn;uifNUv< zl6=a9elQ`lP(~%iZ#JPDOlX4%tw)U2Ec0>`x5$L%o6sE4O;4T#f4m8egicXsa1SVX2ty4f)X#({ zw3ivGL#1YDp$V-|&QD&AyUgUyQ0h5w@g^>kAh>)^Av4(l*pk$N17UwQp%W%_%!GhT z`i$ugnYi~&2)LxTICP(hLtABVe!+xxn9vg@^spZySqv`Q{kWvNOlY$S-DpDBo6yxJ zw9bT9nb0yJGQXr8C$+((hWmvJ8W z$uveviiHbjD8z)6A4>eqgie~!cP4~9=y4N?lg@=Wn^59G;+*)dAD8%s3BBrvNDmkd z5ZxX>j-_Jx5_kD=iO+xv@__Df6ME2u?lGY|K(UGG2-?WdwScZ-Xl>$(#3i_EOKdhF z!p&eDK~qdfrz6}1!ojUz9&L$)8+``dP}~pTaDr+W>J6xzpyUQWlvo6)fJ3uQ9MQSW z7>Nu;cM5fxp*Du#>6{ZzA?Irem+(WvH>oWNpC=qi_`rk?_@UHxKa{ZFg!Y;ca5(po z;_ftYPnpo8CUn0EZ8f1SCUmn2K^BAG4JK}bA4*gjA}@r19kS zaI0DO@t}!h$YDaDF>nZt@1W55pF81BFz#3<+-HnC1lso*ddr0Nnb1on^nwXdj2#@~ ziB7nO8MnO??k*FjL!0AojK3ZfSI7Szw9X7&WkSmsYVQ=c#SERr(A4;e?$PmM0S`B! zK_*mZLVZoB(uBMw1TOL2m`kpS^Z22}YvU&-UPYk^>-`Yn5>_*AxgVFX$b{zmq4;D! zm-tu{3OAt;6H! z;kanw4Cp}@IxG96UW%-$HiT1LRXp4S`$JG7Po|Bw3$$|3C%DeqMO2W69A2l zLz@;iz=Uc{2rZWpS`Mg)=?Y9-wh6gSDA9zXO$e=zDHHm^gud}Z zaU?0njs4t@i#=jOADGYq6WWhfbW`kJ99p^C#O*Ypr%dQkP~1=2h}~*JTTJL?6S~2K zHki<;u((lzZj>E-=v04F zPmAcLuaCVqwZsWJ^M6|e*!z; z3I8zrH2?i67y~1}M=Ym$6@G$-^#j0|YsGtl9I9}31~7;#otg!{U44yMAFIDIp6E4o z1b#HF9DoM%=AcK4@Ue0rBe7$i;9c;Q77gE~6_Kw_zz_2^F}#C)Jr=PT1#*?pTt{ElwyH46@D70 zn?~y{GEM8t7?L4P{mlMz@RM1dA4wjW#(7C&N#fN3U@}>rG|pEVr&vI;K@Bv2ze1j- zSd^mJ&8rT(iG$dPxoIh0;Pr;xyaKVCS0L^Ym^;T>73r|IJVli1O88%KtglFi;tP)T z9ihk z3u#qaSgYMwt3A0)yRrq^)FT{gF#Gl7<1J4q^YDg+lx6G}k`96YihSl!$o5>KUS#}J z@T+Le4DZ82t9XN!O5{8V7;^gHXK;?XvpgB3ADO{?y0fjOlV*Uy`jG6-<=dCbWe~^8 zV7NQOFLSJy8S^q>!~)j#0>X=nS;Gssl(%S?Q7GO@gHQD04Mp{O0b5`<=Fp9KIyiL~ zV_eL0CCMq)k%i+_MJmT-Y!7o8KbPu`n9JomlP$KER|@B`42$v3ABCa@iD_K!^Vxpp za=Fjt7G^P*{#=%7E~hw8hgln`%x9i<4YZNUD`(5pP=c9ep4tPritBF`(^n~KqwsDH zwbHtp8NT{G>I4vYSS&Vmfn6=bD(xIr@pMC0#Eau7inO2XpZ@ z4(PQ=jzw)+GM7j?-pi3Pn`KC*ngX6ANjgi?jqU9hwu)qyDxKx=vL$$#gO^MHeKiC2 zqnCRjr|xB*Hs)E#JbN)W^rzro$b9xwd#DX#{84&UHTL*Tebk!THVS{N}UG=W|ZGvsC$d9yJ^I7iih=yQ$CMXK{|Y8uZjQ zmXgeP%RGcaS%!R;p_VmJOY7FMR+|TZzIFk@OjE0N08Z4Fvp*JooVFEq^(&WMlCPcd z6gN>@1HYc*CUPu#e^tsJ4DVt3k2#f(iBd%}<;P6(G1ClTcnHJSTc|!Zak@>k29I~e zNRlQC@odsak|tWYhfj5RCR0u$+2kNjYbNLG22N!rbDqf@8kuGQ(=;(n6HC>^d2ixe zTu-soWn7v~6c-0aQSZ>i913aG8Lbed+k@7d0aLr-(Jh4e6yl9j;5pqwj+MmpNt{+P z$4cU~TpTOO5)b+$j@w{CPbwQ&a$eCzFG+bH%;^s1Tn}b$gPFq+<~Eq)F5y^%Io-h= zYc0c}x=$FfO56i(7*mqZG{+b|#_&p(WThn+q4#qstYqEZ$eg*wkaL-Gs`e|<;M58! zS8|E0WZ717iCm(s0)9Dbdn#*tC70bw*1%;Pccu0=Xb$6?9dMu=sS=H3TgiD@$+^3q z(_KmWL_a~T`bw5|tu8J5%`9Ov>*qoay->%qmYO-md90;oE~#ebe-m?VX8LBP-^}!z z8MB!&Y0NW?@owgj#%=rU9M{36%%@kvLP)pm9IKQmOPJ3{#yrn?ImWRtaz`$nXZjT+ zxj0Pu5}Yr*r%HTQkUrtl-jror;~F)zmSP1-BJLv#K`81SeAHR^s8ixT;*U31iQDOF8?Z=C4jG9F(!rM_T@6_#&8Cg{#>@4zRa^PTTT^QONNG=%D$XRU#6_G zP`k8A`x1U7Oa7~N7vKV}JAGM(zAVFB*6CzYIfUrw=<%dwQ>ma+|0vfkLPaHb4N zUdfb8INf#3?F#0@pYWXI?iJ? z=P{4-SjTDAX&-?8eeD4JE!rXYC$#O%fpT4Ese@n58pyNc6NYnfu_c3PQ10?#N(FBi zquga3OH~IM6rb%#<2m{&St9nJEW#OvOT-F5t8gCpB{*Ykhq#o#Q1&E!p$t2!@P#tG ztB)^~;SKtQcu##6eW46*v*Qb8cpDvGD3gD~8`W|0SG+%+E`OtMlgZQcZ8F$DzD=h1 z+hjNcmEPzL#fct5IpC<`cfkD&cLEOWjr{~V2U#Wr;#{H7qX86~$ zKanXPVSkIn6B^Efpmd*O|33D=Wf|HT<{FDufM_QAeu0ng;1NBIgK^&W`|$5(d0t|8 zFXL}CXfV1$DAC``_}iFr4#T%Hej<-YUt<3?e(KxFG|w~qH2W_}^bI&u;uQSt>^}^A z@XoJO{AE24-iuara%uP!zuE z^?m4vk?xzmV}aNtr~k(?|H5~$LYDWW?)e#qslDdLs`k|Iq*koyOpXJadSl#m*A>4*A}JR^Ilf<@*ff z`i$==Y$539LmT1y3ho1v5r2ax?8eZL53LFPC`SnW5t=xBX6_7%li0@^^aCYJZiF5= zcPxK8K@t66CrSOt-@gV@M@~=s>0rx0`%dBXH2(QZ-3(;Sp;9HE*$3&v~2#L?{hzd(4z?doze|Z5%ha{=}dL@o$o8k6;e4ydxTMce%7rN zeozfS2>J%!Z@$yMUwr5xf`7>Om%iNyHRSaD1GV8uFoh0-+kbG;A!pzkh{ z8u{Msdma>S+y!#+CWmbDT|<(A{FpzmQ#Cvh5{@k0&x-uE&jH{($N=LR!q0XaC2 zKY_=|KQ95?|#02>1BY}7=f6--WVr&`EQ~a&`<&-1Nswa z>KJMcx1r?gHW{2xqg~Ll0gFXT=8qe=2IC+@kR1kSf+61zR1eO|onPNZ z3S?uT`U}UTlGA_ajr>2ZX@(V|-v@MN{!B_gm2vgs&%Ppuej2oJ_~q*~z7FR9d;RZc zy1x8zaScdpj8*io;4;=>-?#o)MoJXdNR=?u&+0kj{QBGHbCd&9`Srxi0;vTcP#HY* z^v>xkfw>m^N%l}&o!C8Z$H_p^B8*Qj3dh+&X~5;+AB8j2dLX12{}`OyRRW4KoGTY6 z`rw};&J+Das;CjQXk+Vf>Xip?8%)P3Kr`{r7PIls!86ht?8M)Oe;%J2lrJ8|zW`?k zJ&!T!i{d4m#r6vRg*cJzHKg`B{zc*){ENkV_!?vSVvcw=PBFU#XPC{!7kTitDSVR$-ya!J?=j(zQxWmEvV~gNLal6}R<=+pTd0*S)Cvo&2W12PVO$2` zTm}(rt&wc4QAT-?wMHAIvK=Q~#c~C6(>h$z?-dD(Q){PpNF&Ts982;&d({50_8|mry2` zkh4<>QK@8csbq7h)ZwP%e)Yl*DqB1T8hKjU1wL-GLLJ=-I9 z;e@@ra7y2`avA1GCg9Y;39>IvFZAM{k24X;MdB2_3HbWP&u}Lgl4z}{4cUe{*L$J= zkNEUN`aWDEpY-=APV0M1z7KinlsZ14&N!cr&Ve(|eN$6$<{O>(HjmGEYscyJ!6&%U zX>2$*4dA4^NN#y(^-v?MDIVs=reWsS8M^wNZm+yl@Q%SzvD#iCt z<;EyV;qG0AB-$9Okn&d4Ns9kC;vd9a2zb1V_<8u2OT6!&oWef^?8NsvD87`B`c8r3 zYw-4|85qS{fjtE555S%V_PA;SRsnkybqe38Ax?<>73Nhw@*TlEjDx87?rl&VK|Ith zK*v#vkQ#Bv<1HXcTfsj7iI3n7tazLUo9a8F#zX!K&=+C-5BN~w2HYQR4cxuHW1uVI zJf<-13!r_I`TUAEry>w*Je~!?&G(B+HaHRo(#vsh{2I9?=sC=2?S$I}_Yxef1yW9b zQH`8K%KLG(5&8`Q_D3}tC#p_Ciqk{{^8YnLPpfv{%b=h$QkUXv)Jt*x>N-$efmXqe zJpV$aqZ)BG-84wuY9B z3~Ba4zDdaGWSq)7#rG<5e?(37eTC515&F3LGfoQMi11s`4^x`>ei5|zGQy7H%WZE# zJH+=Q;)49^{FBsF=wupl+k~>5fi#hhy2XdtH{__^6_)JBUuoi_aVlb=A8*Mu@Ojw7 z0lX3KQx0FK=4k$Sd0H~wl_kEN=;_XYn z+zX9xJKmq&EV51fauXjZZWC=L{vnee<0(IKxoG8Z%8x%@AU~bsA3Q65nCvQUHTfSn zD?A=&{hlzx-|G}U2I*6NrkLTgjBvY_0DaTj(R#Txns_J9derfdS3PgyS^p;eWD`&N z4wUm&6AwLO_sH4&6LGp@Al(Lo-loMZ&S9Ia!6~25V@!cr`1;J;veLe)A_3B#(|qwE zwYb=LysghB4STjp*s}8GRK;fGMcdJdr@j?s>>b{<_J%Ykn5|eXe_U5 zZvxuk6pTZAp`K;tLTHwUDwr+LTV7V0o0Um|o;wp%EA={9mr|IPR+y5~BQ>>0N>WB< zVnSwS%Kua^Hzs#aN$H-f`vn;ZNuG?vgp3jYQEmMd+D|lV>$7HQEj3G#tcPagLwp?? zt)`U-)!M_+31Rn zc6IzU#4ghqIvi@3gBaQz79G>E?c;cPNA&3j!y>~Rq3SZbEh;Q5($Vp?E6PRJ_rjxb zjdtA_Mz+M#aodxk=SJnB&C_t6s=!IKJJ15=V5};tSx}oj&+ArkvEd4BZZ2Be@)Bzn zWG^YFlF}IDLd%txkDi>}P-@BPUzwRzHKa?&_avW`U%8xLmiF&g`jyr8O~0`PSWCNb zM8S|AT5McleR1jF!uV*HTIGtaithL{Le^AQoY%3})^Rwry1%z~GIUvlUa$pcz+x?@ zIzApYoRn4aps_VroVClvM+J&Qa?_l3bz6nv~jgL`zLw>+piqM0`lqnPiVljVhhI zcEr#%Q_4Ni8B4)BL+`-tR3EO#I-c4+9Up~}G_`w0zKcm}6Ca8`hIG$(lTV(;__O#? zyQlMu#JVxHmwGxAO}vZu=_oF<+fZgv)H_ylNulQ=Yon5i@lq)jsw^rddC8#G0a@o= zHr+?%^5d9U#VI{6Jnvt2o7z!1ZAJZ*+a~J;aeC#@%ZK-xJ)%eG>1_^@8FpdK(H3I2 zKo0Vrhc6=28YtR$Z7%0E3U&h-ARC3-)Txh#=&{so8fk{G)FWKS)RTObLDY79gXT)s z%T|6tq?4@2 zQ0OrmV~lfD%b?1tt9H3;<=S_T!zsHlbRg6!M=^9Ae6@pWU{uG^FsgZujzc!R29l*4 z@~BX@gC4A%aPcGC6Lbwc_2W7|8f&=J|Lb_trjCyie=)RqaS%Q12~Qz`9Lo ziBpKlo`~N?+Pwxo4?B;5XFI%H%wqj61YdtV>VL5=gYe+^q1xwX#Sg=J>o&i^fXi3E6QeY0eP6dpGk$ zJ)y2QDo204LIXps*#e_cI%g(gZI^~eLB{5=sHm`xhb&f^!_a$nV5!nTj3`^j$x!Oh zLOS-M78!lRCD^H0NxCwd|Act|V4Zpj9`s<;Q(j>&OWnJ=$RnwPX(OK6c%ZA?wC=zc9lZ@jzH~blCG@Q6ctj^BhD-5t5RuVfOGS zO~u3yT|aj0`k~43ai5`+4UdcpJ022lb!R~*)Mj78b-6!uL1Xdfxi0H?s>?b)O1y3K z8AMNYPRB>$q#M2MABgka_n7!pna8%R^C6qp>0QzjgeRNS@p0lIw847+-iERW!|02i zrJ#f;e$1i1f=VTDCo}9BD_k)$#)VRmABSUFE}X_0C76Ke$W%L`!%nXzy{HxB2jGqu zF{rcPt4#u5?$lH2f^WNsQ7C)#M@G@-P+I&rb?%fec11?I)Fkpx!|-BU5s?rg4D(N6 zrVttOizp`ooUX_>gCz)tNgA?E-)x+izXSRh%H@zQ9y8mLHrBU}kHi`D+%}@m38qh$ zF2v(LLfp!^5{pf}ktyA(>nYq7lO9kCRDhIE%3nAJdYMt3;>6I?CFukYm+@qt^dw7n zq#4_G8SRRQiiXY?o;NMU660`$*<$*4?@^y09UdN8F-1&Uv|$JVh?@6bqw zo=<;aE$P_EccCME%MZI~G-{u9Y{D*R8q`9Z=GIxqI$txe5(6@WHdh0dTf;K(5@L)- zoNXFeu^z{jNo6(~`=7RPndw-(@Cx=PKzpl3t+tL0J4S6bY6H%5+G=3!8qJI0S&CN3 z@hC%WwoaY+BJubHShq&CL&wHFl7l>2eKpvXvxCMe2~$ z7*B4jjEg}Tg}PFU-7!&-VWAFJ0=1v~Y!u^Am+Q5|;j%iqds5QE!ue^4q`;n7>;$Fu zQkNq3F(5<@?ByV&NaMEu-`Iz=oHsq$8Vj?q#ti6Q*pL?!79LeO)$wmE0ld{vwuI@> z7d>e&;vSFiy|{dJd?aR?+Nibg{f2K$?7$3L4EFD!ea*w>F=|*f*l4UBUw|o>MvG2H zYqP15VWAzL^pI|QLcA*~w4+yuyvxy1g9ZdDlF=5YZ0gam(cz4YR6C=cuF#Hgb@Cd= z>4xA|1f@C2H;~eWW@fUSsp3ssx%NpPv>us(JDPk`c3^M-*1p zINs`@cs9+`Ozlh|JlcUA$>UeD---%uOJeP?+!*sgGf-Xw!^5Hu+3n%3=tC-Gg4@QxGBj%Mn2PD>2o)7}8XZ2m{aV#=naz&Z zoosSV*y#ru=N~_#jfMm$g?7@9mW;Va!%8s2ze9f-@=FBE4G2OFuC$|St4U!IF)mxU zrK2V)(iIjF?F1~Jc0{Qi=yz5{L|Lusg3!|s!C;+gO+*2jvA6<-gt-PYIGCCSv3r3Ga(<-E;aLpMW72%4{Pcqcu zjB>dm4K+o_x^r{(M7km(lr^!yt^OXQlwg(3$SBT?ce1rsX_uHG6$$4oU(Oj#D#?T47(NzzW2CL4x0Ov9 zgEvj?VYAK}@=^pI)nsyy^kM0$L7je8x3lob5bNnDLsTESJ$>Eq9)k-|(`d}K4?KI#lSNn=5TrzOrB@>GM*M9ZOh7Y@>zW$P7!vIv1nOk@r zA1U59=M?s74;Xyt84Y+&=Q%Nt(_a`A56^(GWs;+F{EyFyA10f{9j5%>`oq;xwB*mC z^uNY;xyU;7e9$u>$rVUH7GLjKVTRKfLzg?js2h4b>eqF=Q|Qn5I{rJ8ALAi!9Ohj2 znfwCbE+an_{yK*vzdX*?`Eq{Ecr@zJ@nPcYpmLybhmMcO96rtA>T+~5@kw&6_=kz7 zIe((h(-_~WTuI;lc!BV9%Ml1aw>*LH&T?IPR{F8{;+e&iuicb80{b4yOngA!iNI5v zqvw-GQhNSLkM#7b>~PhsRygePFCW2x9<(a)&qG_P$u z;9|;8@7qwb|Az`F@4?)*Cod*1xoe6$CN#`qi?q`aO-A@Dr2pEfV)6*i9cN2ZNx68; z)vTco9=NGge?|3QgDR|G$-jW)2QV9#gB5;#Bx$T5(U9qX7Wg7ZgiZCaxk4O~A*Wxo zhO3!=0sYrbf+k=|DO5ckVhwX*jcK^uAs6~3^IwA{WZgqTZd10v2B}TS46)Bp zB+ZO+ScR2V+MK=FtkdFk!r2DnY_KtK*!T>_a3&r(hXYKq$s7iA2S>8k_N}wQKd`a! zj{e_Q-4nFC2JZK}zdv3{{kprl>eZ{4>y>=MeWHoSh@S#&p9DuwkgvR~*KrNJXf7V- zDv!gVZaaWsH;LqIGmd@x)T_titIt`mxpm<)vcj6_M&Wmg)TK&aoY*;B+k0s92r>V? zcki2d{i%8SQz0KUn7>+hSk{H@YS)G{ht^-a7X2c>PCNP)b~STPI4PX)t5)g}wsRF6 zpF3C2%x}$Pw&ov%e6iqZeJmZZkDCI^CJ<^LfK9MZzuqUO~Wlui=l?dQkw$&;w>b z9uu=xRa13TRm1G|A_*6NSCX1!KEoi!(v zbi%`2UfXa#&W9s;O%@PFhBafu>s*uQ;8+HB_E2QlzE9pax-W_T^9ko1>NXr`f}s4Juc3M{-93*m)k^iU#^H=$F9nLu>yxUKc?r!(kpxr$je&LGeYbxPf*SAN);ZCo( ztpi>3ZICt_xQr}KSjnH%C2+zg(Mj_J@hRHOC1{7q_#{&346cnxasGbXGCmMtO2G7( zo~l*NiP2V}CD#}mNi^oy_IN`BqpcIC4Auxfuh%Cu&Yizu@U*5n-LK~sll48dHT~(D z%yuo9s1v-Z5%Nf}w)%m1TYrl$*gnzII^0n$Hu$4P^Vo)TVXx)$S?rGN!Hqq25r0_I zJc1JIZfxp|Syp4`M0d}I3}}*ch3|qUAt%Vgo8(@^Xj20iBQ0Z2e=u=DtXwOwBbDs( ziHmmSgpet0_8hy<-LvSs0Lk+^%eXSI$Rqu)=|b zOXlV-SzzzsF8u>TyK=c*Lv%$w+Ov!=@OAuMK4J@zP40i;aI$i2cmUaTJQBv?w0>>4 z-}QBlA-f$~i#FT`OxfOCYM;2K4UbZUtn^*tjy7C(G@d=+rWkPvUc=Oi=gA7NpEqI6 zl>7O?5}a}=$qJzU{6~ zUHQI=C_=G6zv14{mG>ivh?VI$A=kT0?H>}!3ZVP4h*P7v6=37HjIS!3A6>@d zZ0Y&1>ke)O*w0hWg#8^3M|*_lJIRLxEuScBjB_vBx`t31w+mc|)$R+K%?B0edD=*}`;xaMq+pTqe)*I{odBVA9p79Q#*c zdk8Hf)+T-!-nq_V%T6{>DJ@8}zYvKAF9?N2{8ojl6zENwdh82~eMZ$$Z%8ey zcMD6Z2CC+L;;Z~2XO-W{snv$ls20{&);$ zGv5nubv5_QkY+23$spod#oRq$7Hk@E7kEd5a8U}4hF|{greA4=9-qp7Er)aj7F%SP ziI)7|vHwzqd%e1*7QWld+DzlvWvXf+D0RJ}nf_yAeiZ{8%oKiU0^jgRtl7)|Q!LhcA4SIBs z>9-2M7FgT@2KiSw25BE8_ysb$X}#NU!XUvV(RTrHJsV2+v!VLwM8h_8mjfl8$o5hP zmtRLCD8Y*wi2Xca+y18My1wF@A1uKm&@73!*w4>8a74q`kUzkN(h9Nr5?Uh30)s@@ ziuGS#q*7Mtrbez*l%n2{tHOXcAQc7$#-rGUCd)6e`=r9@Buo&AG&JSd2NWNo(;;0` zgspCJSmLX^eU7g`IQV**_uYn*{IKDE@I8{SHk@!{!wuI_PH|bt1N5^5uOT>efnI1P zK0$}X24&K`J1*vd9JiVHw8KvUjf9jIk!RwR-Gl6Ta;RenjoJCs^r6wQvsQJi$v1}m z--g=Ty>Xy_6MnMgfLRzLg1A_z8_G1!UbeXQ;^~I|RW05(n1MofZvV*eo_u!C=m?MX z***FidJ69<{A`c9zK)%i%T7;!>cA!8i9@j>RNUu46T%ahwDWg<=z15wdkCW|zLON5 z2Nze6+f(`Oj`F(~cjDbgkdyMBQp*R*cVE|tH=nuU^`(2SE#Eu025&y)Iu+-36npw* z=dLU~?r1ai$nGt{kGkG~opR3eV!YJa(To2?W5BMOz5FhXq4-vD3^M$Xm2dZy-#(At ze#Euxx~SB4s(knI7jX9(R6?6A-R*PkCeh~Wk>M^0Pwl7GXZQCZ=dL6?d!W7q{d5WX z@IC|r@htUHcc8M3>C)5xR)Rl*6U%80+igEwfvH z5XsV9C`VhnDhc_yzI1J>E+mC+JqgWYJq*ZxNln$%)_Y`Rm#S6`kH^?pAz!mi`%k*w zTE>=mg9A?rumK%z@N{_|g|C$G^VFV~fS(K^g%SUEGcr?vyXx{y>>?$$iDnWke;HLdE)tw|c8?y2UgzIEB*efdyR zK=o;c+A=V8(Yh^{Og4^gA2R$k{jIT7IGKxf){Jz3x@?SmUrI2q&0Dbh#RE*O0~btV z%@nyH_r6d}B$?wLg0eD~9227zV<&X7sp&Jv#?G3GkN3AxhL7p@AuMTW$^NnWEV04t zz=ocl4T3&>@!G}9W+Sbcdh}kyJ?9Xf;ZtL^~k@#YQA+I@aeBuH@54VK1 zpy87xEx&hoWM9rw^|06QCF^G|U7WvU-d>0JI=C=)OW9obJ4G%GICz@_f86mQ^e&%A zy)D82?0UOHxdbn^lN30dxEtyYIx8FZ!QGtpj=HWZ@@ z3c=A=l~)b9`P8aIn6*{y3xiFNSJ@3kd9_J+6rtPgTwYmqqy4ejOO_Tdo#FC|9W(;R z7IJ$>NA~7&dq;pd@<;YUYcnvS7I=SWZ7+tC!W)Ug*@P)01t1e`aMMg7Ih=BiON>e+ zCslS_*C_-OIBxh&n3I&Q{Mb*HVqo07dbY9cg?|bUfa3l>eWModvXIi z^Y}lvXOKND%DUkfTfI$gh5o2D9S;0y${1kK=`mCPEkN_(@H{yDqb2x@PVOM_tfdP0 z%WRl!=FgKvC_n!^^1u`hzqSG{2`?RTS|l~2%z{ZOg!RmCquQnbE zgnFuvBiXY(?0SnxwrhQc%TJ)zI}Cp36<^*iAZwgQusqP(3Ca%GcedV&sP8BB=|}rd*gp zEIblXsZ~IkDnPQAmYv^VZ#N1TnV!BiNk<829_+AGgDU}oj^1v*Yyu*C&KqRiq6mPu7r)drTa09YhP5+wxl#uyn z-S5{yv|cZ~zQK6)v2PK-7se*0pMnkM^Xn!Q1d=v+p$RkH>zZ^lDDJwo%_J^!!MbVh z29Gph&x<7%1@Q@5LQ8saFa~4K@=cw$I=++>6{cvBh}PU)v-4D4ZO>1}W)4qIp1qjc zMlrA)1>yv~u{T#;wVM*~3hUM%9t_lZRlg+bs%WUEZ{8=iWLtx_e9GJMD7$xTZ0~@* zMyT(^jfOavdIHtdY<@&=;zu_8ao6o7{@%p7hYdgKdb=Zu>G_vR&;P-7yQ8TSoYu1a z{1NQ*wAV7hX}u9#5}v-G9(1%0bN3`dbKeI?j2!>`60hr4SD3#R>D^aeAC75?(_ zuh|IT>z4OYe;l|Z{ADkm#@fjK_XBVNig zgql{P7 z%ci-rp^x8Bz5WxRkMWtap+~<3S+V?WK>v&LWgGhJ2f+8RN7&_hlJjL7`tUsf+E8)P zX*VGN%DEwP-H0BZWSj(DK7=aJH2>66LZH#361N{Rp4Y~>Ng%#$f8~*%&|HM@+*btR z+BWo=`@yxbSJ~xyk#lVu`rIdoYfml@v-5=aLLVr%p2V(4Bn1$&~B;!rgW>zLW=BN`ti!;v@5>Z1RyejjL!ppMC>uzLt(iJ#mXreM5++ zT*zLYav_Gp(NHiPAqQ+*eNYauBSeISVPDuEtf|bh5Y=En_XmT1JrG1se+tTyId`>t z`qcYqmY-f8cHP5AxdS7Sgd=diQMTK#>kd@tjv)8KR_&>G<&?MZ9qFki6Hdx#vWhy{ z)w8O_r@IZy&S!H|j|e-|&JoHk1m39iM}5U_{)xO~4)o{)*j-P#?(7+?Ptz5pJlP9? zkrKirMl6-*$_AU0u%?K?UO=`B{;@edpcg(RvQ9N*s*k3RsI(J~FGEtI1s2pzt#D+H z3EHt`{rUDkYT$rG4O^Dm=!@vbE4LyVMi*ztNK_u!nE(`I$I*PrTsrjK=PI z8z1{|EB0-)V(DK+J_7X|FEP#~_7Yx2D>VyQLC{{|Y4jUeiYr$>EM^iGG>KgIhs2Vh z!}0{6(l_24OGgzefK39(fww%8EHsB};}u_y*Y-7OmL)1mmCv-?ZjYh*t2;5zFE8g^ zPjO80{s=FAkMP^Q+~)d71$2jgx6}7L*R$za8T;fv?%DwOJXZ6&E1rHnO1k`&jj*#ZC8RMLs1Ia@mq(!e7Y6* zhFf*(rmlR`t-PU#bGCr=U3t48_>i~c-X;iz2Wcv8(y}FrIE6}$;7*VzNcZ5ICjW+H zaZIk2k|s=&W?*c)&yvj1wQb`|aiZ#)e0TerZu+Y#+togwE()Jou_-$vh?5iUK*K;R zd&;0AgR0u6+uEkv3y)I|S4t$C0C%@GjP#J+xo-Io^%_)vCddEt>}=@hwtV~(G>v~u zKJs2qOs$Jk$7+UqI+l8hU5pB?Lvw;Ya7wQ5U%WT*wy8G!U-&J*;>%%kOAO+XdIOsM z6PG=QcyAo5oa&SbNFa76gj+uc3TKDviK6VMN&47NKkmAbYYyv{^Js;%cY-6A{38A| z)^`~yqu$Jymx%)HR!DBxtsHSZ07~MRS@HbyuKNfx%fAN=5@z6^p0n2w^i79$2oKN~ zPB!V5C>dVMh$O3N8aY;4Rv@f8k!rfnr+Y1tX90_Z9vd+y;_hwjxn`fo9@Vh$80Xm3 zd#ngyiev7Gu+PE8wH2d)b-S~SInu3d3_W!!>DCV3?5qIJ9mqBCDk@RsP$f3yg+|!Z zA3Dk0(7_>902bG|W5fd|=Y@JAh*^kC0cmlL)ydUE?qJUt#p)}B%`Bya=AU2U;7*10S+$V7<&}+OSrM& zzjWZRn$K%1K}ky4Pm`aCIFkMJcS~^c7ZLSvxY*&qVHv;v71Cf3hdZ6$J%sTU-y+NS zXP_)@#~E-l^_ zjyiW?AD_`$f_|w4efV^_2o;kK6nfa{GQRV)>onKrN_P>9=Qv413;G#y_U-#$=J#oo zv<_{Y@lh7v6TVe~KY~5XWn4a9fyJ6>%XyX?5Tgw1;)|I_da zB>5T|fkZ0WHI64;B+dmlfh5T#@0Fbg33>pg8@~>R#(acc2%sj!W;U!>pPM5>#LT_EAjL>zur|>*PyDZy?Kkg zmXBe!>iL@QE@%0Y`9)ED_IJ3zR^2bN&nqT=6&4is{a57)wLV=}*fQ*FT`4e))xHXg zuxEw(M63R`B9B0A#v(<2vou>zy{0sW;w`250MwbS?-$<@-+0{Jhh3+;epNir*4+SRX`bGHYUA$8U-g`&9ObziOZS|Eqlx&!wIfK6R2#*?yCg zMV0;kv#9dl^wMJ+?XlN!oo4)aH~kwCR!*<<(%Tx=`Bvp6?FhXoL3go_i@W@9CP#BqU4C#Sjy`n07WS zFq2W3p@h}irGdI!OUq!ad7`(WYh9*#C?8QZB`jA>CF=W{h1StTY&c!pyD^hJxWS0Z zvY^I0g2{%)L_|@e@k~o6ni6TsBswRWQ-l}0rzB%OC#WeDu2ssI;@{pY+%cYK8Cjj() zo#kWE-nF^m#YCvRk@c+Y9zHPA(C<^-m_gl$1={C2d)Ks?mZrtpgQMAGzRAaYJCF-+ z%$NoW7Fg_owoNms_Q^yj)2X|yiQQv!uN^Z@)Tq&zDr;SvvJ)H9su<9a=A|~Z`&$PZ z`$l7hE`0c_l+OaUst;rIgCzTK{+Y>lUUGp`^w;LNYn6}6frGh{w%_#xxow|7XW)47 zRvC(^sAeppwj`?k?3mxs(YWEe1sqAMt5ZFeZUx0)Pnx}C1b|oPi|egix9(pZ2HgLyXPEYSWDA0 zYklk$AmP7HJ>!g1Sq*2=|Gj$6n$`3-^_REGc@%P{xU~EnUtczyyu}2E7QQc5dYV?1 z4SoEQavS%SphsUvE5vSrc$fX`vpmjXLqA=DKD-6X1J53!u{luksD6{L4*O}+5bfSQ z;=0PQs(=gbIkek;<`Q@g>5IZn;q21We`K$BNhLV(5PF*QP{8?EZ9NrVuXwL~zo@6$ z?G}4czF*W+?fVa((0)-*weOR)SNZ*-o{GB|3wh=2F+PTz8)r0t6F;}d_}o5{9`@63 zD?y*$LK1;P#WNi!^wcdBy?Pivs4sHLnc|d#Vr9i@YS1#l#fxUMpZh<{SEYDVg-?`S z(mol9ry~7komD|y$ZSZa!fn+pQNwaeD5gfGR`Oj9-Ocd8h{B0PN5nX^t=gz*X{c+G zJ(8_|7RMkU*TuoZlgP>|Q&$mtz}lt~9z^oY6Lt~=wW$}oMrqH-GJJ`etH$2RO?jYp z7)TZ+8S!;HeQ}lIbAQtOtP<7&BKwXKRQ>MzaJrX(?9;+Ng?%{0OhZDI#r^Vfi3ZKw}0=pCGrvderz?Jw~ zKzxtrM`b$kEx|V`A#Z`(Xp*KsVs;D&aW`` z(GcOs?#(BFiC+K{WaC<>US5QMssulZ-JnmD;QvyBKa2?HA4>3#mEe!KevSA7bX(Lv z{T9x_@gfJch46W@%u{Tyvc1A^=p}R6Nw3NdU}KS`7w(dRh8C1R()4bXZ8p84`y-8a z>Vn%WWEBk=qwEK=j?~kaEO`5V)$>C`kWpSzbN{aACzOLq9+4*zJLxa+JR;kbvJOEu zYy*L`Tfqu#Uic%^Kk?d`j`^rzcsya{WOY?zPi^nkA=by)=6}pCwy#RCRFQ8|&xoh|+Qz!;vku=RIPpS) zOTy6$Y+guE;(9i;$n^+Hvfpmw2<h=WdnY z#DDD8i`=CE^>H?HtbZ=kxu2L)cB18d#mI>#8@d8_XtSC^O~Jq?-1s z*z9QGFX6C>t${UdHQ|PIghorggrGo~Xiqx0d0)v}5fpyoz#)g%!ozPrEs|%2o=yl) zY#QL)??b#w8Tnnx?~qRUX-Dh0eTyHAf zy`+41Qv!FNf=%p5EQ-2A4*g=1jCAx1M4h@%x`u4yZYx7HR*cwx~}d(#pt$mr2$@G98M*-bW`57`$ew(D52djWZJnIjym@MJ>%V%d-1@>*Z<>Go+R1I5 zNGb_y=6nj}tkS2R8Jbiq%?L3?VGD!U@w{~qj=s#c;mO6t$%)0qcc?~-=fK*bZQZey zg;HUv5p5Xh#O7XRw5`*WfCb}+c!)iwA4v&1wT{+%Z(Rxc`4aT;`BzF%$P(w-qceXh zLH}HW{$ZYUExX-!IZ(2(-;Og;ig5VboHm|LR0E2v9O0|NL-3Ui(#k*`{WG|f0$hAe z37)j!h?vX?h=pUmjtIZw{Jnm8*gg5G&%w)0&rzgBe2@K}_;025_wm>yeYe=Y%=S|I z)UV}X;a3&y&QZT$4IE(?+wBQRv*rB&JF&-sQv!?QKtK8O=qEkz+<&R`J$#4X$H|2_ zbFg3d0c2?hk9HEZaLH0k6|#Lx1IR;%)>t8@{wbBOi;pIICcIwM?V&Po-o{)wmCdxb zWK-;ht~Fhqv#H7PuC(g&YJb%&uhtW*9%$_u%MJ{Ur+X>p9A!7+RLA?FtJVH(ie|HI zGo2mN$>elL=S*9Ft}8t-knYL}t?9Y;_PKP|>JI2dJ>%m&>G5&s2T9E75d56@ZD#@$ z)2VE=09VDlThuMLFWzo=Jv~%p2-`(rsrP!kNJ93!>>m3A=_- z*~t)gYCEKm;Zx6X3yk?uP06m;IE>a_M314dlxsckVpUGrXQ&&;=^Nk^a+3WQSEX(; zgUZodZvAxQXt#;l(?$Rl8zLI(6=J`}zjdWj@_4N1~nU`iAD>qT6rE zy8K%od3eGaRKeexqTIiKZuZQfx;n{_j4*m@q06XRM!U=Sj$>5Ya%hR~k1CcI!9=ig zQ2x2_lE|*&*xCm4uqlrhyU1ut)+mMdqxKdRbApNX0U3oV__Q!&3>DZDIMqGRV;T0) zR_yzC@RG=3w_v#_hn#fs27r<$+c(7|*@rSDHKUEg+j}}U2^it_I^%-pZ_YNMMnm-%UB)En! zXMYtQaPhh-POVQd$GHV4#1dthI%7NeP9Xipp>2b;Rhjwyqq4^gntE#EY_Apx3@&t} z7jun+r%raQZjaCO4J@^{t#2QaQ(t3Za%1Q4Y2!nw zHNEMj-kx=oTZj1>hSm2ds0k~CXG|Su2~gFS&mh~JX?o!koG#8m;Jok*P9>oooWiLV zQLPW9(2iZF>aZen@Nztc`EEkSHikY~_FQuQn3JiPMVS~|oj94Ttp_=mOwfcuAhXws z&H3iR10$pR2jhc{Vr_Q=Lf5$+0}VaPuEbbt%UJ8;@aW=A(_2!r?d`Lv&1|1)_RX|s zxA*sN&vwrAn3|a$Ph=^fGMgMrzrAgwxp|~*cwyn#OKXSQCR$o1+J>oG%FyzkF+1PI z&dWZsKlv_vvBGl5Rp?tMq<4mgx8>`qd*=^~pvF83M+}~|WQP4i^BohrGnkuh%*|{j zyO?TQ5WdSN=j?M{vpynVpNQ98wfD+ZW~{${{EQK2YC6|;cdza4Sm+|jU*46H=KUQbjg2E6ox}7q+1{SSKP|n~-MyGjFLrk? zrF&Nm^i5Cq4XgqsG~ld{_d}LDlrR8ZSz?wBuY9v%Nxg2xqnYNCrs+sV^6F2?je_V? zEw#(TnAa%0tb2(|A!~!_Y&FS7k|eOez;cT=nZu?^ED1c)G0Bz;uOw{@w^vmMVv2x5 zLRL+0OLIrKs@XR!U8Q-w__VA`J8F7r{87X!6+^Mw8?Z^JF4Y=b#CB(m7!KJ@%tQ`A zktb9ta>Y*AovN&<8}SNd%DkB{B^138ok=o;np}yxfm*|{&xJW?GLd! zr7m6DoYlPOi0+j^!ZK?1dSUxWPxNZry5Z6_0zV0%+jF9bHjNdkXm4Q!Zn zC|Y&Eb*>My=SbUP))biH4>hlKn0>aY>L>7Bx!>ZpB*W+Rc=czsHybQc<+*+7r-qH0w5F{)X0AU9j4ZLluN7 zK{u|_A)YR`0uie0+PX%Q4c&F| zY(sK!qV?0w;i_0;G(xqa8YIC4j`8x9XPrP)FhdK;VIN-s-}cYG(t|>OdNnyIg;9T?t46kU_NEzTCq^*I_`Q zxAM2*%Uw+4&w$=IB)yzwvg-;w18**eG_XrqO85aFL@L)%pV=FcKYTAB=rg;X`pn+Q zba-ocpV=D$>BXsRCNdRxpBecf>e!X60e%DCXAa4rWxw!6K+tEW^@-!o0@0)+ZZkTlwn`CHUyoQ&nFf`;)|)HZ-vAYMnuh;YsW z)uLbbd)UWR>_^FM-O(`ohjUlIx|hK0J|O@u+_a}yEWrf zL6VR?IECpAEAJ!JjZrapPjEkj`=1fMf%oG`-MyOL$BT6T9sK?{Y!IA4!`pAR+sDu_ z8l0VOzyE@8=gRkCSJ3^pI^Tam_z-`;6Lc>lotwwLV>V9f;U>0Z^9WwlVtZ5bHw=? zcchwANGNi5tSh2;gQ#9iNyT6wOlXSK#+8$%5_4+|J-HT^AI}8bbX;G=`o=rR zf3Ww3(a$jc_lFC6(OK#E5?bWV23%C6@=m_4*Me!zeEl7oqRki zKDzCsg98-+%j~bN1ITLKj!`D@^DFo*3)^Xy(LeGBTmzkzc1*i2Zcd8a?IR<|bKJOh z!|#k@tX^m~5lZow0)BtsJ7M;fKr|XC%!a>HF>Gpgd6nxLwrsbHcuFwBWp5C5U+p<2 zrc86bJBSv&el)BJ5o%MS*4ap;Fc+w*3a~FnzRhvTo2MR=c6Fcd5M&U@eG^(JZN-Ap z1``OV1RX)6umrg|>+EIDMUNZK_X9@P>Qr(n)xNq)2^)r6jUC7h?ajyX3mu~7p~y08 zD2GU-gpr}|YTE*W&hzq;PccGDWX_&5aZ@rT1$gZS}R z42*sgL1PtmxE^AijLrk4cSw_T@GVInjSt27|1B*;58;oNq2^|k=Np2EW8h(LWv!@f zGs!(h(83Zj1rm{(lgsue?TL#SwW=R@UFtYB3y)(LuWFy(7w&|)vZ7h`>gAc7A$B=oCr zrx^^I>_xg$Fk^@hcMf$7f$L0FJkuk)v5#AQ<#t)oEs`mNs0DO0dxu*>HT4{>J6uOWOOK-h z{Q(|XaQcb+2e}M!zKZM9__d2IxHhtn(fi+92M6VLwr2UG?Bj0i=~#}r)}x<8INx-M zZNsd%h?8RmxWI)>Aq)POJa?`(fMS>Q4?S?6M-R>hC&c@%C)j-~PVdu-D9_*y%kQ_? z5-p-9uoZ=B4G?DWyhtbKocwv=HvT*n4FX4@tQ@C(eD54SBIkWvpKD*+{V(@tc^}4h zJGIYeu0&B=O)t)Sdyf2$@5NCX@TclNKAtrg|MmR+9)4Yo@oePZv#(?5?{5CR9Qr@7 zJi$&8zD3p;&Izy`6pnMISYD7!Yc?q>o6j8_K7WHO8D z-rVE%!xCwK!yW6^-T8*3?9*_jq^o9ml1&QVE?Rp1cA^%RJfRh(0eD`Q3{A*uIt`j| zrflJ#k?w^DN3k2cDhcBBxjWwc(Oo+~@}?d*{uy$X^6XmpBjE?1Y33czQC=TO6`FI% z1eBr>z(3G=8VI%{al=HWf{7HvV21>^xOQVbi}a>EbLaS`j^QLW z$tgN|*@j-;E_?^k7iabe1?XTd3dRYw1-P)qRUeQ6J1J76R_+GkB1~$YG;!p@$Y?mz zDRlRS&>aEJ0nx+OZLAAt+9l2B)2Q!()IyHAzvn|~74&DQbL03aIzxXprU%>oa#+zZ zgr(js7=jO5|Jx^%TUv6dwkk&0T)#ZU&H^uUY(>g4aFz{K$aVfaL|A&1e*9Qfenh{& z?$gC--3N?#M$C-+o+F*)<*5tCLz!$OSm{MyZ|ttBGz2docu$&K=pq8m9IMO zi7jXkc0Fi#VEKH|=%29aFM(FO47$RZ+rpo5eJQ^VFP{Zk_zSKtoQF^sMIa1RbJEUaeGYFSKUeY#rIsdIqjZQgS2n-(BnhSOhmy-BU!@Zhns7?SOxT!*4;hAi-}D zs2@q_Vvn&0$ZH18k(Ms-*|iONA>?H!Wj)N<~)uCrvOc z?SsA#qr8p1Be9}2=!>-95^|r@4ICFx53p=zEY)evuUsl#DSE=}0pnAOp{d2@K7?)l zXik8=_E|`8CQi=0IqG2_R0(Q2H!Ie}OvODeMSS8fEB+S#rN(FcGFpytRrJnoL=opce3!^Ek)l1?(;%;NWtS<8qSY@&e?@5}a^J@LL3eM{!=l zgF*;2c=L19{JD!eyRiFh$B0uns@6->J&wBlLlhZqajnuSj{bVc2&6<)QWtz#d)^TD_5NNxJ3Z=HMoyVu3X zw-vq?pB-vto|;^uW4fnmFjtkXpAoVPt?7lX?t|O2YqFWQ>b^jr@L+R8-m~ZazXnZc$ zv34T0d3193L_!rz=>LM+v+;E-3a{npdFPDA^UYnGhgRs zI`=MZ+?Did$1byAevoy2A>v=(0iNO7n1nYqXB&RNAfeFagS=3MO?;esA{ii%D_XLUM>jF!rv4GZ(d8ZS6o*-t|KJ*8tk$wN@J+GlKn=5 zF0v1YOtX9zC4kvm=C9hH%k95vezpC3_1NJp-Q8ObkBuMR+}*wT@P?67`ZK#mCo&qO zS4atVR&`Ccv`lwZb%Ye?U2e5{SQyxI^_r!t_6`i}y=rOA)q4iI(;Ls7nmT7wSJ$R< zrl!u_n0{^F&U|*~K$E9R#nGyUm7Gj`zc7i1g}oA!PfD) z!UyVdG(4J9XE5X#ijxPxarxr!WVAG9E}%{*P4(}Jp~~}#j>bB{SI0cEBr*|s3PE3> zTQjnu+N#j7rS^=TJ~DFp=-9#0(Su_dl+oId>7#mQ?2xYf$fGyKs~aRmY>IfXrc@7( z{$+J_{)oCo(XS2q5yspqKRtBX#Kghj;e!(srww&OOJ7hYcvhGJNj@Mf=O;6Ke<__B7%7FWVz2Pd=$3&SmO_ACP^_ ztY3LNlKbJpll%%{AX$Yc_U-d^_p zw#h`>WHLFK!~qDsL#?etgUJ?t5}+f`VYj@6+i9zp*SM}ljcu}vIL9oe#$HRV8&rPt zy_0M`@l9lTp$ta10uP?q&ZE!cxKXapTCpGlSMfTtHlSbR? z`X)OS{D*u1+!y7jyRi0Ymda}M$9y>a5C8mZFWGG`(+}Z8JhYxA6OL8mBqNJ*V$doo z_OTBLA4EhJz7km5uoN(&^9g&NTQ5vVtA*+k`gim z_t5JQJnvqc?>lRMo8aEloejeTQM4*G6k{72=9gMyX~^hrD4^Y5*O#Gr**Jk8oIG@| zh86NLmT~l<5{`BfdY&bl_Sw>3sDS`H6}m`AVF|(%LX_4!N@%0mz$ple$Z(>Xbc8o* zoIW0b@fSzkrcflzrBYEzg_Z=zTOw&IO~7K3jc>ek)v8N3E?qS1R?NaqnKka{8a>z| zshTFG&%}WTtZ8RwdPgHu^`&dpZ@6Y@`jT}Xzw{-jNbz{zxQcb8ObxR+>7SUuS{h?< zq{D+!+;ozJ8{T^EV;-maHz&!(BavTZzFCIF%?~>(V{gS_Xw1f)<6m;WA-`_~wXX8} zP}(p*lAP&G&9t@6q&jDkujKjRXe&+wL*jxrAl%858s<1ge>YCdXnf+d;o;LJdKWu8 z7kj(uCo@Zjr&XR4Rytbk*!?JrZy^-Q>zlMKe@naz71bo+Ht2+O=GGycpV5o6Sf(%| z_BtDYMM<*`q6otr3>KNSt?Y5d(2+c(OBMxKgngJ6q<|yls1Wn#|IuT@FQ#RCd6RHq z6+egl)bOzz>x4J{BS(kR`i6GHeuw;;uxkPu?n(Q9+}>tz5{ICQGl^A6W5q&cqju-* zfkYNim-752l&t-@APKc3DN4_$P1y&*06i4RuRXU3>7jVzg@19 zSF=RfYgNtf9YuzvS2x1&6ejDj0#i6~;4@+j-o7||VkhzVK?d?zl-)7Pb7BABEX$#?ik$9K3v^0Ev5(TO=bpevHN;CLB7uWQYIU6sU57P1^P^_7nq zsu=x;rb)tiO&75*vPU=?;gp=ImiZokhx zq219j-+}+r^QqK)XMJ~VZFfEY$sW-L-GP8OgfnX_Y$T-fn*s2PgKFU&T3!tJ-Gdt4 z(r`x`b^HDJN+7+E?po;VTl16k=UI4f76Y;)IVAR%SpJ&5!) zfb+oPfk?zxT`^dWV^qKI;!4g~aZ)M?!D7NDX}=|Qw6X_>HH#XIin-hA5i2Z{vAo_V9pYz$0uNL!6_7lu1>Y{TM zEHjakW>~>#OU$N+e6?(j{Je!Pm;WA{ro%>dUOJoEpD;xQ8$X-Yb}U`Kdj9goj-@6& zBCBpAGB*7z_#jMU{CE?kh2by5U%0k^@3kA&Ub8P7t1r?rP6<5a#)Y~nN!0Xe*;mI; z(x5u)IBp7ahq1sX@bbf7!;JPUpN3PV(}2#|Gs@!7GdwQMIp0;m3a>?89c6CWET*HV zb+EsC<|~{3cN*!x@BJnX^+#;?-#h}A-2tWrPHOoJulYw#gXMJhgm4MG;a zx(c^)@pcZ0x*w*tZECJdn6l}yu%jiKjWkS7jn`FY5}H*d8>VSCXS3a%W*x$~zJXI$ z4V>Db8DT@x-PKDyy|W2Gqb_)qh%vqUw7YQ(0-Mzh z1@2m<@D)`_SYGJ!ECv6v?)4S^Lsc{!>3bs)#IY-?Ly2rN&V~>oMq<@K{dYpDDZi|$ zh^d>>%ZhSyK(&-33a-7{BZ^GY(mqckh8c(4gnmN|#Tf)?EBKQpt!%0kSq!-at|R6_ zg(3?tn7-MI=k2p-f>|Uz?#_FWhz$A1{z#9!@@K5l_bgDgorS^yzE0mWv@4t4HAGj` z4;4Rt3|xlkB)?)52!%Us(!zOcO)@K~q$`vvqA9L)wNbm1VfJ9{B(0L!nnG_7h5t`} z>MYyD*FInTg22u^siIU;qlkM^56Rz7=f=UG=k(E83kU*pb%D+~D_N zk*P)}0xFP)9TYLzM3hN}NAT}=-4T8c?OeKs$YISNUag;Jk(GB3J;PFjezyH@_U=DX ztqZ0OxBB{!t`8Xidmq-pK`yhv0E<1fEjs7QA(VKLQp#uMfgP?i4A@7M+S&jehj%#< z!_D#G#M0O;gmA`VllSFt{9r8K(i|Uaqcik0Me!HzD&J>D%c?w`j)$K5#8w=Qw@?)G z&7F%qskw})iK*FMI!@06hog`Ews@a&wW18jy7rZ*>i-v>zwp1z=h>S7MgA^O9Z>OK zk^R6ep_8vJ;z=R$-D8&dK5P3APO0EaD^L9Cqbb@`EnHBwmHs-T;n-*Dg=hcKQ-Exa z(8nJXS-UL5 zXPrR~=3VR}#Dt3cjrZ-0NGui!$6`$9zrv9ip4FGHKzz9ATzusWMP8isQA4i<(CB`IQ$Yf!|$S>|850>*cKIFJ>c73 zY|8NeGGMU}q41qm*ly9j{0!@152B8uSsH`W<_3L92h<2qMh$V{b}8!{;!&kq-2jvB!KcBF{Y?17J_H*f_(y%xe_wDP~oe$5_*jyVH;+%~6>`C=;(AX?kk#4! zSA2k7Q@d(ryvho>ade6|oNB0BH9J-Xmo`EInlIc|%Wr#w{B|hS$Zt0Y{B9RJ6sQUW zLps6>p;UdaDu{~7me;CDRec;ckcAKS7ig=)jW)oIj(*PTba1Zgse0Mp?LC_gWd^$a zPUk}Hv2cH1kB>SBbIjL?4AY3uA4IUj7fRM5H#daTNw3ik)0y_`+=hJE_mfn^IzY@4 zP9c(KM2$d{+Zxioxah`)* z-)i_h;+=BP@&;rg6x3Mo{FC=Kc+GAO7#@_92&1oN;Yrj`(1W_hysYpC4Z=#qo|zYf zVN_%BVlL5TvJNYA$)j9br1*I;&d0--iK3Td5ap`b!#MQ-%(_v3d|=m1A~ADHcHk8J zo<0RdOnZ8_qWWScvt178hQ=P$u%fj>Ck{$py*HQNKiA$iw|_9VZ*^Nfzk6t8PY%1k zhxX)1x};s*;yC*}G;8d5!wM(F5kI7SO&IhgKN1oyDAbm-y`h8_ju(W!i=F%tY7Y0T zY3rL$d^OVF*w7b?_f=PSwHWs|Ot;4R!(UCz_qDC*>6}k>P1k={Z|SP3>W|0zyHney zR&7mnw%v!LWygDa#~VU*#siJ515MHU+B#EPS50k8B^n+u>O%Hins4{=7qBn$XGB-P zB%kWaR0`^x<4_=NY)vp0LMC}YPiK_%*2dXTQ^*gaSC4g8d)8T-7Ce?|1wDf)_KOYM zJeCi2znEClRafX(zYX6)MwM_gydbdYo!xbCVmQWxy%2$sN@ttn)3ERL^~qg0xOq%q zn`SQ9)D`O+tWj@)?PGjc4alCEZ4>9MSv+q%InyC&e(l2)<-66Y9YmSB&F2gEr#GCl zYT%6B>l?wNjDUqHm9~Cz%iQ7d@xycZ^Itb8L&{s^uQM9g?K&+tdCo?d?bu(9AO9?T z)8(VeLI;t3ODA8!!N3q*f}S8@S)jI1vn<@^_Q)PDPLYuPDvPVa3j1lY_g|K=q*f-bYyigy{&F zrX2Foamb`|c}ge>H;BLr$4pigWc*u&4;afTQ;tb&6MZ_09ZO9iR&T|k5TV{c;UP7w z79LY6?UHCJ39QWspCp>vPwIOPXydDt2b=hbptLMNT0~Q*66BZOR(}?JDQ4hwRaN}% zH(U3*y*Q|nvG02V$n4zf&U<{C4_;wiD||%Q2!X1(74g`+EUwkj`AY%eL7N}Ua4NR* zXQH4OP%oAtKYPhS(0?U?v8JiR6N$;K-2+S6KvYdlZp(rUd^2aQ>5j%HcJ$+nZun+1 zn|gXTiK{Q2&+eIRORr7|`GXtsy4$B=lbAle|Ln8V!>6xH=Lh!<4(u94QE>bLEUaHX z13PL-=B@Bx@r|yqV9Sz@a8oR5l*DF6>9B<|Iw(D!OE(UtYi$z}xh-1HbbIY!N-}+S z_$*;Bd4UQKq40Qh$3Pv6@k^Ya5-`@PRejCTj+pWT6x#P758^MvuMvZ!D0Byp2oPs3 z@+QuGDtFt#WPa6qwvJccxAXZl_LYvM)1!^C(aw(6_V!e3JNs7WSYwQU4YARVR06<6 zs_=#tJABwSpfs~NliA$cvpLhhkQ-W9%ni;L&ORx)`?&o;sCkSrxm#9@X%n4s_x~`i z|NSwub54SYV^@)ThpyyI8md(5}QM<5)^@+QX4f@1O-GD!WodQ&?vt1Yi{2+%n z1OAK)`=0>M2&f(+o=b3FJuJqjz#%^g_>eHi?i9NLKdMkX=TX=9c-L?#WcbFR448k*F8Al0H>o0H9_q4HnE12e*+>pJ1RXp`$f$rhP>iR)T``d6Ye?b zZZAFqb1W`=k87gnDVIQ`b5S-oX=L{7CX=7rChLlDMzhJz_NCQTO!2hQ6@Pccm{W8dL%rGBsF<>% zxjn1(h%o3|tEjSSP7AX#u;o@gYq`|y73$cq@F}}Z3Y_!l=bEE4la}y>=D}7`FlooV z)KOp80XHKGCy8Q9UZ`uz$8`8P;>lzjr&k%VJj6ZCX$MZ|c#d;_n$uV1b9dBs*VR!_ zmVQ<>H&;cQn}v>=bZu?A#{QXVidM&(s-kEY)klOSb{c2}G9In+4px{@*k#~^tmKF^ z?^8u7(;R4RX++G7j1a#jxT7sq-qw~T%M5v#S6GUKo8kfN6%6PWxD?LGiunB@&EWGm z&UOl~BftEn=7D}pA2!IZt*iS(U7avqQ(H?J$!mpP*Pp-@TJVe$SOLja#>=?eCwh`3 zV0OE=HQE^W22f;xp|G)r5`=~y8ER1#iNTT}+-C-=;$DBPPcje(GGtiSlnU(EWtl0m zA9!sLvMh_eB7CiYXB@v`L2k!`SbXIwey3!4*2-Aas4p@tYeH6W&%j7;DB}QsEXP z=VO1Ao6e;%5SMV9bS@3rU0~mI{YE&Q^S}YxXznl$X`#Ct&Q>ix!M-^VPg#*FBRLFF z1+KY#Do$khBE3PH@Jg-;h8w=Cf@uE{Ckb-Ezn$Z%a<7w<@sz z<+I-ma~XOz&Yd~}>kkX$VxCb^thGk$%vN}9HZ&%@w*|x*X|HJrI%QN*#y^VsYfWtp z9?^q>Dnb>NLMzovrD|#oA>N-ni!XnPxY{;*T7abg30FIhn3@O7Y`sqcQ&W(43}J$n z`*9-L7|yK#ZP7?i%74E6s{H4DO}Ur>_S2GV1N-sm#C`~S*RqYvU!b+St#a)?QCoXO zRZR`H4dNNsi!8vpY0fVu0mB(IG3WIZKYBm?c(D{3!VEdm8Z-1T--+T#T3jFD*N!B` z^&|Y+k&C!~)OnsuIb1*HTyr^r>!Z*@7}|d$dpj&LM{=V-j%9Q@>{*K$*q!1P-WV_u z-nP6v)2j#jA>NDAawOqaUYE_04!C}te<6kY|BU-{!mX%Q>-vUk!q%BMzsFNgIQ`(9 z8rM(qYlp+)`YGo==YzO@n)kB>l=3d;OB_MTyp(Ym7DU@Hi; zOrN*54hNeOpMximLfkoOBx&0bl~$|VJ8 zQBysh9g?M@GOv2TqYFRMW$ZPWam#)a{;OWp#S>gJ!spllv_TnXTw*zjSV@U0sb&sj zvscceKpGq;?itztcAq>*<~=39Lk-D8%AyB)4$6=16n-`1v01`Kq|hlFI8TtJNwnS}{Dd`& z8@LWtq7lLb#bQhHEgF5#cE$22DjJuNn56q;-nj1DDHLX9NrevO*{CXtN^MK3v5IE5 zNBAXM5Ko~~?ttqGc4L1CANg9}YRj!b!;#I7*jSAOF{ZiA)xs|adXQzQ*EJwx%<}di zv4QlQqppJZ(f><5=V(p3rmnNLwzCd@w3D6_t9JApQDmo!m(t29>N&Pb#?>>f=h)&m zA}yGxd)C`noq_As4_7bz^`aPUid6OWz!wWG2Up=(yuLmHe=D56F@Jqs(AIJKh3DAW zV)IHJXG4Aca(%tTfu|mTU_d``B4To?>8ctmrj=TRm zP2@soB0nMCLmbl{BzeHeej`of&7q(k4DlbF{+2I;Ch~JU4?E_6q={T#Zm9eh`rNrZ z?|S$01ANDD$u5Ex!KWDtUtHqCG81`sBpwR-RLNuNl$tH8hE-P;jU5Wbk(jP(9)bDb zL1F*jgt!DnOM%LrI21NqQa3vfvC8@OIE{GZ7PJPi(SI{@MhzQDA-70p_E~gTe1*|fx)#3covwlk_50*!^I0MH94e2WFPx)Z%IT!RCr$PoLyGiIuL+IPB+j)o06x}l@wOevJzk=(3Rk>r0&B#2`M>u1C8fi zDLB}&tr=MwI|<5LPc^diX*7S5P>_B>1XPf85{3jYPze&i1Tc_5pm@^21Tc_5pm@^2 z1Tc_5pm@^2Ljbs3{(AxM{$4CTe#`^Mb9CZ^G;sOn&n1-ESEcY0KwVn1E&#AVg?DcO zs24z^X<7MADZB+n5~Bbf%58SHSiCQePPLc=W&_k(r!aeD_FHdOAi~4q)7jks*@G8h z0Stgw0Vq(F*QdCpSpZk-%`X7B=u-#X3DUZ9k`PINtJU)(WT2e|jfiZ4`T6|A71`{F z8aSy$*t#tgsLHET+R9FVPwUM+0(_6F5SU{IKcF1gt3u<^4`mUY04dw2CxQsKP-Z_2 z4in-S;Jx;8kBwzGwPo!cVxa)?67c6@{^4QZas-P}0G+-;$9bRTXV>*nET1+vO2O^$ zkvXAR-R|2?=Ae23>Y!Q8O6`4nf4I%Q*g-N!Zs)UOIHktWCW$w_0NT5*&mpYV8%9*) zSQ%=2JN{prlre+$=v&z7cqlN#_kBZhOo#-)=f{1qpnLLW+gMH{!2U%d2r!yWbjN`$ zhtO-gbZ9|)Uc(1-1lW0P-yf>aRRxGv=5d1dqYR{9t3pk0&$ZFM>*i`ty27}@bX={V zGo`rS>jFsvd=h0&u4}op)+zCLS%My{~sB z;xYElrc}yhggkTWzA=pjZ!`_8+pAzky&dc_k1-s_;8bpi7E;E3NS_Uvddw%BwsnnF z)C*H#MlihB4n`~C+hZ05*shZBsy8%P)6d}_tkVzJ-~uqV~g z(9Tbrw%=Rft#-L*qiDW@j~(AdH4{h$f;PT67n zL-%X{H=R#2!~j+Sthpv!O-^i*E+wNqu3et8uGc!9i6}q=G4RrPgZU&2pidI|-?qpD zWL*d8(ULx31jwPByX6pYJ8NC0ue4SiVD%wZNuM_NGA#(=uCwLQ09H2f<-PICLv4)_>T(Eo+kfTlLttFD~zcYg1aERGnPpK^04q*@gDi``!o7S9L}E&1rQ46OnCd5PH-%|{T)Yct6jPb`1Cc(?a+u!*AeRKgHf8XKc zY+xOUUrFEGENMO8rIzue0XBnpUD(jS#vckYuiwpkzpVT@ +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include +#endif + +namespace autoware::mission_details_overlay_rviz_plugin +{ +class MissionDetailsDisplay : public rviz_common::Display +{ + Q_OBJECT +public: + MissionDetailsDisplay(); + ~MissionDetailsDisplay() override; + +protected: + void onInitialize() override; + void update(float wall_dt, float ros_dt) override; + void reset() override; + void onEnable() override; + void onDisable() override; + +private Q_SLOTS: + void update_size(); + void topic_updated_remaining_distance_time(); + +private: + std::mutex mutex_; + autoware::mission_details_overlay_rviz_plugin::OverlayObject::SharedPtr overlay_; + rviz_common::properties::IntProperty * property_width_; + rviz_common::properties::IntProperty * property_height_; + rviz_common::properties::IntProperty * property_right_; + rviz_common::properties::IntProperty * property_top_; + std::unique_ptr + remaining_distance_time_topic_property_; + + void draw_rounded_rect(QPainter & painter, const QRectF & backgroundRect); + void setupRosSubscriptions(); + + std::unique_ptr remaining_distance_time_display_; + + rclcpp::Subscription::SharedPtr + remaining_distance_time_sub_; + + std::mutex property_mutex_; + + void cb_remaining_distance_time( + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + void draw_widget(QImage & hud); +}; +} // namespace autoware::mission_details_overlay_rviz_plugin + +#endif // MISSION_DETAILS_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp new file mode 100644 index 0000000000000..a0344f872f524 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/overlay_utils.hpp @@ -0,0 +1,131 @@ +// Copyright 2024 The Autoware Contributors +// +// 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. + +// -*- mode: c++ -*- +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Team Spatzenhirn + * Copyright (c) 2014, JSK Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/o2r other materials provided + * with the distribution. + * * Neither the name of the JSK Lab nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#ifndef OVERLAY_UTILS_HPP_ +#define OVERLAY_UTILS_HPP_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ +class OverlayObject; + +class ScopedPixelBuffer +{ +public: + explicit ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer); + virtual ~ScopedPixelBuffer(); + virtual Ogre::HardwarePixelBufferSharedPtr getPixelBuffer(); + virtual QImage getQImage(unsigned int width, unsigned int height); + virtual QImage getQImage(OverlayObject & overlay); + virtual QImage getQImage(unsigned int width, unsigned int height, QColor & bg_color); + virtual QImage getQImage(OverlayObject & overlay, QColor & bg_color); + +protected: + Ogre::HardwarePixelBufferSharedPtr pixel_buffer_; +}; + +enum class VerticalAlignment : uint8_t { CENTER, TOP, BOTTOM }; + +enum class HorizontalAlignment : uint8_t { LEFT, RIGHT, CENTER }; + +/** + * Helper class for realizing an overlay object on top of the rviz 3D panel. + * + * This class is supposed to be instantiated in the onInitialize method of the + * rviz_common::Display class. + */ +class OverlayObject +{ +public: + using SharedPtr = std::shared_ptr; + + explicit OverlayObject(const std::string & name); + virtual ~OverlayObject(); + + virtual std::string getName() const; + virtual void hide(); + virtual void show(); + virtual bool isTextureReady() const; + virtual void updateTextureSize(unsigned int width, unsigned int height); + virtual ScopedPixelBuffer getBuffer(); + virtual void setPosition( + double hor_dist, double ver_dist, HorizontalAlignment hor_alignment = HorizontalAlignment::LEFT, + VerticalAlignment ver_alignment = VerticalAlignment::TOP); + virtual void setDimensions(double width, double height); + virtual bool isVisible() const; + virtual unsigned int getTextureWidth() const; + virtual unsigned int getTextureHeight() const; + +protected: + const std::string name_; + Ogre::Overlay * overlay_; + Ogre::PanelOverlayElement * panel_; + Ogre::MaterialPtr panel_material_; + Ogre::TexturePtr texture_; +}; +} // namespace autoware::mission_details_overlay_rviz_plugin + +#endif // OVERLAY_UTILS_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp new file mode 100644 index 0000000000000..843b75e352648 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/include/remaining_distance_time_display.hpp @@ -0,0 +1,57 @@ +// Copyright 2024 The Autoware Contributors +// +// 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. + +#ifndef REMAINING_DISTANCE_TIME_DISPLAY_HPP_ +#define REMAINING_DISTANCE_TIME_DISPLAY_HPP_ +#include "overlay_utils.hpp" + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ + +class RemainingDistanceTimeDisplay +{ +public: + RemainingDistanceTimeDisplay(); + void drawRemainingDistanceTimeDisplay(QPainter & painter, const QRectF & backgroundRect); + void updateRemainingDistanceTimeData( + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg); + +private: + double remaining_distance_; // Internal variable to store remaining distance + double remaining_time_; // Internal variable to store remaining time + + QColor gray = QColor(194, 194, 194); + + QImage icon_dist_; + QImage icon_dist_scaled_; + QImage icon_time_; + QImage icon_time_scaled_; +}; + +} // namespace autoware::mission_details_overlay_rviz_plugin + +#endif // REMAINING_DISTANCE_TIME_DISPLAY_HPP_ diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml new file mode 100644 index 0000000000000..1054ac4f516bd --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/package.xml @@ -0,0 +1,28 @@ + + + + autoware_mission_details_overlay_rviz_plugin + 0.0.1 + + RViz2 plugin for 2D overlays for mission details in the 3D view. Mainly a port of the JSK overlay plugin + (https://github.com/jsk-ros-pkg/jsk_visualization). + + Ahmed Ebrahim + + BSD-3-Clause + + autoware_internal_msgs + boost + rviz_common + rviz_ogre_vendor + rviz_rendering + + ament_lint_auto + autoware_lint_common + + ament_cmake_auto + + + ament_cmake + + diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml new file mode 100644 index 0000000000000..5177b10859704 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/plugins_description.xml @@ -0,0 +1,5 @@ + + + Mission Details overlay plugin for the 3D view. + + diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp new file mode 100644 index 0000000000000..bafae1727b2f1 --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/mission_details_display.cpp @@ -0,0 +1,212 @@ +// Copyright 2024 The Autoware Contributors +// +// 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. + +#include "mission_details_display.hpp" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ + +MissionDetailsDisplay::MissionDetailsDisplay() +{ + property_width_ = new rviz_common::properties::IntProperty( + "Width", 170, "Width of the overlay", this, SLOT(update_size())); + property_height_ = new rviz_common::properties::IntProperty( + "Height", 100, "Height of the overlay", this, SLOT(update_size())); + property_right_ = new rviz_common::properties::IntProperty( + "Right", 10, "Margin from the right border", this, SLOT(update_size())); + property_top_ = new rviz_common::properties::IntProperty( + "Top", 10, "Margin from the top border", this, SLOT(update_size())); + + // Initialize the component displays + remaining_distance_time_display_ = std::make_unique(); +} + +void MissionDetailsDisplay::onInitialize() +{ + std::lock_guard lock(property_mutex_); + + rviz_common::Display::onInitialize(); + rviz_rendering::RenderSystem::get()->prepareOverlays(scene_manager_); + static int count = 0; + std::stringstream ss; + ss << "MissionDetailsDisplay" << count++; + overlay_ = + std::make_shared(ss.str()); + overlay_->show(); + update_size(); + + auto rviz_ros_node = context_->getRosNodeAbstraction(); + + remaining_distance_time_topic_property_ = + std::make_unique( + "Remaining Distance and Time Topic", "/planning/mission_remaining_distance_time", + "autoware_internal_msgs/msg/MissionRemainingDistanceTime", + "Topic for Mission Remaining Distance and Time Data", this, + SLOT(topic_updated_remaining_distance_time())); + remaining_distance_time_topic_property_->initialize(rviz_ros_node); +} + +void MissionDetailsDisplay::setupRosSubscriptions() +{ + // Don't create a node, just use the one from the parent class + auto rviz_node_ = context_->getRosNodeAbstraction().lock()->get_raw_node(); + + remaining_distance_time_sub_ = + rviz_node_->create_subscription( + remaining_distance_time_topic_property_->getTopicStd(), + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + cb_remaining_distance_time(msg); + }); +} + +MissionDetailsDisplay::~MissionDetailsDisplay() +{ + std::lock_guard lock(property_mutex_); + overlay_.reset(); + + remaining_distance_time_sub_.reset(); + remaining_distance_time_display_.reset(); + remaining_distance_time_topic_property_.reset(); +} + +// mark maybe unused +void MissionDetailsDisplay::update(float wall_dt, float ros_dt) +{ + (void)wall_dt; // Mark as unused + (void)ros_dt; // Mark as unused + + if (!overlay_) { + return; + } + autoware::mission_details_overlay_rviz_plugin::ScopedPixelBuffer buffer = overlay_->getBuffer(); + QImage hud = buffer.getQImage(*overlay_); + hud.fill(Qt::transparent); + draw_widget(hud); +} + +void MissionDetailsDisplay::onEnable() +{ + std::lock_guard lock(property_mutex_); + if (overlay_) { + overlay_->show(); + } + setupRosSubscriptions(); +} + +void MissionDetailsDisplay::onDisable() +{ + std::lock_guard lock(property_mutex_); + + remaining_distance_time_sub_.reset(); + + if (overlay_) { + overlay_->hide(); + } +} + +void MissionDetailsDisplay::cb_remaining_distance_time( + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) +{ + std::lock_guard lock(property_mutex_); + + if (remaining_distance_time_display_) { + remaining_distance_time_display_->updateRemainingDistanceTimeData(msg); + queueRender(); + } +} + +void MissionDetailsDisplay::draw_widget(QImage & hud) +{ + std::lock_guard lock(property_mutex_); + + if (!overlay_->isVisible()) { + return; + } + + QPainter painter(&hud); + painter.setRenderHint(QPainter::Antialiasing, true); + + QRectF backgroundRect(0, 0, qreal(property_width_->getInt()), qreal(property_height_->getInt())); + draw_rounded_rect(painter, backgroundRect); + + if (remaining_distance_time_display_) { + remaining_distance_time_display_->drawRemainingDistanceTimeDisplay(painter, backgroundRect); + } + + painter.end(); +} + +void MissionDetailsDisplay::draw_rounded_rect(QPainter & painter, const QRectF & backgroundRect) +{ + painter.setRenderHint(QPainter::Antialiasing, true); + QColor colorFromHSV; + colorFromHSV.setHsv(0, 0, 29); + colorFromHSV.setAlphaF(0.60); + + painter.setBrush(colorFromHSV); + + painter.setPen(Qt::NoPen); + painter.drawRoundedRect(backgroundRect, backgroundRect.height() / 2, backgroundRect.height() / 2); +} + +void MissionDetailsDisplay::reset() +{ + rviz_common::Display::reset(); + overlay_->hide(); +} + +void MissionDetailsDisplay::update_size() +{ + std::lock_guard lock(mutex_); + overlay_->updateTextureSize(property_width_->getInt(), property_height_->getInt()); + overlay_->setDimensions(overlay_->getTextureWidth(), overlay_->getTextureHeight()); + overlay_->setPosition( + property_right_->getInt(), property_top_->getInt(), HorizontalAlignment::RIGHT, + VerticalAlignment::TOP); + queueRender(); +} + +void MissionDetailsDisplay::topic_updated_remaining_distance_time() +{ + // resubscribe to the topic + remaining_distance_time_sub_.reset(); + auto rviz_ros_node = context_->getRosNodeAbstraction().lock(); + remaining_distance_time_sub_ = + rviz_ros_node->get_raw_node() + ->create_subscription( + remaining_distance_time_topic_property_->getTopicStd(), + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable(), + [this](const autoware_internal_msgs::msg::MissionRemainingDistanceTime::SharedPtr msg) { + cb_remaining_distance_time(msg); + }); +} + +} // namespace autoware::mission_details_overlay_rviz_plugin + +#include +PLUGINLIB_EXPORT_CLASS( + autoware::mission_details_overlay_rviz_plugin::MissionDetailsDisplay, rviz_common::Display) diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp new file mode 100644 index 0000000000000..68813a5f1140f --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/overlay_utils.cpp @@ -0,0 +1,267 @@ +// Copyright 2024 The Autoware Contributors +// +// 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. + +// -*- mode: c++ -*- +/********************************************************************* + * Software License Agreement (BSD License) + * + * Copyright (c) 2022, Team Spatzenhirn + * Copyright (c) 2014, JSK Lab + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/o2r other materials provided + * with the distribution. + * * Neither the name of the JSK Lab nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + *********************************************************************/ + +#include "overlay_utils.hpp" + +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ +ScopedPixelBuffer::ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr pixel_buffer) +: pixel_buffer_(pixel_buffer) +{ + pixel_buffer_->lock(Ogre::HardwareBuffer::HBL_NORMAL); +} + +ScopedPixelBuffer::~ScopedPixelBuffer() +{ + pixel_buffer_->unlock(); +} + +Ogre::HardwarePixelBufferSharedPtr ScopedPixelBuffer::getPixelBuffer() +{ + return pixel_buffer_; +} + +QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height) +{ + const Ogre::PixelBox & pixelBox = pixel_buffer_->getCurrentLock(); + Ogre::uint8 * pDest = static_cast(pixelBox.data); + memset(pDest, 0, width * height); + return QImage(pDest, width, height, QImage::Format_ARGB32); +} + +QImage ScopedPixelBuffer::getQImage(unsigned int width, unsigned int height, QColor & bg_color) +{ + QImage Hud = getQImage(width, height); + for (unsigned int i = 0; i < width; i++) { + for (unsigned int j = 0; j < height; j++) { + Hud.setPixel(i, j, bg_color.rgba()); + } + } + return Hud; +} + +QImage ScopedPixelBuffer::getQImage(OverlayObject & overlay) +{ + return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight()); +} + +QImage ScopedPixelBuffer::getQImage(OverlayObject & overlay, QColor & bg_color) +{ + return getQImage(overlay.getTextureWidth(), overlay.getTextureHeight(), bg_color); +} + +OverlayObject::OverlayObject(const std::string & name) : name_(name) +{ + std::string material_name = name_ + "Material"; + Ogre::OverlayManager * mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); + overlay_ = mOverlayMgr->create(name_); + panel_ = static_cast( + mOverlayMgr->createOverlayElement("Panel", name_ + "Panel")); + panel_->setMetricsMode(Ogre::GMM_PIXELS); + + panel_material_ = Ogre::MaterialManager::getSingleton().create( + material_name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); + panel_->setMaterialName(panel_material_->getName()); + overlay_->add2D(panel_); +} + +OverlayObject::~OverlayObject() +{ + Ogre::OverlayManager * mOverlayMgr = Ogre::OverlayManager::getSingletonPtr(); + if (mOverlayMgr) { + mOverlayMgr->destroyOverlayElement(panel_); + mOverlayMgr->destroy(overlay_); + } + if (panel_material_) { + panel_material_->unload(); + Ogre::MaterialManager::getSingleton().remove(panel_material_->getName()); + } +} + +std::string OverlayObject::getName() const +{ + return name_; +} + +void OverlayObject::hide() +{ + if (overlay_->isVisible()) { + overlay_->hide(); + } +} + +void OverlayObject::show() +{ + if (!overlay_->isVisible()) { + overlay_->show(); + } +} + +bool OverlayObject::isTextureReady() const +{ + return texture_ != nullptr; +} + +void OverlayObject::updateTextureSize(unsigned int width, unsigned int height) +{ + const std::string texture_name = name_ + "Texture"; + if (width == 0) { + RVIZ_COMMON_LOG_WARNING_STREAM("[OverlayObject] width=0 is specified as texture size"); + width = 1; + } + + if (height == 0) { + RVIZ_COMMON_LOG_WARNING_STREAM("[OverlayObject] height=0 is specified as texture size"); + height = 1; + } + + if (!isTextureReady() || ((width != texture_->getWidth()) || (height != texture_->getHeight()))) { + if (isTextureReady()) { + Ogre::TextureManager::getSingleton().remove(texture_name); + panel_material_->getTechnique(0)->getPass(0)->removeAllTextureUnitStates(); + } + + texture_ = Ogre::TextureManager::getSingleton().createManual( + texture_name, // name + Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, + Ogre::TEX_TYPE_2D, // type + width, height, // width & height of the render window + 0, // number of mipmaps + Ogre::PF_A8R8G8B8, // pixel format chosen to match a format Qt can use + Ogre::TU_DEFAULT // usage + ); + panel_material_->getTechnique(0)->getPass(0)->createTextureUnitState(texture_name); + + panel_material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA); + } +} + +ScopedPixelBuffer OverlayObject::getBuffer() +{ + if (isTextureReady()) { + return ScopedPixelBuffer(texture_->getBuffer()); + } else { + return ScopedPixelBuffer(Ogre::HardwarePixelBufferSharedPtr()); + } +} + +void OverlayObject::setPosition( + double hor_dist, double ver_dist, HorizontalAlignment hor_alignment, + VerticalAlignment ver_alignment) +{ + // ogre position is always based on the top left corner of the panel, while our position input + // depends on the chosen alignment, i.e. if the horizontal alignment is right, increasing the + // horizontal dist moves the panel to the left (further away from the right border) + double left = 0; + double top = 0; + + switch (hor_alignment) { + case HorizontalAlignment::LEFT: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_LEFT); + left = hor_dist; + break; + case HorizontalAlignment::CENTER: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_CENTER); + left = hor_dist - panel_->getWidth() / 2; + break; + case HorizontalAlignment::RIGHT: + panel_->setHorizontalAlignment(Ogre::GuiHorizontalAlignment::GHA_RIGHT); + left = -hor_dist - panel_->getWidth(); + break; + } + + switch (ver_alignment) { + case VerticalAlignment::BOTTOM: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_BOTTOM); + top = -ver_dist - panel_->getHeight(); + break; + case VerticalAlignment::CENTER: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_CENTER); + top = ver_dist - panel_->getHeight() / 2; + break; + case VerticalAlignment::TOP: + panel_->setVerticalAlignment(Ogre::GuiVerticalAlignment::GVA_TOP); + top = ver_dist; + break; + } + + panel_->setPosition(left, top); +} + +void OverlayObject::setDimensions(double width, double height) +{ + panel_->setDimensions(width, height); +} + +bool OverlayObject::isVisible() const +{ + return overlay_->isVisible(); +} + +unsigned int OverlayObject::getTextureWidth() const +{ + if (isTextureReady()) { + return texture_->getWidth(); + } else { + return 0; + } +} + +unsigned int OverlayObject::getTextureHeight() const +{ + if (isTextureReady()) { + return texture_->getHeight(); + } else { + return 0; + } +} +} // namespace autoware::mission_details_overlay_rviz_plugin diff --git a/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp new file mode 100644 index 0000000000000..86395ef1918bc --- /dev/null +++ b/common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin/src/remaining_distance_time_display.cpp @@ -0,0 +1,157 @@ +// Copyright 2024 The Autoware Contributors +// +// 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. + +#include "remaining_distance_time_display.hpp" + +#include +#include +#include +#include + +#include + +#include +#include +#include +#include + +namespace autoware::mission_details_overlay_rviz_plugin +{ + +RemainingDistanceTimeDisplay::RemainingDistanceTimeDisplay() +: remaining_distance_(0.0), remaining_time_(0.0) +{ + std::string package_path = + ament_index_cpp::get_package_share_directory("autoware_mission_details_overlay_rviz_plugin"); + std::string font_path = package_path + "/assets/font/Quicksand/static/Quicksand-Regular.ttf"; + std::string font_path2 = package_path + "/assets/font/Quicksand/static/Quicksand-Bold.ttf"; + int fontId = QFontDatabase::addApplicationFont( + font_path.c_str()); // returns -1 on failure (see docs for more info) + int fontId2 = QFontDatabase::addApplicationFont( + font_path2.c_str()); // returns -1 on failure (see docs for more info) + if (fontId == -1 || fontId2 == -1) { + std::cout << "Failed to load the Quicksand font."; + } + + std::string dist_image = package_path + "/assets/path.png"; + std::string time_image = package_path + "/assets/av_timer.png"; + icon_dist_.load(dist_image.c_str()); + icon_time_.load(time_image.c_str()); + icon_dist_scaled_ = icon_dist_.scaled(28, 28, Qt::KeepAspectRatio, Qt::SmoothTransformation); + icon_time_scaled_ = icon_time_.scaled(28, 28, Qt::KeepAspectRatio, Qt::SmoothTransformation); +} + +void RemainingDistanceTimeDisplay::updateRemainingDistanceTimeData( + const autoware_internal_msgs::msg::MissionRemainingDistanceTime::ConstSharedPtr & msg) +{ + remaining_distance_ = msg->remaining_distance; + remaining_time_ = msg->remaining_time; +} + +void RemainingDistanceTimeDisplay::drawRemainingDistanceTimeDisplay( + QPainter & painter, const QRectF & backgroundRect) +{ + const QFont font("Quicksand", 15, QFont::Bold); + painter.setFont(font); + + // We'll display the distance and time in two rows + + auto calculate_inner_rect = [](const QRectF & outer_rect, double ratio_x, double ratio_y) { + QSizeF size_inner(outer_rect.width() * ratio_x, outer_rect.height() * ratio_y); + QPointF top_left_inner = QPointF( + outer_rect.center().x() - size_inner.width() / 2, + outer_rect.center().y() - size_inner.height() / 2); + return QRectF(top_left_inner, size_inner); + }; + + QRectF rect_inner = calculate_inner_rect(backgroundRect, 0.7, 0.7); + // Proportionally extend the rect to the right to account for visual icon distance to the left + rect_inner.setWidth(rect_inner.width() * 1.08); + + // Calculate distance row rectangle + const QSizeF distance_row_size(rect_inner.width(), rect_inner.height() / 2); + const QPointF distance_row_top_left(rect_inner.topLeft()); + const QRectF distance_row_rect_outer(distance_row_top_left, distance_row_size); + + // Calculate time row rectangle + const QSizeF time_row_size(rect_inner.width(), rect_inner.height() / 2); + const QPointF time_row_top_left( + rect_inner.topLeft().x(), rect_inner.topLeft().y() + rect_inner.height() / 2); + const QRectF time_row_rect_outer(time_row_top_left, time_row_size); + + const auto rect_time = calculate_inner_rect(time_row_rect_outer, 1.0, 0.9); + const auto rect_dist = calculate_inner_rect(distance_row_rect_outer, 1.0, 0.9); + + auto place_row = [&, this]( + const QRectF & rect, const QImage & icon, const QString & str_value, + const QString & str_unit) { + // order: icon, value, unit + + // place the icon + QPointF icon_top_left(rect.topLeft().x(), rect.center().y() - icon.height() / 2.0); + painter.drawImage(icon_top_left, icon); + + // place the unit text + const float unit_width = 40.0; + QRectF rect_text_unit( + rect.topRight().x() - unit_width, rect.topRight().y(), unit_width, rect.height()); + + painter.setPen(gray); + painter.drawText(rect_text_unit, Qt::AlignLeft | Qt::AlignVCenter, str_unit); + + // place the value text + const double margin_x = 5.0; // margin around the text + + const double used_width = icon.width() + rect_text_unit.width() + margin_x * 2.0; + + QRectF rect_text( + rect.topLeft().x() + icon.width() + margin_x, rect.topLeft().y(), rect.width() - used_width, + rect.height()); + + painter.drawText(rect_text, Qt::AlignRight | Qt::AlignVCenter, str_value); + }; + + // remaining_time_ is in seconds + if (remaining_time_ <= 60) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_, 'f', 0), "sec"); + } else if (remaining_time_ <= 600) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_ / 60.0, 'f', 1), "min"); + } else if (remaining_time_ <= 3600) { + place_row(rect_time, icon_time_scaled_, QString::number(remaining_time_ / 60.0, 'f', 0), "min"); + } else if (remaining_time_ <= 36000) { + place_row( + rect_time, icon_time_scaled_, QString::number(remaining_time_ / 3600.0, 'f', 1), "hrs"); + } else { + place_row( + rect_time, icon_time_scaled_, QString::number(remaining_time_ / 3600.0, 'f', 0), "hrs"); + } + + // remaining_distance_ is in meters + if (remaining_distance_ <= 10) { + place_row(rect_dist, icon_dist_scaled_, QString::number(remaining_distance_, 'f', 1), "m"); + } else if (remaining_distance_ <= 1000) { + place_row(rect_dist, icon_dist_scaled_, QString::number(remaining_distance_, 'f', 0), "m"); + } else if (remaining_distance_ <= 10000) { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 2), "km"); + } else if (remaining_distance_ <= 100000) { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 1), "km"); + } else { + place_row( + rect_dist, icon_dist_scaled_, QString::number(remaining_distance_ / 1000.0, 'f', 0), "km"); + } +} + +} // namespace autoware::mission_details_overlay_rviz_plugin diff --git a/launch/tier4_planning_launch/launch/planning.launch.xml b/launch/tier4_planning_launch/launch/planning.launch.xml index 710fb20631a45..0e693943a4d03 100644 --- a/launch/tier4_planning_launch/launch/planning.launch.xml +++ b/launch/tier4_planning_launch/launch/planning.launch.xml @@ -43,5 +43,10 @@ + + + + + diff --git a/launch/tier4_planning_launch/package.xml b/launch/tier4_planning_launch/package.xml index 950ef67865a85..d04a405a61c7b 100644 --- a/launch/tier4_planning_launch/package.xml +++ b/launch/tier4_planning_launch/package.xml @@ -57,6 +57,7 @@ ament_cmake_auto autoware_cmake + autoware_remaining_distance_time_calculator behavior_path_planner behavior_velocity_planner costmap_generator diff --git a/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt new file mode 100644 index 0000000000000..d29a153a0ce5d --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/CMakeLists.txt @@ -0,0 +1,21 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_remaining_distance_time_calculator) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + src/remaining_distance_time_calculator_node.cpp +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode" + EXECUTABLE ${PROJECT_NAME}_node +) + + +ament_auto_package( + INSTALL_TO_SHARE + config + launch +) diff --git a/planning/autoware_remaining_distance_time_calculator/README.md b/planning/autoware_remaining_distance_time_calculator/README.md new file mode 100644 index 0000000000000..694c6764de91c --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/README.md @@ -0,0 +1,39 @@ +## Remaining Distance and Time Calculator + +### Role + +This package aims to provide mission remaining distance and remaining time calculations. + +### Activation and Timing + +- The calculations are activated once we have a route planned for a mission in Autoware. +- The calculations are triggered timely based on the `update_rate` parameter. + +### Module Parameters + +| Name | Type | Default Value | Explanation | +| ------------- | ------ | ------------- | --------------------------- | +| `update_rate` | double | 10.0 | Timer callback period. [Hz] | + +### Inner-workings + +#### Remaining Distance Calculation + +- The remaining distance calculation is based on getting the remaining shortest path between the current vehicle pose and goal pose using `lanelet2` routing APIs. +- The remaining distance is calculated by summing the 2D length of remaining shortest path, with exception to current lanelet and goal lanelet. + - For the current lanelet, the distance is calculated from the current vehicle position to the end of that lanelet. + - For the goal lanelet, the distance is calculated from the start of the lanelet to the goal pose in this lanelet. +- When there is only one lanelet remaining, the distance is calculated by getting the 2D distance between the current vehicle pose and goal pose. +- Checks are added to handle cases when current lanelet, goal lanelet, or routing graph are not valid to prevent node process die. + - In such cases when, last valid remaining distance and time are maintained. + +#### Remaining Time Calculation + +- The remaining time currently depends on a simple equation of motion by getting the maximum velocity limit. +- The remaining distance is calculated by dividing the remaining distance by the maximum velocity limit. +- A check is added to the remaining time calculation to make sure that maximum velocity limit is greater than zero. This prevents division by zero or getting negative time value. + +### Future Work + +- Find a more efficient way for remaining distance calculation instead of regularly searching the graph for finding the remaining shortest path. +- Engage more sophisticated motion models for more accurate remaining time calculations. diff --git a/planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml b/planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml new file mode 100644 index 0000000000000..5b8c019de5a20 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/config/remaining_distance_time_calculator.param.yaml @@ -0,0 +1,3 @@ +/**: + ros__parameters: + update_rate: 10.0 diff --git a/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml new file mode 100644 index 0000000000000..cfb456c57ca41 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/launch/remaining_distance_time_calculator.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/planning/autoware_remaining_distance_time_calculator/package.xml b/planning/autoware_remaining_distance_time_calculator/package.xml new file mode 100644 index 0000000000000..4f0324b23f299 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/package.xml @@ -0,0 +1,35 @@ + + + autoware_remaining_distance_time_calculator + 0.1.0 + Calculates and publishes remaining distance and time of the mission. + + Ahmed Ebrahim + + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_internal_msgs + autoware_planning_msgs + geometry_msgs + lanelet2_extension + motion_utils + nav_msgs + planning_test_utils + rclcpp + rclcpp_components + route_handler + std_msgs + tier4_autoware_utils + tier4_planning_msgs + + ament_cmake_ros + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json b/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json new file mode 100644 index 0000000000000..4b3bc15432d0d --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/schema/remaining_distance_time_calculator.schema.json @@ -0,0 +1,31 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Remaining Distance Time Calculator Parameters", + "type": "object", + "actual_parameters": { + "type": "object", + "properties": { + "update_rate": { + "type": "number", + "default": 10.0, + "description": "Recalculate remaining distance and time at this rate, Hz" + } + }, + "required": ["update_rate"], + "additionalProperties": false + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/actual_parameters" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp new file mode 100644 index 0000000000000..327bd0ff3b582 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.cpp @@ -0,0 +1,188 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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. + +#include "remaining_distance_time_calculator_node.hpp" + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include + +namespace autoware::remaining_distance_time_calculator +{ + +RemainingDistanceTimeCalculatorNode::RemainingDistanceTimeCalculatorNode( + const rclcpp::NodeOptions & options) +: Node("remaining_distance_time_calculator", options), + is_graph_ready_{false}, + has_received_route_{false}, + velocity_limit_{99.99}, + remaining_distance_{0.0}, + remaining_time_{0.0} +{ + using std::placeholders::_1; + + sub_odometry_ = create_subscription( + "~/input/odometry", 1, std::bind(&RemainingDistanceTimeCalculatorNode::on_odometry, this, _1)); + + const auto qos_transient_local = rclcpp::QoS{1}.transient_local(); + + sub_map_ = create_subscription( + "~/input/map", qos_transient_local, + std::bind(&RemainingDistanceTimeCalculatorNode::on_map, this, _1)); + sub_route_ = create_subscription( + "~/input/route", qos_transient_local, + std::bind(&RemainingDistanceTimeCalculatorNode::on_route, this, _1)); + sub_planning_velocity_ = create_subscription( + "/planning/scenario_planning/current_max_velocity", qos_transient_local, + std::bind(&RemainingDistanceTimeCalculatorNode::on_velocity_limit, this, _1)); + + pub_mission_remaining_distance_time_ = create_publisher( + "~/output/mission_remaining_distance_time", + rclcpp::QoS(rclcpp::KeepLast(10)).durability_volatile().reliable()); + + node_param_.update_rate = declare_parameter("update_rate"); + + const auto period_ns = rclcpp::Rate(node_param_.update_rate).period(); + timer_ = rclcpp::create_timer( + this, get_clock(), period_ns, std::bind(&RemainingDistanceTimeCalculatorNode::on_timer, this)); +} + +void RemainingDistanceTimeCalculatorNode::on_map(const HADMapBin::ConstSharedPtr & msg) +{ + route_handler_.setMap(*msg); + lanelet_map_ptr_ = std::make_shared(); + lanelet::utils::conversion::fromBinMsg( + *msg, lanelet_map_ptr_, &traffic_rules_ptr_, &routing_graph_ptr_); + lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_); + road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets); + is_graph_ready_ = true; +} + +void RemainingDistanceTimeCalculatorNode::on_odometry(const Odometry::ConstSharedPtr & msg) +{ + current_vehicle_pose_ = msg->pose.pose; + current_vehicle_velocity_ = msg->twist.twist.linear; +} + +void RemainingDistanceTimeCalculatorNode::on_route(const LaneletRoute::ConstSharedPtr & msg) +{ + goal_pose_ = msg->goal_pose; + has_received_route_ = true; +} + +void RemainingDistanceTimeCalculatorNode::on_velocity_limit( + const VelocityLimit::ConstSharedPtr & msg) +{ + if (msg->max_velocity > 1e-5) { + velocity_limit_ = msg->max_velocity; + } +} + +void RemainingDistanceTimeCalculatorNode::on_timer() +{ + if (is_graph_ready_ && has_received_route_) { + calculate_remaining_distance(); + calculate_remaining_time(); + publish_mission_remaining_distance_time(); + } +} + +void RemainingDistanceTimeCalculatorNode::calculate_remaining_distance() +{ + size_t index = 0; + + lanelet::ConstLanelet current_lanelet; + if (!lanelet::utils::query::getClosestLanelet( + road_lanelets_, current_vehicle_pose_, ¤t_lanelet)) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find current lanelet."); + + return; + } + + lanelet::ConstLanelet goal_lanelet; + if (!lanelet::utils::query::getClosestLanelet(road_lanelets_, goal_pose_, &goal_lanelet)) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find goal lanelet."); + + return; + } + + const lanelet::Optional optional_route = + routing_graph_ptr_->getRoute(current_lanelet, goal_lanelet, 0); + if (!optional_route) { + RCLCPP_WARN_STREAM(this->get_logger(), "Failed to find proper route."); + + return; + } + + lanelet::routing::LaneletPath remaining_shortest_path; + remaining_shortest_path = optional_route->shortestPath(); + + remaining_distance_ = 0.0; + + for (auto & llt : remaining_shortest_path) { + if (remaining_shortest_path.size() == 1) { + remaining_distance_ += + tier4_autoware_utils::calcDistance2d(current_vehicle_pose_.position, goal_pose_.position); + break; + } + + if (index == 0) { + lanelet::ArcCoordinates arc_coord = + lanelet::utils::getArcCoordinates({llt}, current_vehicle_pose_); + double this_lanelet_length = lanelet::utils::getLaneletLength2d(llt); + + remaining_distance_ += this_lanelet_length - arc_coord.length; + } else if (index == (remaining_shortest_path.size() - 1)) { + lanelet::ArcCoordinates arc_coord = lanelet::utils::getArcCoordinates({llt}, goal_pose_); + remaining_distance_ += arc_coord.length; + } else { + remaining_distance_ += lanelet::utils::getLaneletLength2d(llt); + } + + index++; + } +} + +void RemainingDistanceTimeCalculatorNode::calculate_remaining_time() +{ + if (velocity_limit_ > 0.0) { + remaining_time_ = remaining_distance_ / velocity_limit_; + } +} + +void RemainingDistanceTimeCalculatorNode::publish_mission_remaining_distance_time() +{ + MissionRemainingDistanceTime mission_remaining_distance_time; + + mission_remaining_distance_time.remaining_distance = remaining_distance_; + mission_remaining_distance_time.remaining_time = remaining_time_; + pub_mission_remaining_distance_time_->publish(mission_remaining_distance_time); +} + +} // namespace autoware::remaining_distance_time_calculator + +#include +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::remaining_distance_time_calculator::RemainingDistanceTimeCalculatorNode) diff --git a/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp new file mode 100644 index 0000000000000..2a88cdb57abf4 --- /dev/null +++ b/planning/autoware_remaining_distance_time_calculator/src/remaining_distance_time_calculator_node.hpp @@ -0,0 +1,110 @@ +// Copyright 2022 TIER IV, Inc. +// +// 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. + +#ifndef REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ +#define REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_ + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +namespace autoware::remaining_distance_time_calculator +{ + +struct NodeParam +{ + double update_rate{0.0}; +}; + +class RemainingDistanceTimeCalculatorNode : public rclcpp::Node +{ +public: + explicit RemainingDistanceTimeCalculatorNode(const rclcpp::NodeOptions & options); + +private: + using LaneletRoute = autoware_planning_msgs::msg::LaneletRoute; + using HADMapBin = autoware_auto_mapping_msgs::msg::HADMapBin; + using Odometry = nav_msgs::msg::Odometry; + using VelocityLimit = tier4_planning_msgs::msg::VelocityLimit; + using MissionRemainingDistanceTime = autoware_internal_msgs::msg::MissionRemainingDistanceTime; + + rclcpp::Subscription::SharedPtr sub_route_; + rclcpp::Subscription::SharedPtr sub_map_; + rclcpp::Subscription::SharedPtr sub_odometry_; + rclcpp::Subscription::SharedPtr sub_planning_velocity_; + + rclcpp::Publisher::SharedPtr pub_mission_remaining_distance_time_; + + rclcpp::TimerBase::SharedPtr timer_; + + route_handler::RouteHandler route_handler_; + lanelet::LaneletMapPtr lanelet_map_ptr_; + lanelet::routing::RoutingGraphPtr routing_graph_ptr_; + lanelet::traffic_rules::TrafficRulesPtr traffic_rules_ptr_; + lanelet::ConstLanelets road_lanelets_; + bool is_graph_ready_; + + // Data Buffer + geometry_msgs::msg::Pose current_vehicle_pose_; + geometry_msgs::msg::Vector3 current_vehicle_velocity_; + geometry_msgs::msg::Pose goal_pose_; + bool has_received_route_; + double velocity_limit_; + + double remaining_distance_; + double remaining_time_; + + // Parameter + NodeParam node_param_; + + // Callbacks + void on_timer(); + void on_odometry(const Odometry::ConstSharedPtr & msg); + void on_route(const LaneletRoute::ConstSharedPtr & msg); + void on_map(const HADMapBin::ConstSharedPtr & msg); + void on_velocity_limit(const VelocityLimit::ConstSharedPtr & msg); + + /** + * @brief calculate mission remaining distance + */ + void calculate_remaining_distance(); + + /** + * @brief calculate mission remaining time + */ + void calculate_remaining_time(); + + /** + * @brief publish mission remaining distance and time + */ + void publish_mission_remaining_distance_time(); +}; +} // namespace autoware::remaining_distance_time_calculator +#endif // REMAINING_DISTANCE_TIME_CALCULATOR_NODE_HPP_