From 61b0fd62c9a255af8469e10423b732a562da1635 Mon Sep 17 00:00:00 2001 From: Scott K Logan Date: Mon, 13 Jan 2025 13:00:07 -0600 Subject: [PATCH 01/29] Drop unsupported Python packages from instructions (#4914) We no longer use or require the following Python packages: - flake8-docstrings - pep8 - pydocstyle --- source/Installation/Alternatives/RHEL-Development-Setup.rst | 1 - source/Installation/Alternatives/RHEL-Install-Binary.rst | 1 - .../Installation/Alternatives/Windows-Development-Setup.rst | 2 +- source/Installation/Alternatives/macOS-Development-Setup.rst | 4 ++-- source/Installation/RHEL-Install-RPMs.rst | 1 - 5 files changed, 3 insertions(+), 6 deletions(-) diff --git a/source/Installation/Alternatives/RHEL-Development-Setup.rst b/source/Installation/Alternatives/RHEL-Development-Setup.rst index 57d77d39168..e14c3898cac 100644 --- a/source/Installation/Alternatives/RHEL-Development-Setup.rst +++ b/source/Installation/Alternatives/RHEL-Development-Setup.rst @@ -64,7 +64,6 @@ Install development tools python3-colcon-common-extensions \ python3-mypy \ python3-pip \ - python3-pydocstyle \ python3-pytest \ python3-pytest-cov \ python3-pytest-mock \ diff --git a/source/Installation/Alternatives/RHEL-Install-Binary.rst b/source/Installation/Alternatives/RHEL-Install-Binary.rst index 5a64eb58073..e53e09c70de 100644 --- a/source/Installation/Alternatives/RHEL-Install-Binary.rst +++ b/source/Installation/Alternatives/RHEL-Install-Binary.rst @@ -68,7 +68,6 @@ If you are going to build ROS packages or otherwise do development, you can also python3-colcon-common-extensions \ python3-mypy \ python3-pip \ - python3-pydocstyle \ python3-pytest \ python3-pytest-repeat \ python3-pytest-rerunfailures \ diff --git a/source/Installation/Alternatives/Windows-Development-Setup.rst b/source/Installation/Alternatives/Windows-Development-Setup.rst index 06e96b2c5bd..2670766a14f 100644 --- a/source/Installation/Alternatives/Windows-Development-Setup.rst +++ b/source/Installation/Alternatives/Windows-Development-Setup.rst @@ -41,7 +41,7 @@ Install additional Python dependencies: .. code-block:: bash - pip install -U colcon-common-extensions coverage flake8 flake8-blind-except flake8-builtins flake8-class-newline flake8-comprehensions flake8-deprecated flake8-docstrings flake8-import-order flake8-quotes mock mypy==0.931 pep8 pydocstyle pytest pytest-cov pytest-mock pytest-repeat pytest-rerunfailures pytest-runner vcstool + pip install -U colcon-common-extensions coverage flake8 flake8-blind-except flake8-builtins flake8-class-newline flake8-comprehensions flake8-deprecated flake8-import-order flake8-quotes mock mypy==0.931 pytest pytest-cov pytest-mock pytest-repeat pytest-rerunfailures pytest-runner vcstool Build ROS 2 ----------- diff --git a/source/Installation/Alternatives/macOS-Development-Setup.rst b/source/Installation/Alternatives/macOS-Development-Setup.rst index 4ee35a41786..631e9b81aaf 100644 --- a/source/Installation/Alternatives/macOS-Development-Setup.rst +++ b/source/Installation/Alternatives/macOS-Development-Setup.rst @@ -92,9 +92,9 @@ You need the following things installed to build ROS 2: argcomplete catkin_pkg colcon-common-extensions coverage \ cryptography empy flake8 flake8-blind-except==0.1.1 flake8-builtins \ flake8-class-newline flake8-comprehensions flake8-deprecated \ - flake8-docstrings flake8-import-order flake8-quotes \ + flake8-import-order flake8-quotes \ importlib-metadata jsonschema lark==1.1.1 lxml matplotlib mock mypy==0.931 netifaces \ - nose pep8 psutil pydocstyle pydot pygraphviz pyparsing==2.4.7 \ + psutil pydot pygraphviz pyparsing==2.4.7 \ pytest-mock rosdep rosdistro setuptools==59.6.0 vcstool Please ensure that the ``$PATH`` environment variable contains the install location of the binaries (``$(brew --prefix)/bin``) diff --git a/source/Installation/RHEL-Install-RPMs.rst b/source/Installation/RHEL-Install-RPMs.rst index 3f36192bd24..80b1f00e1db 100644 --- a/source/Installation/RHEL-Install-RPMs.rst +++ b/source/Installation/RHEL-Install-RPMs.rst @@ -69,7 +69,6 @@ If you are going to build ROS packages or otherwise do development, you can also python3-colcon-common-extensions \ python3-mypy \ python3-pip \ - python3-pydocstyle \ python3-pytest \ python3-pytest-repeat \ python3-pytest-rerunfailures \ From 783b7f65ee266c34a339f1a18ac08dd6672731cd Mon Sep 17 00:00:00 2001 From: "David V. Lu!!" Date: Mon, 13 Jan 2025 14:01:28 -0500 Subject: [PATCH 02/29] Rviz Panel Tutorial (#4869) Signed-off-by: David V. Lu!! Signed-off-by: Katherine Scott Co-authored-by: Katherine Scott --- .../RViz-Custom-Panel/RViz-Custom-Panel.rst | 351 ++++++++++++++++++ .../RViz/RViz-Custom-Panel/images/RViz0.png | Bin 0 -> 136047 bytes .../RViz/RViz-Custom-Panel/images/RViz1.png | Bin 0 -> 5818 bytes .../RViz/RViz-Custom-Panel/images/RViz2.png | Bin 0 -> 6344 bytes .../RViz/RViz-Custom-Panel/images/RViz3.png | Bin 0 -> 6113 bytes .../RViz/RViz-Custom-Panel/images/Select0.png | Bin 0 -> 32255 bytes .../RViz/RViz-Custom-Panel/images/Select1.png | Bin 0 -> 38305 bytes .../Tutorials/Intermediate/RViz/RViz-Main.rst | 1 + 8 files changed, 352 insertions(+) create mode 100644 source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/RViz-Custom-Panel.rst create mode 100644 source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz0.png create mode 100644 source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz1.png create mode 100644 source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz2.png create mode 100644 source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz3.png create mode 100644 source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/Select0.png create mode 100644 source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/Select1.png diff --git a/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/RViz-Custom-Panel.rst b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/RViz-Custom-Panel.rst new file mode 100644 index 00000000000..1f03660ea1b --- /dev/null +++ b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/RViz-Custom-Panel.rst @@ -0,0 +1,351 @@ +Building a Custom RViz Panel +============================ + +This tutorial is for people who would like to work within the RViz environment to either display or interact with some data in a two-dimensional environment. + +In this tutorial you will learn how to do three things within RViz: + +* Create a new QT panel within RViz. +* Create a topic subscriber within RViz that can monitor messages published on that topic and display them within the RViz panel. +* Create a topic publisher such button presses within RViz publish to an output topic in ROS. + +All of the code for this tutorial can be found in `this repository `__. + +Boilerplate Code +---------------- + +Header File +^^^^^^^^^^^ + +Here are the contents of ``demo_panel.hpp`` + +.. code-block:: c++ + + #ifndef RVIZ_PANEL_TUTORIAL__DEMO_PANEL_HPP_ + #define RVIZ_PANEL_TUTORIAL__DEMO_PANEL_HPP_ + + #include + + namespace rviz_panel_tutorial + { + class DemoPanel + : public rviz_common::Panel + { + Q_OBJECT + public: + explicit DemoPanel(QWidget * parent = 0); + ~DemoPanel() override; + }; + } // namespace rviz_panel_tutorial + + #endif // RVIZ_PANEL_TUTORIAL__DEMO_PANEL_HPP_ + +* We're extending the `rviz_common::Panel `__ class. +* `For reasons outside the scope of this tutorial `__, you need the ``Q_OBJECT`` macro in there to get the QT parts of the GUI to work. +* We start by declaring just a constructor and destructor, implemented in the cpp file. + +Source File +^^^^^^^^^^^ + +``demo_panel.cpp`` + +.. code-block:: c++ + + #include + + namespace rviz_panel_tutorial + { + DemoPanel::DemoPanel(QWidget* parent) : Panel(parent) + { + } + + DemoPanel::~DemoPanel() = default; + } // namespace rviz_panel_tutorial + + #include + PLUGINLIB_EXPORT_CLASS(rviz_panel_tutorial::DemoPanel, rviz_common::Panel) + +* Overriding the constructor and deconstructor are not strictly necessary, but we can do more with them later. +* In order for RViz to find our plugin, we need this ``PLUGINLIB`` invocation in our code (as well as other things below). + +package.xml +^^^^^^^^^^^ + +We need the following dependencies in our package.xml: + +.. code-block:: xml + + pluginlib + rviz_common + +rviz_common_plugins.xml +^^^^^^^^^^^^^^^^^^^^^^^ + +.. code-block:: xml + + + + + + + +* This is standard ``pluginlib`` code. + + * The library ``path`` is the name of the library we'll assign in the CMake. + * The class should match the ``PLUGINLIB`` invocation from above. + +* We'll come back to the description later, I promise. + +CMakeLists.txt +^^^^^^^^^^^^^^ + +Add the following lines to the top of the standard boilerplate. + +.. code-block:: cmake + + find_package(ament_cmake_ros REQUIRED) + find_package(pluginlib REQUIRED) + find_package(rviz_common REQUIRED) + + set(CMAKE_AUTOMOC ON) + qt5_wrap_cpp(MOC_FILES + include/rviz_panel_tutorial/demo_panel.hpp + ) + + add_library(demo_panel src/demo_panel.cpp ${MOC_FILES}) + target_include_directories(demo_panel PUBLIC + $ + $ + ) + ament_target_dependencies(demo_panel + pluginlib + rviz_common + ) + install(TARGETS demo_panel + EXPORT export_rviz_panel_tutorial + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin + ) + install(DIRECTORY include/ + DESTINATION include + ) + install(FILES rviz_common_plugins.xml + DESTINATION share/${PROJECT_NAME} + ) + ament_export_include_directories(include) + ament_export_targets(export_rviz_panel_tutorial) + pluginlib_export_plugin_description_file(rviz_common rviz_common_plugins.xml) + + +* To generate the proper Qt files, we need to + + * Turn ``CMAKE_AUTOMOC`` on. + * Wrap the headers by calling ``qt5_wrap_cpp`` with each header that has ``Q_OBJECT`` in it. + * Include the ``MOC_FILES`` in the library alongside our other cpp files. + +* A lot of the other code ensures that the plugin portion works. + Namely, calling ``pluginlib_export_plugin_description_file`` is essential to getting RViz to find your new plugin. + +Testing it out +^^^^^^^^^^^^^^ + +Compile your code, source your workspace and run ``rviz2``. + +In the top Menu bar, there should be a "Panels" menu. +Select "Add New Panel" from that menu. + +.. image:: images/Select0.png + :target: images/Select0.png + :alt: screenshot of Add New Panel dialog + +A dialog will pop up showing all the panels accessible in your ROS environment, grouped into folders based on their ROS package. +Create a new instance of your panel by either double clicking on its name, or selecting it and clicking OK. + +This should create a new panel in your RViz window, albeit with nothing but a title bar with the name of your panel. + +.. image:: images/RViz0.png + :target: images/RViz0.png + :alt: screenshot of the whole RViz window showing the new simple panel + +Filling in the Panel +-------------------- +We're going to update our panel with some very basic ROS/QT interaction. +What we will do, roughly, is access the ROS node from within RViz that can both subscribe and publish to ROS topics. +We will use our subscriber to monitor an ``/input`` topic within ROS and display the published ``String`` values in the widget. +We use our publisher to map button presses within RViz to messages published on a ROS topic named ``/output`` . + +Updated Header File +^^^^^^^^^^^^^^^^^^^ + +Update ``demo_panel.hpp`` to include the following includes and class Body. + +.. code-block:: c++ + + #include + #include + #include + #include + #include + + namespace rviz_panel_tutorial + { + class DemoPanel : public rviz_common::Panel + { + Q_OBJECT + public: + explicit DemoPanel(QWidget * parent = 0); + ~DemoPanel() override; + + void onInitialize() override; + + protected: + std::shared_ptr node_ptr_; + rclcpp::Publisher::SharedPtr publisher_; + rclcpp::Subscription::SharedPtr subscription_; + + void topicCallback(const std_msgs::msg::String & msg); + + QLabel* label_; + QPushButton* button_; + + private Q_SLOTS: + void buttonActivated(); + }; + } // namespace rviz_panel_tutorial + +* On the ROS side, we declare an abstract node pointer, which we will use to create interfaces to the wider ROS ecosystem. + We have a subscriber which will allow us to take information from ROS and use it in RViz. + The publisher allows us to publish information/events from within RViz and make them available in ROS. + We also have methods an initialization method for setting up the ROS components (``onInitialize``) and a callback for the subscriber (``topicCallback``). +* On the QT side, we declare a label and a button, as well as a callback for the button (``buttonActivated``). + +Updated Source File +^^^^^^^^^^^^^^^^^^^ + +Update ``demo_panel.cpp`` to have the following contents: + +.. code-block:: c++ + + #include + #include + #include + + namespace rviz_panel_tutorial + { + + DemoPanel::DemoPanel(QWidget* parent) : Panel(parent) + { + // Create a label and a button, displayed vertically (the V in VBox means vertical) + const auto layout = new QVBoxLayout(this); + // Create a button and a label for the button + label_ = new QLabel("[no data]"); + button_ = new QPushButton("GO!"); + // Add those elements to the GUI layout + layout->addWidget(label_); + layout->addWidget(button_); + + // Connect the event of when the button is released to our callback, + // so pressing the button results in the buttonActivated callback being called. + QObject::connect(button_, &QPushButton::released, this, &DemoPanel::buttonActivated); + } + + DemoPanel::~DemoPanel() = default; + + void DemoPanel::onInitialize() + { + // Access the abstract ROS Node and + // in the process lock it for exclusive use until the method is done. + node_ptr_ = getDisplayContext()->getRosNodeAbstraction().lock(); + + // Get a pointer to the familiar rclcpp::Node for making subscriptions/publishers + // (as per normal rclcpp code) + rclcpp::Node::SharedPtr node = node_ptr_->get_raw_node(); + + // Create a String publisher for the output + publisher_ = node->create_publisher("/output", 10); + + // Create a String subscription and bind it to the topicCallback inside this class. + subscription_ = node->create_subscription("/input", 10, std::bind(&DemoPanel::topicCallback, this, std::placeholders::_1)); + } + + // When the subscriber gets a message, this callback is triggered, + // and then we copy its data into the widget's label + void DemoPanel::topicCallback(const std_msgs::msg::String & msg) + { + label_->setText(QString(msg.data.c_str())); + } + + // When the widget's button is pressed, this callback is triggered, + // and then we publish a new message on our topic. + void DemoPanel::buttonActivated() + { + auto message = std_msgs::msg::String(); + message.data = "Button clicked!"; + publisher_->publish(message); + } + + } // namespace rviz_panel_tutorial + + #include + + PLUGINLIB_EXPORT_CLASS(rviz_panel_tutorial::DemoPanel, rviz_common::Panel) + +Testing with ROS +^^^^^^^^^^^^^^^^ +Compile and launch RViz2 with your panel again. You should see your label and button in the panel now. + +.. image:: images/RViz1.png + :target: images/RViz1.png + :alt: screenshot of the RViz panel in its default state + +To change the label, we simply have to publish a message on the ``/input`` topic, which you can do with this command: + +.. code-block:: bash + + ros2 topic pub /input std_msgs/msg/String "{data: 'Please be kind.'}" + +Since the widget is subscribed to this topic, it will trigger the callback and change the text of the label. + +.. image:: images/RViz2.png + :target: images/RViz2.png + :alt: screenshot of the RViz panel with custom string message displayed + + +Pressing the button will publish a message, which you can see by echoing the ``/output`` topic, like with this command. + +.. code-block:: bash + + ros2 topic echo /output + + +Cleanup +------- + +Now its time to clean it up a bit. +This makes things look nicer and be a little easier to use, but aren't strictly required. + +First, you should update the description of your plugin in ``rviz_common_plugins.xml`` + +We also add an icon for the plugin at ``icons/classes/DemoPanel.png``. +The folder is hardcoded, and the filename should match the name from the plugin declaration (or the name of the class if not specified). + +We need to install the image file in the CMake. + +.. code-block:: cmake + + install(FILES icons/classes/DemoPanel.png + DESTINATION share/${PROJECT_NAME}/icons/classes + ) + +Now when you add the panel, it should show up with an icon and description. + +.. image:: images/Select1.png + :target: images/Select1.png + :alt: screenshot of Add New Panel dialog with our custom icon and description + +The panel will also have an updated icon. + +.. image:: images/RViz3.png + :target: images/RViz3.png + :alt: screenshot of the RViz panel with custom icon diff --git a/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz0.png b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz0.png new file mode 100644 index 0000000000000000000000000000000000000000..ca1d8f5cb5ff3d1f01a4a7dff31c2091704572a7 GIT binary patch literal 136047 zcmeFYWmKI@5;lsvySoN=cMGmTf^J~r?oMzG1W0iA0Kql5LvRc3?(VWL$;ml0bMNHQepQnmHw~ zw>^uSonQN`w|rePX{nz3c5MR%-BB#%xgF#@EOM75UQSb}<~%fi!BRixvny3M*6s)5 zCp=w!w4ZxaI&IJ3p`LRv^i{%yq{NmWTD`*qO@8e6)!}3vk3yX(6^$z^X>002n zJsb;UpkE$*2I|tYZqs;(k0H-X-&s9W*waqYSbM0HOktlP%LC4ru~O0r0+!k2tcl1M zSJ}JuttY-0ua(BD&7iZCRsRgWpR)|0XP;AML7eBaHoq~Q>m{z5ND_|n(F&>7Bo9N! zj0<(hcR`l(IDVKCpC700zM5WBVJBu#U9P!0XEwz~*)^TSEZ*`i_w?*FoQL49D3hKH z5=7ej!Su2m^b;F~uOoaR8za2Id+Nt=FS2z@70?ClY&T8|z&I~mH24p%wyqQPF7n;S zk2lk{tqjd4=M3z#B%!0b8z?ExcAjQsfv{#pp%PlkFf4i91SO)kUdY5615osmdD}Yj z%4WeD!@pwoso+nbbK%AhjpCd}IrCOyWXJ4deIk|YDA>Z4e!vr_;nu)Vcb0d&Rm&1A zLf!@Epa35Z5w|I355zX1@RuvwQc))F{j8=$Ju|H~M&6(9G)j$#KF6j4#~Aye zO$|$X7leqW0dQtUbJZ?EPT-{WlDYY${*in}iIq0f<$}H_)9r!Qs-p5`d)Hoaq&0WP zKHmj!FZr>ipe4*9Fd;t~oz*^1MRD5Yn$$Unrvh;tSffyh#yAzEY9i~z>OHC2{J-d%07UOEXz7MPx$ijLm7Op zyv_<3oQ<5{OeD>e5;JA8BM7660j9aqS-nr}>RiAc?mXcwqLJYS zy1&O*>E9SlcHHG}tbhCtciNHSS$IZZ`AK8*h=Q}EzrqR*@a^2?@i0)^yrNk-%~1uh zv+nRHx+Y>wX&n>Uxx2~@W+uzX2Ew{O`v8NT(hfBDt_{|7&Lpid#>$abIJp6~LP!Wy z+3!AAva{7~tOqR^J-t!?AiJ(~-m~Phqa8Jz?d6uO7WB9(L~Lo{Ia~*LvG2u zJU>J@3BUZ&uV2tQOI4mX6ZmZ#UQk7xS+fBp$59}zCvrGT%MWk)AT@Df11~19!8oSA zKi>->$&`?8Qf+jFc4HI)*IYo>q>leH!{ibxSmyD(b=`PQECEnO7yfLian?!X#zEN6Csv}x^+CBa z9n~-G@c|O^Lcm2E!cfG0qRHkh>0u|?Y+NK*-|af3VVtzbN%QSO}e~@u8!=O8iQN4OrJiU&7p0QM=aY#~4RN zP9v$Hl$V>+gOyfQ#O?6iR{Fy9O_@UHx6fD$p@tYf{T+xPn-Bbkdv8m>OtC_^fIF^v zOl`)qeBc^ScQNb`+{%0$q;e)5G9!IN#Tl#we0UJcZfe+;k3 z|5ouGo%Qn@T(fBMeR}8*AH4b9$gok43YzIR)P(TFq0>fe(3JJ1Y~K{{)3-vW_XpN8 z!TRQ?>`l){g}dO)CPf;7`C5PYvKegi;m+f_KzV~`!)?|Z zM;BZ$M9{P~L^U>+MiVw13tRvU&dqJNQ|Dz1Q-655vy7akGA3Fco|BriIDPPeVnH#( z;&7ycgBsN;{V16iHDq#<96UWX;r%W}Qj7;?&js*f(s3wECo>0CS=au zhQv^QPY`ursG`b?fWt_{x&SKCWkE;SaZqp2m3=P~s+4jz{pubx?nq9gc&e+CTRyJN zt}6AeR{v9QaWTdkzA?|9Cc*`tV<;rxL`8rXaWZDz1fmx+HNdnaI`V5=U`_O!w?~-O zEyb>)%4){u&J%H^?p1_yT(z=fHZu#3N9GlEa2`ZclKUs{$l{K14*J!(n4n9tB z%fY(bN`p2K(pz+)$iTytyyfK1zz6A8mOm@Ey_SnM%KO0c9Aa)hVxyy8RqMK#0{ZyZW8MZ6avbK3YAm@{*-9t2dl5Q z++_Q2!!>>c>{Er+fp)%1qS+wPV|BRd2CYJuS?8*!J%Rbbu}4B1o#D%Up{5?7fv}OK zmpJQ`KR~DtiW|VOV>hvk(R#9t$K%`BbREQ2qvFJ>-aD_D*9j2%{#DPGHNX?mN9BD( zGjCa19g-KGi&yZ|CbX-UEGM(2@`wb73j7zQhvfzpIr5siuZceObo?bI88}8#WvC%t zG?6`6UU@orYkkt%gRy6JczIJfohNwn_4w(9&s#88q?(`WxUhRD21PpRt-FbtBh@N< zp4Gs2=mVtj$r}V}JjmY{at`2j4Y}rQB4p`|!&TnWwsW-pC~r{m=8Om>IBk+=iOUzq z*9Vb2;V5Qm!L5s1-*y{`ve1y~ojls^(kAOiF2qvtyCD93Fk^*;MnDlD!;(LZjOosu1M`?~k zUr(b74!n?~0|b(XMM=|=13f=S)+6q9Zm&81Z0Xb@Sj3+o*WmVvngxe8&9&7bqwh;p(koKc-s-nnEoEmrOC$kq zT2OvEp&f0VwLyydg+p2v$C7^**-xjGouW&XCx>$oqy7=*7jl%IRvvNEUuM2HX{n;# z$+5?2szMV;mjGLtlHBaQN;nz@^Mj?)7HX;MSXtBTJ*ILqJJ84~!zT4!8OvZNm1i3b1br=-^s0rv~jPMubyeyKj6k_#afIJ)qIeN>%3-r zfS_mCC*3ktF-d}z+Lh_wz=Qec4vbe)3ej<-3rboC>wh>*z2Vvrs##WTG-IW zY@wJ?k7elXCKg;XKCGkig9MxL$<&f>aw(y@Ii*%&g?7p0mb@S|Bw>O9L_%e0MvGm0 zRqw5GxAXKH1~b3lG;0=Noem7R2)uWvA^j`sjd4~t@BBC6f4*GovzQuTDQz7QGrs%! zi2ib{;v4b#zC!$(T5U(U_yt>yqKZS5%$E-PBbBEHov$|xbgf1V_LqRQB8$At(uunFvf7h2 z9!DQhQ>kI)0tyy(u)O6-M4(D)G*9 z9nD-%sZ3%G>q}ut?F+MpGeMJ6E{QZge)vBpO(wNeZ3Mrk>m5LmMn z(}7GsMJlqir!N}JRrxI91+*S@HgGf zG1%+gk)IDTVX?J0*l1I( z(UQ{Mkc-5ET9#yaGKw9)Y)0yEV=^|%p+5g{Drw%0lxV4pS3G(s$%xmdsEk1?HK^-= zI`WeRqmg+eDrU(|(?%x%gsb{u-(7hx;*dOw<7yx=fy11O8rvPtGv!3N)tO$*p zb7u@bIyxt7x+PSIz;~5=8?TKj0eSHVQ3sjkltanYDOR-YE9AO>QB-9B7}x&yritbf z(QS*$hfkegb(6h_pIoQn?f@UNi=98BglWoyLyugd z%4jV{z%kb8EJ>|+JSCG-jNCFCsZPiB)&pha+~zHe3iB>!#!Vx*8`_PzU4MVbY=E*j zWAmj$>*O?)P;hFTPYNra4K4FAHr-WEuQLktqqpW1tPrZGOCNua1yTnILg2eE?{-`$ zGyoFWpUA&~`30^yQ-ol6B{Vy#Jim;hnEy}+_w)Kx;tQDOCYC){vEHL3O+%~bI|-%u9R5xd}XWp3_~S_r9;8?aqQ0wvH%-+cBgiLt4k9AZ>M(%4&jSK9kzj6?Mtae&7$NyI3@*Y37>m+r@@_gYbdG zwd_|jZ%`#%T=z$nxgOo@bJ5*3V39#5KGw)XXkY{Mrj=Gk3nUW?4`yJgWCyZB1Yc1w zMh@7d9a)7fsLWwpZX0=RSd+^(N&3ArdFuV)n5y zeSG>dp61x@soN}w{f(mc;N2v)?-&gE#DFOrp$-vv)R~*)^30V2sPan=r;;zGUiPQB zM4a`9lLbo=bhaX;0dxW(HPZqYYkA9`)Wb|Jl7<-j1)nHC<`$@gzd!u6w>&9{sH#P8 zQED~sndREix{&$P#McU^N$2|PgPEAr@~{Ya7q@{Tmi9n3LNtjL3?5(=3F5JEWjgED*2auy zI(v1rV70{1p1>X59MoLmFizzWn2dcLJV|$3of}VuMT>D#%<4XZr`n}OXlp1GX!Uk5 zd>@bUE3r(`=}V{TopAD9?(V;Bh8wf;Jsq3*X2u9}C%K_xmdt$)b3R>Y>##zLQuTVF zmW3IcI!$&?Ig1^;%DbzF<6$0bPY$(KtU^KaT_ z*TVORLHNGFltT@PZ~(geCo*v{d}u5HrFgSaWC&D-jP4z*e!C=dh#oYn6Js_Ma`hoB zC}_2&t{QXGK#dilww-shpA~Hm+6ue>Uf3;t0e;ONru-_jT?5)oShj+*_6&Wz23b#! zhZBg}xC9Q9i8TLNe^8m)w5H<`-&dVruNj(uwxwxi%<%z?%2M;3aBU3@Z&3BdE6UxS zbL@Ck;QIa zJDh)aD2-2agNJNDnguTqMN{F3%2uD{%ql@y}*WuM>F-o(x;A7%60hloHv9aC zx1m?PzlKaK0CwiU*Y*7;q5kf-{69<M0d6~b8!ba0maN;BYlnLHGzIdLq_+TO8WnlcDDfj;)#`=lZlOuiH%o- zjhmm1kDv3^AQwL?D+SA+fLVU6>c1lvWcmMaBKTY2-^#$N-d}yM<>j?nvHVl6{&4n- z#{Y}$&s_XpwD1c3KO_GYzyG7_e{}s<4E$HZ|I4ob(e+<3@Lvi4FT4JKqYL3*FFZiI z*He)D>+4KM7;N$Ds}PK_yo@9m=+{qnYf-{$54^)$9cM5wM9g2m;9#lgc(0wXF0zVJ zuzQFY*qDqL^Ap)%U}Rvjl42Sj3rEZD$=EZ`{pYvCOpAz%b4ofmbHM#pI64Rfw<_wN z+Qt#8ms1wgcqS2C1SYbaY>9Z3y^_!qWZ{$Er#~if=GumCmc37hPh*=IZ4t@3BC}>M z&se>OmQqgBoy~T<$M|NouTBK&fjS;m*7SoT)KnDdd%;lYc07gq9jr)_f44T4dRr46 z;TBg{tm9?*cRGA=wu>7Ga2=eA>6r@zRwX5KNm6n`4+ zN881@M5&Bf3H^82Cmm$3GTUii7+5heSmm9a_s45s>t^0f&uB0h|E=L9H#4K5uB$H< zMzTylGSZ9mF}mkQ=T6WyGUksf;k5|D%Ea|!6jbaOHHtohB-bq%=zq01%|3N?MHg{F zrNw$M#cAfhLBGWUb&|D(rNsZH<2~(A*wls2fj{*>BJtZbthNOee@oE@Zn#=DeB~C=;(2zT&HG<&-W%jT3|&i)<~R$B*J=)r$r1`%;;Jx2<7rERqK2( zqRfwJ9HyC&4hTb4LCn_uxWgGO2zk3-kO(t!%TIpUrwuPJeYLyQKQbTE)(}lT2QPgv zkJNH&023qES+k~(!^G0hzgKVr0P!?1{#H1PS4?{U>&cBHmM1Bf|H@OQxdz|ybe^e9 z{TI^X^>t~*dTE)>od7Fa1i2PyE8piP@OGvD#&e$o03k-+38tZ?S!H}-ij)*ZE+W)+ zJdP&*8fzS8$B(T3KzCd^>Zld+#dXh=^daI-s`21o(Eb`hIM`Icp!810ZFp zjI_{~#vV07<5fxQyDp=3H7Ec_r$-uL^fwLLk%O;{J7%yMJsRT1X6sUaxsdny%0+E* z>g(69W}QP7oPNlcLi^79P>G69AHH{qCn~4IeJCo1b5}s}Wp2G{Y>+VAi+EL==1?0g z1l{YiMPoLq$>2ULJCm9lhyvFpy zuI`lX8W`=t^!qi%f8XB6P-Vlcg;^5&0<74@#HBiz~CBJAHLP)if?D*AS^IS=FDT7PYfato$3B$2NgRHljS8|iGa8dHwB(tD9aSEe&JC|-G&R0Li-R%kgJ{o=d!Od?47tuoA0 zZ6Gu#y|-E)X4D{w!^46x)EDdU$`;VO+Lrx&M8!*gCC$jDL{mYSRo44dCHhk)Qp;m@ zxj`$7x#=lQz07N@@4w8CiL4%7ny+}D$}VR@v$O}|V<{{oPf!&VWnFocC9~rztD=|h zSv(k=WcB#o_e4x%V^dL>L^WQli6xsgsiAx=o@t*=U^SR?+WpLyxdhn}DzuRQ0CCa~v zaR#gW4ehlSmV z_Gy`wEpMGCPo+&|0k6sRkgz?H1HdNY?D@xg`MzZ#yrQ~~(5Qmq*TFpaTpiD?r=RSX z4;4UD!;sEXgfvh+YX|IswG7O;&bqg*rd3-Bl~@PKym#ae+TH-1$W%@mpeY`!aA7}3`nUI zgY(KZZTUe&yRBMR7wUiq$v!T-=JSFt%G;`PFBZ1;7t*?|`yP?7FBWg6{EdRzTSZ&B zloKo?HRU2glQ4eM3Mcf%8wiDthpl+`(i&waf3z&i=(p!r@86nKj!SKMl>d)v@MTZM z1zqUyJ;L0>s{5RvIrRzwBxOA=8?K=u$nSi$ALc#{f zY5TZkL8rs<5eT{yavm|qo2N}b1=drSe%KJI<9(2RoFzpQb=bY!6C%$TFp7$_H>)`~ z-c2UGkm-w#C|!j?Jk=sqbGc^0clL!SU&tu)+h+UuEEJmTErS7b=jPj`#lk{;RN~E7 zqlEzeZr%VV~<1IGF z*c(((pBJ^SFI{oty%U(fT8S$2DMY$-*ZQ=lR`6%t#9)%P9e>D)x>g7vv5 z2a(D)7C}lORmyCpqGclc+e$_KiahEMhe`95mPC~7sHmd!T-!=|j%-j(OUdW>ruvzV z8*U9|+=up{)a#Eu;LS{8{SHK31gNxtq!qEOD^bvD=U3C0BNRE3C!s@}Xlj5YRqDy# zRYfV^MA@hgL?2{_@6bb}J$ja%=TW10+>mybSYdw5vRircsfZEo_-zXG`l{>AZEA(K zfB(`0RSa|@X3aAlzpw-La_*B*M%mx zpsA$fW-X7ZmPrspSm5#Y^tbk~ucX9nrQ89YGjl0ny}c=74N)B0SEDS+!g(ULFd1UI z9A21&K7n3F&`8ruU>~L{p9yi~+z#cG)8Wk2&Ew$|`5F!}_BR0(8#< znp51rQZjC8@^x84bVWpev^K-IO~f1Dfq)V8#Xeu1EpGY%?&5JqOU2*8x(p>Ljjmow=3!Q+}0N5(LlV#YDZd(jReZTy>Yp$L3~$8lKA2{ZN=o+yQ%c zP`MkqsEP*QclBy5w4rRA3ngv{cVSkob>MuvOf(7>P zVK^+2^dG$Gytb(mE9MoYT&WAv%rCA@+Ko@NLPltOmGETVth3!?jcH2)>Y&@?5VRD` z28V6?8*|C{_1VF-ZqkN5-AS6G-V`r4B-ji4gtGXH#OY^Jt^#()Om|FJs$6uqA4?9- zKA(`;yK{}+B`5H^PoI;(b|dAuJzNf_)FlRPU_>@B8&5=4sNi@B>jY79g8tqR(;bS| zwBWkmKF*sYXFVl+v={0)K|l?5A#)jSMIv;KkLNXe<9qr99kr6#(`DEiX&bzG;K-J; zdu4Q;Zld>YgLl-2ESMUU+7$_F*hhmW(_gc9<*)T=VSwcVzY21I*Mx^q*eiz5pP|#O zcjM%d;~^`-Bfchri8M?)K|7{Af0Zjb{&vM|BA>{H13_ynYX36I`5N)>4fdjyRZ}U` zh5^Zmv+U^h?kKjv#d9Cm#pw;npAFc_$>ImaKilI>%y-zIv^)lG8VoIKBZEaY=6-OC z9woQWF3bLZ7gk?OxPNWMRs_FKC%?hIrPh=+zEypF_xRmjj}7<<$@z4DwwCa>rQ5Z( z^8Yq0|JOh=tlltu{Z_1krCj-8TqUrpD_mLe9qXSI z-I5ve6trJx_7!lQnUU=6H%UI|am}4il(O^_ZW3@qTP@Fk_!A_Bh*kfWj*_osSF{yK zkVCubSjwzZoDtDcdAvMYoqrsTBW>M05Pqkt8URSuPW0VCvIL2>!Z!!FRmj+C__0C=D zmWpAihVVmj4;8e;*6TMOdBQGQ1iLmC;$8b3pkIUAg6(5w>3p2wEF;$KApVdtj!!zjxY z^48`!#su?9cL$${h(K7e+}Uil>&9MAJV`PfTo@z;8-K1&OyXc^`#j_C{SnddAu4bV zBCB7*YRmxZWXW^dRasIg6M`~U&@CQ#tHmn0Ef>>bw^D;S)^88cngOAy*>bgAsFfWd z^Y-h7rcCIHVW8iGTi3!Sj_q2zG*O36$y%7^`_HdyxG2Xz50*~2FTr=PPC!*o zbX#pvAcYfwHRn*R^%Tv5`(fzVu7K%%@lpGF4b$sX@bY>BQ(x#uq*on_;~pdeJe*cPCqLs8M$M6YB_%(AnM%gbH>+v$6Re|g`jeZ z)KDEX?l1bxziToL#X9PzP~#r?;|phr*}09?klYgwuPiZ~Fo?irNM^==rAw<3)~d7$ zXOzm~2#D}=-(?B$%>aJ|F4$q=H#Jd7CFhScl{ct_f<8^u^+2xgJ}&mg|06^}z`r=AvsPJj2_x@(SWF+J$=aI!M&vu`Mo5tM{ z<=fKE1>jcNU1+G0yy$m79#)&P-Y$=QWvu8fzXsG3iiZu+ewtx!ynlCm&yv-41YAo< zLicXL?r2WoyH%vvs0!Q1cRPr+T8Sb4ytB=I7KlhcI@C>!ChF54BZ*8h{BVECrkKz; zJ>9peXBc~<*<(ba_b!@l!_NP+SO!s%52$RTjuB*p;mv~!j#Ez=pB;cZahoe930usa zkxbUmb#nz<9`int-z@I*3F1urTP#Nl>V_LM$ppzyGyl#fcj1EEVTeF@{zsZoyd-2jRy1aKV$z4 zIPOHTkx6qdH|`ifS*^11oV(b~s`2eOjK<&MzxsNi8BvRq+0qJFFDG?9fLw{Ek3 z$4mFPx;Z>5oONk;7?c-Lt@bn_!C2|nc_$zLUQqgl+l0w1*?-I?>tl-GXXaUbvEBMn z9P3`y227E)?<^EW>JUT1PMNq_vx|EdRjdjLI=4%~ly3s!+I`b2GJUW<#Gwj#4OG{D z_Tjy{lLTIy_RMIR=-^Cc`NgX$3o2`;aogxNl&^DTj1owNl`-CA_=88S`bIgT3I!J#&ugFKRv%s4kK|ZOVwgNk|PpZ4Y=Fo^1>qdEw zBp%bOWvLDEWtLyeeH9B^iSpVY9E9mpv|~HL(m+GBVnZ78Ixg*Vp&_{p=h}4yb~*rF0ZjrEtPX0n{iT~`&Wdk^@5|bcWWBP z+l1NFYpyBVo~EqJe4oI*Br}E00}i@cwXfmJ4l;D%_clOX4gBT|b=R@8*t=7ORS#zw z2W`t;o}jf&6Exu+bY`0>gNN7x+eN0VB3rV}LP*?a*+~#XX9S-488g;m8VBSo5a@-8)=-m8(78!;sALupZ{;_8X<-1;QG*dr#=X7R1UY?3%p z21)m1U1e$~j)mVO`7e_Y7#p+;b?indAi_#CGx@=M?Lx1JCEJ;I(tt9C;Zo?l4k zYs)bfZ;UWyj%M6h=?=G6o+>h)z==sopri+?sH>v2t7-HcRlwimmGgg2E`B)SktSn< zWF{+IzsIOox)(^(#5EDHi5_R1v~P?YtqSv3-Yf8!XxC=9g*2Fg;z*o(y?PYo0r6z6 zwDdB1?Mg%<`rs8pn)lsbHCNMyoIZtY_}+gOe6e=>UOnKm#Xq@3+kReSo3?y7%dr-S zsQtQ9`B8~~jJjHb!^J9-73lKdyxfW)@q)w?m7ceF!!X`|u6PcYO4wD=hn&lSihZJ& z=mXvzM(N9rf>z9~lXRbKKMI7@Yb}X_qU90=FW8sPsUR^A>^~*8^%Tj6alG8D@V?=$ z-m7z`FL5&RU?O@g$#>gA2Zw6``3^Uq{nZ4X0DT!5OXEr@HyZ?uqca|#ewj9zN( zt17Fk6$7Q0yUv^i(ARYPhMS8v3Gn5QZzu$zA01GdLtXlP+U8Xv->HSOTpNcjaYob0 zIB)mm-)+L`sCeTOTNhp&A4sxiHKoLOrsp z*7CN}vN5~Y1yS&fATt#S@XR zCq)^lW4~F7SJ*!ZRV@9udGQAhlkHYz&>nKv-1RmLteOW@z=%JN-~Y7U z!%!dW;~})}R$h9^NZkI>@C6&BC%^S=Y^q}D1v67jbVD@s{50%XMMKX5t7Q zP`qD8(EDj2E_DIHX?oS#SNBPl+U;~!nU?-03R#&=ZT~%i!VIuOvnA5?=StrYa^jFn}>&`lL%Ys8h2?z zh0ie(fmQ35V+17bP*7+j#K$7wy!yxq%{+{Y+@Z}W_8eut(?4BJ_C|0wxqUwSyfBsu zA4*SR@8|2g5>wBs!#7)l(8QzSQ%)yd5;{V{~DLoekObwJZWg(@QF@-MPF&Un2FJFG9@$i#%xvonn%wKKW)V$lsLlO z@up@U3Saom&z7O1-Ibo}o^LJ$4#IJuXC6Yt&~cv8j&kiEiPx_IV~44>M&8@oQmx0( z4u(5^;7R&2Cej^vSHxR7o73NBwrM4p(LYIEyFXQ(!W)ks8{K<+Wj~wPF4$9D;pH^C z_qHRv~Vw#*9bJ+Y}A+0E{tG_z_VzJ<0h7GXsv*rewCgcX+lC^K#%`k|e$D!Hqp? zhk6_ocNp#(^sf37OO{v0HR`gAW(UlUhzNeUU-G4wwDJ1_o2 zH{@QSnNPZD*Oxo%mtMuCB@~?8iCse8XBt{n&dcvhA|v7UCcl(yP`KG@zy8-Nw3PQP z8Uf+Z#r~8dH0-)V(;m0W+{DZ*F=+kJ{bu}pb}RvZH+X?av+WA2<~WS^wgu{D#3ul| z^pRulTp%3r!}sM&orcoL9dn}EuLe)#&{ebSC!t8`Zd?UYIAVS1q@yPzaXtFU(+avk zw24#xJ|vVLAlQs<^5Y|q_Qa+oOh061#&p3_?;bq5N>d=qsej;gcc$@Ct7YS{v8Ko+ z*ih27$(5)($M%k3N0)#(LX+0gAm1$28utg9L+7*vzwT!LgTB1y_OIIYOPPt4FQ=ef ztLfJ0Ly{O-WN#6l^j`INyxRmN-qgs!6wk89;_!T#tZc2ufQH%+2WxrFvbD~I)oiwQ?IVSyoFM&^2MRDzNz|^Y?cFesX~BWgSNB`6^_f3SalP zFy)%9ceLg&s}AXk(<5e!L*dd8?dPNl?YBWeZXA*I4Z_16oKdz@!d-YEj7?Z5<5`^Q z3T}jM{GsvYQIm&K?jVxpd_TCH-81R+y|IK7POsH#suNMzwLF&_XP@U&U@d67LwfPd zWTl-{r>Pq8r>fO$fflWM4e*=k4q}=1RF+umvXUN{$0hE?HHUH)*&ThTs~gX<0WIke zml#v;kg&0`B@eqAk%Jy^A=kp|&{}?pn7x>BZtBckfAlA%0p?Q9;RMXV`1jR~p{RKt za~5B}YpkyTn3bpdVZR4_oPNQfPbi9od4v^XkB5gl#%d(@kmkW++tper_dkoU1o;9Q z6YWF=du>2>&Q|=Hih+3rPC%l0r7hn5i#^|3*G+rem6y+fv^41#hYg|Lp@9fqhI52j z#~}V$bK*V6FRlg^&l$6KB3{z%w*p+abrbI?zr}}% z0Ru%WuREaOkj8eei`?_nFKy(XnL&}aPCoJQ^M=1Yh0EGjH7|0OTo`&oVJ^jOFiXog zXxFIMS$tD979|p}y{8lw<#m^!^`XIm*t%%6p!!Du00PM65foL)ges7Pg~29ZGr3#k96vcDus&Cm~;lZBw;MiW39s;2-Xe3lq~8*E3pnypRH|A1oTl)7Db>I~ z=!mSg|DB6mYl5w{kPE@wmoju=oZ$uOic)?RZgZHr=ZXS#Ru8RV6T?m=tCtrfft!Zj zcQjjA#@BMfSB0I0y(a^iPuPqZoC&_~P!y&Q;i<4_6>~g^ZqOt z&uO!6X*SUc{E<{W7Fhgo#6}B8l!`6MQ2gK}Li&jPX7q)JFmczUnFvpst1S{t&Weod zYK!>sR519ggPO#)|0VS@^qAUw+3Th}YqSe>g={Ss7SFYC@MlQcc_R&*w|qA}PKghe zCof&VHl_Qz-~qyh&P!KyXwV)9!(78`m#$FSGdvF#g;FgP&@C@ zPZ=9A!Xjdppw({q=K$_+FZzWD5WVcVw>(R~duM!Zd>8a;ZN$}%Czh*u8}a2(NmLjF)7a9&bR zYsvV-sSVhMyQ3PMGX@QxJ4({K4<2W0`Z(E$?1(TkpvCs z3f9ac{x~~sz}E?y~a-o5w?I zPz}LP+(~D!PJ5R8X_-yWn?14|5MDdnd`V zD)$he-TK^#LRXTgYTvr+JhNvBf>r~woUNy+g z4+KsP_U7B>S*jN!G!KT(LSXWsdv4pw=JO^*S+rKBo6>yD%Q_@Uq$BR+vT%}k7o z?Y5zt+3d!6M#*@O4U0Fo(>1qas1ws}p3a?d;uwQJ~$60Y@HfzM@u2&f|o)&O$2xU5Bh&`-I=ouKPxVgR@QAfdB6DqsP zvVrODjM4JGiM(jhg9r?wpQ{Rr%oW!Y>kRJeBYqznO|{{7%@~B51vylIFth@AoFA{8 z=`XC}oqLH0upP4V7`^Z!Ft(zKF+1W28Zc~#KB@rqM1Q5kcL6mKu{(7uP?LX49zk?I zGe}>$ldLK*tXlhKqekKtZpVg_ojBtELfw30-@M;pQ~U_CrhK<}Ent=`{mf19S{;lR zd*V_RI$kcu#eH9Lh6kL=j_E%f?r84Wz!i4SjD6Cp4EZL%Q?oNj z?{k?TgFjJo?__LZQfn&{J!D50HS+UR-Q{9&1SPS_u$#LSP@!np-#UH$m7J?^NVOgv z2gtB$va&@HZwF!$QimYeiQ)4gNr6P3CaGs;p}eZbitb)4Hao06ZqMe;wY^Nz?kTB?ag}~eS zW%y{k4fk2`$$X4uBzy8af)f!CgY);8sdvj)yJBpczG$BhpM-rXws?luDr>+sN*otQ z&rCe?pBEGZWv+9igQcG}HtM^FU*-rD+wy-uykr}Di}=A{$wiyl7Ix&t8awfrzASlb znQ9|r;>a5m(Tp~g+rGVJC5b9{N$n1G6|^E6XuebLylA|(ZwBcxx#sO}a9pK$e`kX_ zK(Q(1bGxyNn&UZYPQeWFRsiyqPYgd{9d0roh2*;lbI+=@)M}fPGn}kJPz5qLzbJ=}h*y1s`6MNo;}S2buKXJ|y8iyLdb`h;XyNBY<-y=NN+oNHqWEyq*= z0H>qJ-Oe1)2(W$5EFEu|m~t|8VXLDrVb)^tv+QX%7R=$f)??dItj%;V;zPhL-z`SL47q;IG_v~LtahB^%F!14Iion}yYkw2+0kVL7 zOpoDqfIsgTIs%6^yTv8N*@e0Olg2|cAO5iBYn2;>RgoNL9l-}2K}_~4qp|EQgx==K zov{-iD-wzOUD;(?{GoPk_XWag-pTRPpw8!wiL`cdg&d~1STpbOxx~hp+rP7_ogH%c z^*WIoeeMXg!=kN!MLyNs;imN!^1r9s-JCv{#Zzd%>i^*34$WA#Jh5E=BDN3>d_;@u z@OX6~#nE1;o8#F7TUXcoYB&?P=!>J;=1sb9%AXw{^4Cy8L43KT{?YYD2sl_`(|J)j zUkOJ;mkl9Ks_$VuOJ_>tU3fP;bsabAi8%Z8D5v%#;=}2GgtL0S4UJVU_ufeAE1!Xj zA4m|v6xIF|l>{a)EbL9Dk1QH}G=&xBg{6flqx6j%_8mDKq~7tm;i5r6^plYyeZ!Wr zR73AkoS9csMZ!fBmHI*Ex4qp@LZ+ywA^~vNJ^p;$1Od-ue!}Xlnz`DnYv^VDg-N$5 zxPibc()j3`5pIn$HoEL}{?tfW3B8qQnI^9tH$HP*$g)vb(x-Uch#w2$JjEXMJdbKP zqk$)>JWPdqd4?B3tt!Y_#g%}KcU_Tp@CD-5nb{VUcFxq6xz=7xkUu%fAteAM{*vmo8j63`P|j8oiwqZ zz#0`JTX-`R{i5TM7enhCHJfq8nF+Pf+KPDlGUUNWytZt8<8rV%y#duH4TmG)ZBd;Y z(H-d_#7-ng5Lwmc?utMc0anjK*?bxo5kkV^u`js^Rfk=P~=7@O^N zGI=m;UTa3$rA{o3C3TsDNJGgb<8hApK6X3&n#WHZAEL)g7FzYF$-B;6-hryl(UY?< z@R6uAo`*9Uh+y!D7pLC-j);JNr^rl#q;}6in%|FOG#(R44;tTG0Qvs zw~%W9;aZG9Oh;7a3hVtN}q9RZ^4Xbcn#+y%3 zi$Z{-^q!|%nP_PUhzD7a?88n(S(i>1Xzp!^8kO9+b;TvW`tOATW*3LyBo~ zh#MKe3Qi2jvM;B8O|pAujdgJ$d!o_Fv(0u=FkY(Y<2-G$(O|r``Qfbv78H3NL1Z#q zaEFH+d5kL>jZ{_pG84S~4L^vvky`NDZzwjKJ=C&r9TzKw#Ur!$nbk(Ei~4- z?cC>N(>-|w@f`)6Kx`-Vu9>j;IpwDnh4#JOqK^h-VdS|?(QO4D17jK`Ir$cc_tX!r z&BEReWFD6<7sCcJz4Qzd#_77XmKS3*Kzmj(6MQQI{qEHl>GbUDF2i~I?p4`$f=eSy zU{%$&rS$S}meXQNWgxD+AMDxS^lPQTjJ7-@5Wv^nzhcS*wBrt7upUh>PM>H@j$C;n z%i4JC$+_qB!4KumX7IfJ6dSxDX0598O5W(p?5PD2?xm%xs$(lXHL%gP^+<*XQ$9lBbbd-(+`=`kI$_`Fw%+l>^8RA z4j0^bh>{}Lk(6A-)R1mW@AWg00zfcs&vE3mmKQicM#WK-V_`>gC%=hMp59oRqn;F! z@dq22yQdNKZPkTUB{>-deFZXD+2Sd_V(b^F!5Zr2WR9_$FMaIJ1}DiQPWIk{#h`M^ z5IYW6^)<0C5!GoewI;i}W!>0pZF2%DO;$9iGC$cT!eclE)3L7Z+4b5euFXyTMrzM< zdV)P@e}H=AW<#z>13vOwA~mOjkkL*k4oeX4Z6Rn3$B_w$hEj-EkpJWf(xivS?@gB$YO&Mj!DNU?JQdA!w8 z_v+A|`u2o%7cF1=@P5t{ST8M5xVwP4U~$CAhGVeOgb&v^LA`dhI6**AV}1gZ_~&tO zlhfsPeOIeLQ#OhuUpJQnhHj|?rNlBlbfFNGzKL{#2agR*E|fusM=JjXT={e>F}+ei ze?E*=WJAE|KYe=7)=ERJZ#*O}(n)|N98`Sq7d0x2148i zH3P=)9|)DiDSCXuchun34n0Mg_g7@BMdkkw0h2NqAR~>< ziWk1#?3h`+Ikhqf8h18m&bgkAzv2LeB1r17!I4&E<&UWhVI!}ugeEI>GerHHT^#1 z!5KC%3BNYay~cCoL&XY0b$DFTEOvIqPM2MNuc&bF?=_3%zt?==sLCB`IcM=v5&^kd zT$m~F^|fB(t9*1j24wAL`Bn=2&C9AMQk(qHV0Pf%UIGXW9f@5~RuI*GTvP35+7=8A zbChCyWKKx$NVWiZjBvxUB&^z|xQP7rsmF7q0Z8z^=?GA-t1ZP+U;4JY?NdHuy5hE; z!}7fhz`s47d@rVB+A$1Kau_B%AlC9|3+~#KIy{*+IE%7Al#MRtd6o+cwPvFxRO)o#YmnB}gw5i1ag{G$3%R#KTtwnCvldJiSY*J1=luGP z`<*!$GUVWjz~_$p*FU;;x4NR4M9<-f7>F{qLhS#_iet8f%B2lKFDd*1g30Xa%J*CF z+|c6$Df3?ltsxmS?~wEA+QJv}B^<7{;MXdT8S&#KYpGpj0UFVzD_tZbu>~8emNH~;}VcuV%T6GKVI`nfe)<-rW0EekevxoSUkp!>>ag+UhQIyd~H zr-47ZIB9bDruviWbU)^Sa%Q(&~dA4T~oR4X8Mta*jd0G6Mx+D^{^e_-E zd9nhlzU8;g?xMPIrq|-1=I>>_#&z>P!|*jClDNc;V7*6Bwu*-#vzgA;wPIC3R*V4b z^m4|MjV6z-njLSI9oY6Gk(xZVgC*hU_ToDq;g>Rd;?Oo@^MOgb0fZ&gq)qq(8C{eMeZr(@Wc2qh@~Arvm+W81FlnNCG*Cl8!&wI04u> zUIA~?mH1@omxqyD*IO~FU^vnQDHyiHts@UULdfNXeT^^MQE)xmOkX7@iD)(V6`iwO zSUv>`dG!go75iy06qk;iOmY`gl491fBS+>kotbwujW6BfKfvH#CPmk5k8_IN&|9CCnHI z3RoTk54x)gJexsE4GE%@@oqb5!X1uqf@bgLLYw_VOA5oSd6TS&56C&y10j4qJRSSw z!?{BWncQ4|=3;2tz13A>qS2Bn!OxD0i=@9o0&r|wU756A5Kgg{DWf!{H;;Niu<#mn z;3B3&KxBNN)JlbMTK;obSI}J(D%Z0k%n^z=#9PH!DG5sko*)B4!;rmQ@g5^h7y z4#~4LfnT=x|87;r!08nR#3W6?+NkqvOgqyFxm^?9JHBS&TVD)F%P00J`eZ|USi37}=c7}^aP+tHr>QSIJNobv<&`%DE6XD7`fS-KlL`-Bl{>ai z`K6^>U9j`-(A*YE~U#_&;MLZTaC<(eO1sCb9V<65k|-a!O{ z%&6dk*iD(y#SrIO%$2-y;{9GM#{Qi?gmP1G^V1bG=@|}x>k;of(b5lb`V@Xqm)16A zX#|~a>z>hJ*(q2YOK_Y zfa9HW%ILD=Gu6~#OH9#eYJR@HM052*8%VWQvNAbder8po2}siXA?LUd8bQp>?;cIumxg9BmcR|Wp=|6q0osYu)D&GqLzQ->c^BPs zDE7&m=|-yN~g0EQ4C}5Kl1W*j(Ma&(;^5Ik)_lk$!vGyMp zU}sZ`9z#lk{}c>Z?lD(b&&8|NfgdRstX5Pu+C8i8Q#GeP5n51|aRyWhP#;8=y1n_t zX%|r(q89BoIX(GiIqrl|Pv*VsYF(ydjE?BtlR~MT5ptJ(%PYy~HMU4`p47-puaXyJ zB-mNrxzCUpDUX1d zew}%z5NY$5j)eUHv-5Ll`z)VG{O!4;Sb>-CJlYz{jjmYxuIJY`ox`rHAa5Rl2Al7+ z!LE3D)y)|iV(^2edU5%R+i-+z*CPhhPS# zP`>-!xvcpFQ#s|mGVTYAQqt$s+#{GmguwFf`??bXq2h(yiqUeV(oLb_iX^`R6;p#$ zmSl(cOdYY=b<;%3RBYa`28^H|;Lz9`kVBBlWbhmfmtyaOwE4b|P(zW}sIP^~04}&k zOHg{*CyBR;JkIyiB9nv^#j`X6W_u!8t@#f~p@AH5Svy)1Q{V?ja|x<*B_`3!HnLa5 z*($X*%K+_i+-^(em8&XUi?vV)&d#ycGYuoAeVYp=*1*8t-lyEFxb2s+JcT(%p#UK!3W} zG^f%Pm6whl+uR9VA9a*=|Gios7H;AFO<70V$g0iH|JT)RD9X$C3~>02Vfdkr)nZ&> zdlEXV(~`Q!Va6}d!&cD0@9O9lr<8m=cki(YD}b zz5EI|`}y7<2%J9Ab5x_L)GLW9;ZBrF6*HMD(zEi~Gw`1N2ZC{{l>HNXDnej*!O;S& z`g&xExr!n0E|mBaX`ove*bmW};qAW_{;n?aTE6r5)zkJ9Hb22e4R{ut&5X8I#^p9z za!jWiVu5CAvE_z)C8}sZK{_`d(m8|1*fa*=J3O$Q3rnNoGF{^`NW960*lo@cMCWxQ zNMEGCE4x)S41tc=!Wg-9@T>4)%@^q_sgU%jf)3tNO;N>euh2eF)-ZodwVL{-(bgp9ZhogzcY={gd8n36$*et`# zt1`fnam(}2>Phb!NVV+RoZg6+zx~yLc@B$4VzVik%w|>R#$KRqMMg>njtf@0MB;O) z|9h1bupAOxW51vv|8gTBAdA1^q8SJFGz~>15fwcyF>bu(DD$a4RKP4|oa9qXjSQ}Y z=4R;Zu-Rs_@PEWLHqj6oUt14RPc$Bn({jXgp#5bY6 zO!+Tw{g?vEUxXOW>2gmxHl2ANnLvwG;ir$3yh%;4q8 zC+c^hHGHHi`SR}w&AlejIscCJm)Mm+V`1oIx(LokV94w0TO@BuLVmgNYjjt<_Yw2~ z6SIc9k@-sabWPJt?^3NJt1{DRR))-sEm5DgO^$s%hQ?e*mcY1tIA<+!P?*0GLvuD_B$4^udHvU#uJYnMP8;gA2Q4H%7BHy& zvsp)kcGk3jw2=r8LaD)cnE%$h)9O57gdXZZ*)NI#GF_X82ePfm*KaFVb-hvmQ75x! zoidU}|Bw^j8m~s*FtC9iHoGIC_sm?QESLLyWRbQ;#Xb(fSV(8~e43?v!kW?@YWHo+ zDxC8XQ+$bz%;5xbcBpG0`@Itb?$^RlM(6LleYz*asP66cK@YG&xdElGt$V<)|II~6 zhkA+T7aE4Hz|RCkEDMN!(L>{7^Y8RkaMI%74l@wVkgL1LRztJD86y#lQlsfj``R(f z$$f^iwb!Ri$v8bsbhKYv&xHP<-87we zYg$2mL*n(X>Mu~PMzjs?Scm$D_kZ~nr8}o+{P}W?6|5_(eGl8z^eo<|%#Zf#Q3Ulz9W zaC~O2m`%3&+><~tZ_13hBz4C6#e*@m=4;C6I7Or1@?ECD;~H_b-FymvVr~V0oaTJy zB1$Pl)#S|1`l+H&qa2Chh@4c`X&5PKzf4#BUiIU#c~jg*mrYT7^%q?2ZN4AKiW}`S zIZEx8FkMq+85$m^y8M2*eFxWBSl9*g%;hsO@9+96FF=C5q93`Iy3L%DEKXIH zbb}jjtQH8ZuLJ^32h_Du`?;kE8h6cE_`5_7rCJp&wNd4j?tkdH!JmGW6=Z zM+h7`$_-VTP9;y((HL_H4>fe}oVAksngMnA+Xp+vhQ4cu#k1GCy`Pqkx)#IERqeBAqL#vEWRHkZ{winKd=KaII`~_Td1$*# zS;5((TjLaj>Nod~x}CYc<&9^Sjy8zwDOs}XCigQ>#@L-E{hSKVh1BAeJ(^9St2yRl zB$I&WJxDcK&uEt@0%oIpdhA<9*GWAI&3We_IK;s6FUX4*1>-cA@c)XB^`~0-{5%R6 zS*@m|(Whi-X_>vd5tQbi?$X*VVfP+AAZqK275TPnT9;<;vAPy34OV#w9BBz={#BMES`QFzYkjNqF*zaNB+cAt%0lQgqCWQc=%&T-UC521!XYRah4D zR(Zp{fC{UL>wKl=W2@Q8yWGCu$LV}aSJzWpx7~fUp4p|tx*`A^(G=thjLlW*3tT1- zbpX8_UEZ}l<-yWY=a0)PHs|}rU*6QK@VvfX(kIY02CrI3>r%wZ}vA`i))FC&{)@HY_kB>IJLIN+{=5|I9FiTGs9hU>@5o=4{M#`XK zh2KpEk~a1L2jO{~$#GzK9*FAYcaSWb+al{IbZ*)IP{&23I zQXBy{rqMC+^xhw|ybiQ%2sM7EV6(m(K3Rj@^ zw>D1T4!4T+jCPV@hB}yvsSRaR;Kw0~|EOwr{|JHJ_sVsZsX?+?qaB6SD3a{OG6kAv=8fELqDcG1R>Kf$`M`J5yFejsx}KTrF2(65Reyb{_irS~2)gnq=%}IUcbtBpKAn`%yshE}*z;bvDQuKV*a#v3lOVk)R~lsfrpz@k4y)YuTH zvJF5=inNzg)e0_x$9HcdR*R+@5y5AP@B!ciHIK7tWqCq{jwAM!Mh4M_{v3!_?K z6sFW$ebsV(9V<8&_kv|P)sMWA9CAXwir(d}pWu`O70{enlY!Sq=(STUeeC60G5bek zJ9UuLGr+eAGpUV{-eQ`dZ6YsnbmA5bU8_=)_H?Ft$U(Ihc11u zp%S<(tT+d$6Hc7CmjP2ac#~68zp-{7WHWH_enr2()n=Tp728Ait+kx2Cxin=!#p{n zTmf;7lmQQY9h34ARe!dxk~CNhg|DWS+)m12rjAnf=j?HNoQQRvsyv0$(DnZ+ zZtoNIIgj>Zo_S^OcpWi;^7?x!bIGCDN16*w%myytU#d@36|BJV%7W#O+pj7ZAAJ_OVIuN-&xc;3*+0t(AV~>ey;Ouel-N z69Y`AzbR*WP_8^e;9%emoj1xIolYsYTr5;BiOKKyaQc;UoBRKrO_P872OJ|uXo9x&$l+}k7lsl$ni{zkR>%=nM>BXJ^a;q?I={L zPu&Ul%E;>6T3H7k@5rZ@(sqQ)R#-pO6F}|0ZRcckVU;^dc-xVk=;m3Vn+PAz*qlA@ zkk1#Zhh8ZOz<2lDqZYld3mt%OIIyF}HymO#(n^D-PexXegfn>Xu*aIt0SpJm0-)O~ zF#LQTirq_abstfN8utviuVsnA>scp78SRW;xwX=w&wpn*aca&;FF($GwI=Wa1(d3? z%F&tM7)wM=boaDnIKuMloLk}PV@M5ME55NFvL>aI&oo*w?^A}lsi)bUG z0A_Ckwb2M$EN^VRz2Mbl9KE5t1xH-1!~xL1{}J6sHq}mzoUh=JycCO3%bacYdF?Nf zs#cJSAmhhfbrzd?G?(d;AD_zM$8JXvedl>=%+)jO*~gW%(hnXlTfPI>!5=D#u)zdp z_I79vK6y@lRpB=3Ej~Ss(JSrEa34#Bvpw=t00b8eccgFIs;4BCn-B_9ctx>8Oosu3 zJ1`i+E#-}lqW(PSY|Hapc&uh9I9)5hZRcN|ZGQAbVs(~kSG8KX+so^7GtI&b^QHOP zau_aNdr3_t>|&co7ggb{h|}*U#(D5Sc8z9dCt80z%Rh9yV;#Vt4Xk2>FY=l{FILpw z*=;5I1d%zXvjwEsb&(tgkaMWOggJ3cHg(B%b;?>5EgG1n<#M3(4s*e5Y zlQCHu?WA~rq2cTvQk=s#?D-!zBTsvN)Lm8-N!T$(`nf@>5)4aC3bAVES@9;QxxsfYU3k%pOmGih*mV*TKS2MeLt7=|g>FAZ z(0b7XBa@@`Ny1xOoxK2FA0mU%p@NihGP+@nNGB^GdC@oB*$X?-bvriZ?FkGwOX7OJ z;O($&${F~Yq3-Ib@p57GG26|N9Q&SWcfxKQal(a_!f<0UOFkJALaAT&Y8d*l6_X3@ zUKGeGsNRhw^cI@wAt%&DYU%)MH-*nMP7(-q2ep^VYLh99DI z`5+D|DXgz;`@DKPAMb@udL>Lu@yX7Q>sMNTD^V=U)=QUMk32qmF-I8aL7XwGwwqx4 znbT@<)jDN3P1~4_9@BWjZIonJ$WnwkFiKEXtmxd#3&S2>=0ug8>38oI*<3Zz(uCA_ zX6|Oov3(7`ugZTI@6GbDV@FUf9B#Ax{iT!Xh^P$0X^fnIN#_TeM0)6)Ide_VNw0f9 zR0N*l^ISF-F*X8^yZDTmrAkGCum#hTmufK2J04*q2XUk^CLVrF5E2ha0mlP6=RxEr?IQfS5e5{966{( zjz{T;E3dYEX_Us-i{J&p%P$v2sIF-e$quv*i&@)GX}@uQ+M%B$j0Cn(X|NuL1*~AC zi@lAtl`dif%($dhdxU6$-1-~+o`2WCku$7!zo+~heRUZSQUxXc-PJL6k$dn(=4a}! zgT=&GRanltD{q+I;2GCZ5nRrJ8Z=l*k6T)*Lb;rP=!bQkK`JWq^ci4)=Go7EPDiNm zJYP3z)JXISC0|XLCVFCk2gnB3$^uWc$Cyd5@wEVr8gQUzUeKAFyDO11Gr$Vb_~`Zv ze%h^I+UOSsh^4h33@442ZIgh$)ukUwUSmJCR_B@>Tr80!Z}rFy43yu$f| z+Wjd!E$h2#hnXo@ZE%tOtego|w3BN**B$Yy7%P|M!`dq6ez6pkw?9Z>HuMWt`X9Wwpcnk_o zm7h+k;M`xi3psPAQ@(0NxM&$6@&YJqFzN+r)&+h{h6|Zwv|YPbX?>XFfjJN|BW0Y4 zYky+!D=91+avV#w+{`l>BRA@P!~*shU*KRxmWEqW$H~#RkSQc*`W_*#=y0l(v-$_6;(=lXl)`o6@5 z`TKKa9iN{aad^P7xw-@~<**#kST-e6%N3Y>2<57)Y`v@lSsE(bWhWv_(jhC`p8H`Q zs^+$?S3hP-EcIB|4w|NSMLiege6o1cJ(;SD`p~lIid{QS-b;d~3(T}aTg%OFPn7b> z{{2w1(?%lFLN)w2pGC_!a-!#3l|itR>7Ra8)G0NUqqGN}6p0h!?F z8Ss`zHD}x)h~5nyB_NX=&hUK-yA%k4&IrWY$-*Y-tGg}_%nekqWiR~)7;xnY%5myZ zgJYlt4{7j;UvbhNPA9kJ)nmQHorKCqIa)o4EsKhvYf47Jl@}~E4Hq6YhhslFge{L1 zxOkT#v_)<1#%0hXgNv)}#D6t44(g#j+Wv&{62+#X`XPm~%XmOw0LVLCQQuwuQ4LEr zm2Xr9n(z{BZDS@r^jYZycxyCzI|Wq(_mDVNaej7EH77RdSD-i0Qarz2Vf}K+Ro@37 zWtz`jteGENkOg1r*qipD%HT#hD=KTzKUMn@q+QL=_EmYxRsG%6=3@_6<3I0Je}Q84 zF$-Lg{^tJlpV*)7mE^?S{xNh7n<92>Mx`hO3XJIy*@~0r(#KCc0ptyxM42`X57b}{ z?>~dJP@0UPo;zNR^!0V}SfY#_Of{n5MBQw2T|CR%%dLt8RbSOATyz9-E~@!eD>$ED zf9vaqObQ9o(v{%)s2@V#Cw_G{1h;SUOieiQN)yBVZc)X1LH}DdQ~G{KMZStDw(fw~ z$Q5eV`h=n#KKV(DX914Y-}o@OY=OK&9rO^%+5M8Pz5ZUmCVU~hArlWzEb7P76u+XL z!mpeYGb`>k$R;b1w^Cc}mN*%#GvFO_7#Nwu*f;%pm#DenR>noQ4OND+!$Yhxv||+o z0maJEH@${a)q^?oe@WxuJ;z?4>gyZ!p*7IckgmXukS$s9=u%P$o-ca1c&48`=)|)b zB5DqTefKkvO*C?&cV;Io^E}Moi;Au+Sa+p_|HD);KBp;H`Z=lMRL-dU)}3zzFhMR4 z$U@h}n?j^kb~dk{*TVQ7+-`H7u&^n9XP7{i(`;TU52xqdw)$FnDIIQ=&0d&b0(0uM zsF13nG7yaJ?N6!Mlv+<)M)80r0IOdx$aQE$rpli@=sT7)(9+C%4Q)6XNvS)~heH9t6Mj_}Y3XX0dNht=}kqSF~*Kj=f*Z5vR`-lUm>tJ9r! z*%*@)D=jES1l8r99N6dgw6Tcp-2qWOv?`e6HO0o{I2q%#;|$)z2~Vfnn)jL1?UnY7 zJgLyrxdvh_M`t*7IaGbTRPioTSLcvk4sZQr0v^QuhnT7VruIbT`a=9RY9J$xHT;NI zoHIUsqQu*`_Fz{wrEH?H>Ios+y~wfF%vZu$hD(%mAcM0#twA}<`xsicN6n%gVU>ZBJ{!ABo9SuSpUc!`n83 zxI+&pq}ZjxsQ(u<2szC%4a~)oF$$|MU+pA*+EE6NvQk_iHOptnc=FR4x>P ze_VX&ut%(DXSufvhRrXo>q{+zCm$jrq z#CC)(uYsIr`Z&GP?CXml08l>H>yhR7aMVJ24r){2_H?O#Doe)05Mr67$9BuOnrGSegne;Mw`XIc>Tuoo2+6cur!Z)2rxg!}=whJpF12YJHCMH9<$o}Cf zChXf%L*Pc+6)gPgP*m4hf!RLMUuVTmE@T($?%;7AMh201Lm!bRuQvZ1%2+Uew)j|D zD$hZJoyL0)mJq*3M&S~LEV26~z7UslGnLbajxySD|9IM9O|72@j|+}ZW7zulWC=x7 zWVdr7j@*rj4Yl`ej}8as>NH-FD)KhN;#)sZD{Tnq!ihO$%E!*ASs*H6MwWMQlwd=j z3XB%D_*cDuBQGNGWR7lhCTlz1DGh%#5Z%)zX=$sfh&GP|zh<)A{PBT36(y*#ivmZO zdg$DW>82jR%YEZs9p%@lVz&huGl&i-qlQPsY3$2$ zX*)e1`87F%Ca(Tf_1_ov4_G){z=ni>{y*TKe+1m}2*2w5q?L{L#Jo9fpx3>ZoU=2> z#z@=bj3gst#;(-O5M6U55 z+gSqsOidkAbJgFOOOi`upHB~(LIGS4>2jaeA=Mxk*>SJTXt@2H$_UW zCh+O#?-FuKkfpy7)tVy6YbO#Z8#%9~liE{-pUz?vydEJ&xF??4ui0WRj&Yw}sFB_J z6=L<_Al2cJh%NZ9)!uB-1W3(}>&jP`GDAYX7$u+gX&8ykIa5>+;Dic~3pE1kf8XRX z*;@x+_I>17rJO&zI*=uu-(tj|#|N%hM>bm636ZT!r-PK8-hm~5V+P8_rSr%eTukMk zaYn6J2jr}M$-S@;JIIyiY~}=Y;xzY%ntKWLG(XVcJkp+s_%XK>J`y3@t@1;x2EM=W z@=GfK->(Cb;o_i5(uslRp31fjBc_@bNjWu)EStRN5g;xSlgK0SuVXjSE@}55REk1t zLe_imR?_3qFik7dWJ&y^faHcW$h9Pcc+A=Q z>lk1ytnW!3bH0aQEY}3Vi#6bUPP*o&Ckwt7LlLm&rUa1t;E^I1ueB`#DX#9_H|V}n zY&k}K_idcWeQ_rMK+_smAU-b2;$cH56OWN;2H4ExN*v1aKDAZdU9|n z4jqNyg$Q^kGuX)U``oUpd-G5|4;EW?2`hTbRCWBCps2=X@DTUq>BHO>J^|MRIFC3S z?G^DSUTe3Mzi$T3X@&Qkcl@$lEb#R{t<0j(Xu-%4-#Zj3x-IvQM&BqUvj)z&U(S*; z+)FzI+kVMe+BMND-}T__LgzAdwuY9`+8Z0#CCtFUpv-$t;#tNkq?OGfgI9?7!k&wJ z#-B&ZePVpm>8J1I3!laDpHj}}^on*O*^l<9HJ$%aMBdUhS67VGR8dh?7HH6J?BHuD zu*XZo3NkC|6U+X0c22iwk~X>97KM1(5WPmGwXIK91j5&*%`EUANjwkPhW3Cs;-j{C zug&%}XupgQXtn$uPlNAH4)n14tIfsQ#0d`XP?$qPaRfgW#gH+4#oeD!;P3$ORuJ94 z*--TQ8uyS~&)YR}!v^ms}M8oUi{Z{VDb{_1l8-A&xa7A_g-o3=_HGVT_FGuT!>{=WA_P7+B zPnKrBDJH!6VmETr9-U*%rIH!XEgSSfFc5rkcy(f2-$MOu;(jGxadllVTCOq?ex(iL z-1B2R$i>Fo(-YR3{=1`0`o`OzeYcxw|6yYd|qW8_=e3771w-R zT$=iMOH*!>U!k-ADKWt{dQgs@MNBHb`}_Cwv~Js=VrcO{uwYHenF9Qv(>l3fs_Lqg zS@DU9IiqV+f}gI3wANC4PE;6Em^f2a{1;MORsH_dl|!Gc{N|l0z@V(>miurINAP3q z6AW8~Y&-eNn`Y1++*r=pmCP9MM9{S}eE_b4iX&(iJ}DZ$vL|PeI@%I;byf6&`Wek+ z#*V~6xLAlPap|9JO~^H3HaIYOBb*01yz$wpRot@WX=L<{-{W-8K0m8i^}{sE$!+cY zHooVwcNQ!oQ`9Q;FYxDdyip=DTskS{+^vdr@0=d3|>T-7ca(M@dcU0znZYu{U$ z_vmudB@E~4F)x4KAHeT9^ATnz*%5~B7BbI1N zmF&LgoaU}UUK^Nl_wkkG44ex9GS2c3>i+X{0>Ij7T$Lm)^CD<1WONJd*Wm0|tALUN z4@(3yw#y_xKmX5cjJsZU0I{G81F-|Od!%i;sC$xE%I`m>ZrWqq7i9_kc*T0p~rSmDX6#}k$rQn;EZ;@V?D&2 z3Fuj5HhnzrUMFa-g=w~xKe7@3h6Xf!Z3*i%AdHbTxw}l~Y7?}mweoP&hV)^ntDN*! z1&t2m52v>azii?Y-s=A!oMUOaYmYYYGeG_!eTPmU1i%YwL+B2@69041zvrg$;R)S@ za4UMs9w9hqy@3R*$}`e~1+)Vii#Ng_5%CSUp&dATd*8I&awWY}_&)6C z2p=Xc-j44XIs7Y~W!4ZkvBZ5kw_ReY>ZkrW@>C)uIxbmj?SkUqEGv z)eTY2Eb-aPo=u!vfuGhXa~m`dfoISK(&W-(HHj0p_8;$*dgTph{U;*Y`}?ZGA2g=N z%vs8|%n@=~d@>5>_fomfr!yscsYG92_ekH^+q=W;5OT3N;uTTSblF`LF2mbKqiW11 z*GSGKL@T`U@VIv$=b4@1>pHHYBHNy=cC7YV-ldR^9sGCr9tkZDv8Cjw3zWBn71*Jozw9?k-gSa~L>eBF2m1{w}5{J-mE{H`8U8vo~*1eb+l} z`Q2s^o_P59hTyfZ{?n75IJN!hocGG^dq$*U3ej(m5l(+p{-YkYv;1Z4!Z;Ln1F2}N z(^K_^tz&5Pqj39vQe5OYlfH?QJm_5Cdnk07M8?#E#Jdm+CQ7Z7WF{+ z%>7a{4iP>3=l#IrgWwk^&fe5KT+NP<`3ldGlv~=7x~%X0CxiUD19=#NhWbt%uDrny z5#+^ns*znE;jV9@K3^#mh0SfN1n1m|ko2C9c)hD`LG=DVs@^d=vnSXdjx{kSwrzW2 zPt1vJI}_WsZQHhuC${bUGrxQ9de{5)oORaf(_Ou5S9R5HG7o@H*1!q~>U7uhCSMGh zOosdv4x!Nj0uG?bf6u0C?9l8A8Eqp3FT6MI$5769^NX81mPtgEtGbS;n-ua2&xOcb zbn5JbYZPApr_P6Y$LrkADtf~Dvq80%r&oAX{4vifEVuV(s2BZ_{LLZrcOsj8(#i`I zqDDI7{g9FEGfU&bT3Ns%n5_gGc<-{sXIn)@Dz;Q_aD#7%FFmAWEL8j0JJUu_dxaw#(*6li9Xvna{fOrz1ltB*>MeZ z_RDmbpW~G6FXH(8fX^M8*mS_`Ypme25@|(AFsi>}XmCxuSH&KX!)e789EfZ++|ae< z6l#r;eX^akyl=zpX_LLm?eb{&JP=JoKq>Zn600#0R@KH}nP=!MT3dB3f7F_Hq0log z50gsDy7bj~){p4&YYr~%FZcdnmM|9AJ>3l&BFYXF0K1xh9Xf5a{T*2GyvCPnK548r zfJ_6EHR^wQ6VGnWn74r&9`sD${qz2-$V;wm>riTFEfI(NQ0NY_qYOk1qQNcn{7Mh)5L%a?cBn%rWo-4U+Mxil<% z2)?V}VVF+C*;h_VLi3&svi@zpVp$Z~p^QJ~8$~evy$6mq<~mPvFBY=setLU+M^SruQn4=%`z{n=w=Un($7n&{7L#%7!^>A?~HBz%V6fHw#>^C9* zXTi%}@29Xg)Xn+3QR6MKNB($6rgo=HIOISMWUK8M~TdnBzBK!+m zT?vJv@y*Pcae0Qncj5EPuo}=oDH|(oUUV0xU?BP3VpnL*j-uR+_mJm&u%*vVqLB`N zE%Kp^tapM)!~A5C*O8qXTg-5O;dKwnAapo#jwqyxk#W1%7@Pf#>`HD9In4FdVma%~ zP$g?I6806|QlaDMT&>mb=?PaVM%813Sm{SCH82Wy1*^1Pw-AF(WLzBBgAe3E6TwW@uY5*S^hD&58TU`l#6 z)e8em^=>-Sm(`Pda|47!kUHlo(r$6#PcQFerLV(1A6s1uvge56_0GyEa_o|ab!}AQ+Mj5v+%PrP+|XVp?%&@RcI5CD?d1NOT>MNW@|obW98-_1 zA9pQqu4(9R_$1cTPv>i^(Sq96QEr3Q8yp!^FxVb%W%Ob=o|?!v+x;Ax12O2DL%?+dvW@&dmHV?faCOAg*A= zdsEcL%NtaIeBpB6v50|S_4^r~C`@{LcOwZ)w27}j?qq&X~x+- zZiG{+^`pG{n4yeT^3fiiW<~I%)hn&13WL_D)$9UW4HII=r{$|ttwqf#w^-ZzE zizVkwG#p$C^P!s*w!6|dR(G1pP zfAGdvp*E>fA7*t;c6}D?8Y~{D>DOB<^Tbl8>D(2~vK01eg2D>(%(%`0n@Ny#JeFw3 z5+@uu>wJFwa|9n1uaDjs6NsEyAUfd?*KbB*_6OCY&-x-f2n2?0Sl&B+V~u?kM-2;A zBzkGra-}1nA@NV0$qSn#vx5Q}c7q@|)s9g7N`j|d$? zjfv1db^DVzeJ0Tb`|b4NTV_K?k^?GS{yTxwC%Ep9KZ~J1qxnz%d`aA-64jXc?X3*A7P>Uv zF=mpT9J!tUY4i`%r^Nz@gIsp|{|L?+6MsE0p%NmS`7W>C{2Qbn{>O0OTMK6_-rMlP zFW$B58hwWjhWsoen|dez&Cc_ZhRvN{=&ecTc#6b!+vkn~_NUY|dSYWS2kUTaJu{sO zhNLP}Z09cTz0gs6F>JWrRZk_`5E6^zZl~79n;&)0_9MdNg=# zV?A=RUgL{2&J|mcWgNMCh&KQ{BD@|;fqc+;--`k)?mdkcRStCFVU$btRYiwm9@OOO z<+#Ko@gy@u_}BWcmazz$IqQbVG=0HWO2pir1Vv z1pbKGm;oQps&ub}5j#gq=l?12Qtp1S1S84l!N4cZqvD>_TVXzyBdsx*G>&uT`4z6i z%JtV2OZ!W-E~?0X*I!W_6lH9g4h7c~>7e&^o%|J}>@i#s+Oe+oSiG&r%CS6;D3Yn73-Gy^KMkHg{yR&Fc)UcSW49untVT$1%kh z8Skr4{{K^xM`JNX_@d9$(MZQyQzt8p=P$QzNk-Bp$1Uhua|@Dani3j#;>D#uplk!) zH}BL~&)}M#CvsIw;1`6Dk7SK)EScZ&KmX1UV28ywBQif(h5eX-gRGSnu6~z| zOcS^i%{#Qzn~XS6+js(2AWZsO+C>h}b}>BL^+tXEey#V()4ozgK3R+~(0OV-_xx0N z6_3G#Mf!$OqgR{SV}@d8Uc8X}45o&}aLS*-@lJF@{~_A(TOES*UeG#|nOD(sN3?9qns)hd#JWcQ1<-1!UAl3-9vT&lZ4_+Wc#hQ1Hj&__a1>1wk z;$B9`3rKi>#V29GuzSg@rEWQ9I3WlsudhD3LtR;;nZmLPbC%tZycx?9F51%bW_N*` z(Ed%GNaUB_c4YU;!U?lbR+=w*>vU~Tx;eYYWgXYXlL|dr-+0w6FUv`g+zG0d;GPeM z$KMi;FAENHYHq)=FV{UeyIY;Nfr!;f{>=&eyulv^G(3j=UF5@1pm$^5%Ho z+4DMBTj6s+EBh9i-w(NYbJtMtZpdR7epqvpD8$w6%?^w)Ij%ekc!kznZb5on%3QpR zY>N={-ic=S7UMRB;e89(GqxgOcfYm@DBc$AFP93rvr2mppU78_b!ConL{Xi5N8@ z1LW5ZzoV>mhi@H~WE?v3xpr0e`%8_|SH3#oL>D32FRf}@kc;!aN7RY%JtDG;WsWhj zz~$9y$_Kf)z44wd+Rv`V-x23pHI?*xB?Rdp#I9IVPsw5S-xuHJG&YLnUNil$@NMh_ zFX2QzO6#r6TB|CS#>(yj3-lK2+v(;&^h%4!7fo0aHal?kjY_@&Yv*$f&X{+HHPFeG z6AOM_rXDTq5CYc}t1v=-@=>dYJbo}eDnpTHOh&UOGy7qe&EJckdS!Qp_=hFI-u$Ea z{N3OO>8eOht-#(n2wLC@YASGILkdSi6Y)*;V(l`P`2j?l9Lm>8FbNK9!RonhhRIO>j3>bTVsY?D#a6|7@0NMgtTuf;*Tk67Ty-yyQ3j?{Uo zsU%ROF+=munr<_1!L;8?4!3G_hxu|h z<2H@_nN!m)D|;L-*spFCWZvnx-pu$!efeeI7ZI59J-RL2L*qOf;a_B*+s5jp7|YtI zi%RU+Np5xei!}1fw#JM6aUrzqEeErCiB&ZEIDQw) zeK$gYuUQ%vnT9t~*!I8oF<~h7e#yFBipOMpeP1zKM*lc@lg5)G z_Zj{~x(K~bfJ*u=q1WOpSg{6Rk3!GZyc%@=;6|EmAYO_S;yt4vWog;QAssQxww)A3t#kEu1srv#jnJjYIP zm#M)@Bp#2`pdK9K5Dn;YCnRCcmS7gfi>2)2~`S&PuFl0%~GQ%ZBj@q7pLPA-y@EHJgzA9WBch#8>@SzQKF zK6RtIi;Xn(iOXns&K*q5QxaAHiB8AxcllzGawg z)VR^7ZNy`Z_X=Q2z0Zvc4!Upf_7Jcw)c=SVi{MNl9al9zb+QB7*70I$p-bQV(k5 z{WrheB(C)ZO=U;7@xyW#=iQ) zSo|8^rvIx2APxi4K(L%_y?O+d<$yc23vJTW9y{|zhfY4uIzGHA?x_-5@5H7<7N2a} zJGo&VEoJ(>uEVnYr&n@&Ez?_Wb1ICztJrq*u0rD^vMdzx_ZDXbCgB-B?KAA@I+`=&_({krzRrmDY{h+b7$jU3Lb~V3k!h38qg>!M3==#0n z%8@YR=SKuFw@e*V$X9mB|AWk-DY6f5m~x~T7B4a#@Tn>!uu=Y98u^1Cw?6_ znQsOU^Wi=R{G?B$@Eh+9<{Sj+Hb;Bf;?+k_?ZkMfe?aLOl$NDW-QER&6Foazo!B9%Wv4pl;ncz~2?T7ZhWES0Ag^wrEJH930 zy~6YxQVO_GqEYF)!C?kEIOzD~aw+<%P-i*Y!V>vpyfr}BV`v)kx?P7&M^%U>bk^vz z@j1{HBYn|T!zMty=}HNeDvJCJ6*w33Y;zS;Sk4i^oLlAv)mM& z%jz7&{ehE;dZ8}!*cAR%_n1w6`PW!R|Es+^E`uhw<3_LzjJi6#z3t|)r|!UDYLxQK zmvnu?aL`I0(7dkT=#>bR2;w2mFqfu$9%d!8Ou>$GGR$%P!ET5#mLh2lQM~0ccYk$q z?y(r^w+@N8pd_^w+r4@>X&j*l$o(S)1b%7_YGxc4Bkh0e0T5L2d_?E&*CAc|6S`o? z0GjPkvr`|f?(%guxC#5M)wt`+ZQJoo45NI(UZ8l@e*Nab^=6D!v%wZ){0TuLrdt0t z&L0EOsllWr)5rY^kudIK*njo8F+&bScW&^7U{Sk#M-K|qP55i`8siO+(%&?SVuq=o zN8nBU=DqfJv!rCvoXXESZ<)7P?dd@2lY=QX>0@ngk4jI1XW*ugKQ;|fygr5xjJsTX z{T-As_2Pt&2PTs^%L`C3Gh` zS_h$GSJLB!a`T43?GMLav_Di}a?a?nz58X`o`K(K3eoWi!j1ku(W}~J;NuH-?|sY_ zku!fr48^kNU=A0T@vrAqD%efMJvg0x`Jbh zWHz^^cB-eLkghga?N$A4*VFhS8eE)|gETwea3p&pRa4g{UV+pp&tumYQ1{_#%!bCE z*BKa(T!*mWYUX+d9{r>dz^|HZaoY)4gc{=tVhDu{rn{@eRylOFaZ| z*1TJtI1>zKaGl;C6F#xO?)39s5~sN9sAU6{zgo)CaXw(?3;vRvPd1Y({`o4`mnU;UT@PeL=B>R#j-5&Ch6R@N>z%je)%PHRNIn^tdwQtEs z@$P}bb3j>eg|}~c5e?7tHmR$&jn(wkk+8D*$F4?P)ZRRb@KvSl!v+X=3Z_T)(YIS% z$~M>56_sn)ZL0bM#pBw_5mr%;w?49=k&Ma4q69=L^vWvRUg}_Qt?1Vl*Y|}D7OPC= zU|qlfgA%zkhEadIdUVyzWD}1z-mR|hv?y-qrMTXM1dN5yX8g{bhf3-CP>3F^t6hrg zJQ5Vx|C!J$Q7TlI728lzcJ0Z!6$v@IP{~aiuFe#vqvN}1K*=Tw7 z$PO-dXqYpnp|$QodpiR>j)c;>u9l;SA@2IXlpH^K^<;R&cNdS75$_i*Q(U~=(@kle z=gxC(iKpLb1A^u)<`BJ>H=2|g`Azf_hdz!N;L}$XfXF>ndo}-uvdxZZmNp_UjsfosmMOm|;imli` z;+#pZ;s-@)HgO@o^j(axy$~qhDh_?QlllC-2dR_s-A4|ZkDO-It%y-w2GP7th4_t3 z`k9|K@TGw(yCe1%jE8~tzs^E{pv4?j?z+KFn?b=wwpjUKf5RSGvzT9et>+~INB0$D zTwUPwk$>gm2+Mw2N1%y1MoXB{317H4y=|`&w8rkepL?a+JE&GsBe&tgWYLRWxAjF+ z6v4?NWv7|U;eNTAqr;h9r5{jdrV3w{>=;HJIdJrzz6FTYeg46N9LCp)G$!Nv%!SWpN$rO!WxCR3Q7E-)Beit7Wg=Q*-A zvU(u5NG9Y&mOe=bJlP`;M(cm_m5RVg?1giDt^ct6%!gVIWe%}E3gor>mUGP-Z)<^d z@8$r(PmCZn#w6dpcNGPT@exqE35r5g`(J}x#)Rnvjtpj}@<&P^j98ja?`uFMto#0x zZF{Jb@SDD5%lB4rVzQtl8H&d%;`q)--bWidLfbN1k_K=(E}2d`P4Bheb;& z&Yk%pVNkdh>C4w?4sWKoB%6M=om_UXC^LyQ$OWbO1t`iYl z&R9(OABm}*@A?gUhFZ9bKk3sgSBLXQOU8!Yk1XXbhp5&03pqC@;tTgrm|Qk|pjqvZ zM-G7ck3HIy@hdhLa%__?aqk5ZEKTG-7_@6m3iq$!~as)oRiC{L}2{Q5SzOpNrRcy2NaOmK`KDKD9hyz~+a_&-h=+clz$tO_1lY`3pzz9||)^KXCQEU;j5``6@n z;dr}nnk_!#i1jh)BQzIoE+7T4Fy<*?-kdUpcCo+2-3^P@8427L4c7EFm~MfQo2YK| zyU%_rc~Zbz?MS=T#{CS}?<{nfIo&}n@1)WMebY;9!=a@ z`dA(pI}_FpVqY94!6%RA$MP6_z+}1vBzfsgRy2w4TmTaTR(Gfi%H~kzWs$ zXB$;A30JG7CpNqL;P}vAjh0P5Ro;!lZl#lwB7t&T`f@J0#B^CBoS2g{pX7&B5~#GQ zfWCxIi!*GVz6m{VFRn)2S21zHTKl#OZQM$EWJy9R>Y);O8qWUFzF%)Zmt^`>h$zD2 zIgVjRxj4;gM!2w^P%&C$?~v%;q%Rs@U{|zDweb)z97O!W$h6pyo-Co=JOYk~0Yp+U zU~g#23CDuw$kuvMuE0W6`v^ozcpv2sx;Babf!EUWzyRh|mLyL}=VMQu`hO7kuT>E> zK^2vvx*BxsKhSXMDg5D83~zE$!D(sAi7OmPPkQ}REc)rPMDTt^;`vep{_@**nHJx0eoRC-!Us$eqGh`9EJgV@&;c-PDvHhwwl=eiQ z@D^M@0-5QuvRYJLjv_?O&yV&3J>*fXtUaQdW{u~*HY9vY%9Z6$Ga0#(-{(#2kLRar z8q$XTLhqP{XPaY~RJy+SI9~kp6N?u}L-0=NjeZ#FdIxpRvI`M_`JRKEUd6P(oqWRJ zXHsU-6>}t4-w?^zAph;x%>}XDAUB6wVs3heNs=Fs<7OH|ekHaBw!|kwtgG8ItOIez z--*R309;X!K8JQiTgU!}D~Kd^iBh4BNj2Ii?=;}gqp!yyth%+;oIVAbaJJ~PuR2-1 zj$j&E@yXZ1QJEk$^P*F-z|bGC!qn`G{Q7F*SfV8$tMoK9gn|DYTMf`nd;C!)YEE%; z!42fJtM7a{Rr;*Fr1DrLBL?Uux6T7q$=`d;46Jc{3^;Kx^WMdNq}vR1e>Z`>Dkrg9 zTt5G>zy_yG9f?CSvb9MAxFB5kI|6Y;`AphW7b4x(;2#}U6Y!6NSmQ#c+%i}tVy|2e z+UytY`;Ors*+tLV*j^9n@Fb^M<>?%MSES&(S;4fz&rllP!qXbx^(F3S@C93{61g?? zTkL|~x8*`ht|Kk+@I*GyU>4oYJD%putSkiDl<&*E zN|RSBOgqlIoHT+pXm-wI=@;=~Ao<8oKHm_!T#j-Y!y&7qkfPdI#RqIYAlzp z;jGk^0RZMW0$d6Z(OIK?wkGdu8fx+_sdadn?RV=(pF7q=h_YZ$lIv)s@nLc zVT*GnF=Tr{I7>K--@bs=E%9|#Dj2JSn3=@>K=l>M)2nJr#}^{uTAWOHlfC`JrlZFN z_Ird|#^)!v^MrT6uP5h*6uxM-F3He|-T;(Loys&uPe`Cf6Z4z@%BxsjDO zZcRR~w8b!lpBsa%UDYuKSu#TQPgIy=G`X`ayIk8yT)!Z66Y3<^-g)2n(ngoauI8Cr zNWB1GA+%rYi4%kXriNxbR4OHyDxp;@m_U-xcPhxImihhBsFnnFg~EE34XwKhG?VD; z0h-`FlJoX|jtdK_updkrVviL~b+IcnVLYDnSJL-$rKcIXso=!hg|mbQueb~-pKTe` z@UHD1@@NOPW~foru=#6~6aJMS&`@1_B23-y0ig5bHPc0+NDIj|cEqDzN89|=!TX}) zkXyZ-lQ!o%x3uj^1q9p+6djs-T+c@C@K*j(+L~W+D3?#Xkxx@@=iZ07=WMuR+k63? zj_el}(%z);Ufc9@$XXOQc!5)PS$7s+19+a;xcy3M)0V_mm7x>sr^Gcth4`6SZjk+b z^c+lAlv5gpB-3oJ8=T2_UVdW%LBwYCnCW*C-CkgVT+lPyKI0bm_pe#n-QB%GSCisH z#y?+qM84A7cdJm9n;GX^!IySi)IHzc64A>Tx87L$-x5e>;}u8caDP>=qKrq{DDTdD zq4E{tYZIR^7%@>Ic#o8#C_;r&m5%;qe!s->&6WVkFmt}+(EsvAS>N_B-P1hJkg+14 z;qk;IcP8I9#e^-am+9colMZlmO8o^`5UzMPAYRQ3R%MPffm>mcP`e|2YcjX%-C?l6SD<^X)IG)qF^my!PsoslT4~4BwQb9_Q*jPB{}#` znl3pL9gmWqU|G|oH}k}ouO zlYFrZs1NVOx2DdXt#~>(ysWCoOtReLPvK&xQ?$ZeF#1eKh1pi7-jAdNFN>eoFnf^i z{nr+rp&cJ?L^jn274AIa&v?pvJL^~8qL1xgbNVE&l-8l>tev^@uHY(n?I$0{aEWd7 zlBQZ?#nX!U_&gQA?VCX2mg#km=4kheQw4KHb}oUJcp{7;6Q&w-Zu>XuGZy9B^A^+P z-xAIoC{GyLPGTpGzj6JHY5kWBQZ>!~dCv8f=sdZJgK+w9FH(b0&E6#Zq&O!sI83xS zMHEzUcpRC#5;x=-uBm|8pBDaxB;OSfVfZ~wu)AH}QC<$+gKz%9P%p#Z)B4Ym+g?y) zr)*j?vQyY8r`{5cBO+=g(M#QrebfAZZyU`zK%~z6(xVa9)|O(m7+F|V)RbCG@UXi% zgQpi(Va?AXA*hoIa4kJwcySJRgGrRr^aQCsRgHrDCGpKOt@6;vezazETBbgHV;#!L z+ScB;q};?qg_{>}gjYu=ClvH+ z@c)ezt_6!3Mu&PVoTjqaCGg-MFEgF6DvN^se3e3i6zs3aT7EjAR8Zm&<~|9I-iFE+ zUv}Oi?QCB7$pb5{^1>9Y%(XtiwJR&zL*JnVV32}0j$|HM%hT2wd4VnZGB8nlT(Yo) z@(%Y_80;K7H-V3>4k_xdfy$72EOd4jqt&EN$X6>HRjsmwL-N29OTO&ouq6OKXp`q; zVy@YV*pi@1Z`?ii10R6(@O?DmJsq3WxUsDf-=_N}M}8KP2I#7Zl=O88LAwEWL~`HY z)bbfKs(FJmuF_Zt*wDN-r+^FTiyxrj^F6Ea1xq!5DerJXk-EwVT-BLJPy~|Ec}v+M zOujrJD5g1xCO_Qy`M{WO1Km<)RT|L30YiJ}Zk5ma6B-HuL-~uY#5xTkegT5)`h*i3Hv5${!KJqRznrn<)P`_5wxw*2jf%VuDE3TppM_vF{Olb zJXj+GKH?&yy#w+t_Fyx%5GK)RH9>n21+SL*2p*GdI36$VNcPeH(gAs0ksmYPKtvRh zD-HkO?`kB#*Vn60EN8ZqNgL_?k4IvOFz#MjZTA7pBLu&0g->6@Qc(=Ihh0Mn**`X1as48Z932z+S+>GmFHfa$YsCU2|4-t`5@2D zGJ=|+);m<~O?oB`Q#Xcfb;Rh{;_%Z~7FpiDB83n(wZh~|^-e-2x@epQ#Utw#raZsG zEPBBMot<|fhzk~MpzaGLsT(c)sNQC_xUfo=aYW~Zhg!9%XnG?(*4rb_somXS@0`(9 zt9J|WVBM4aI}_5N{pN1e~1<>9`k7;DW|4FwHv`k=>A=?>2K@C|m#$#Z-Wn-u&A`wXu zAZod!yv}(4hSXw3rpSP5Gb5@x-@RwVCeS-(f@Np3bF?|J@s(bCMMH&v&9`DE)!jMn z1H_0<ttwTgaO& zP$W7X!x-^TU%K%1;M@{;i9-BdhCU64r#le3gljn7QR(Pugrwz0i)nIPJ}BNrf;tTm z2PXNS!Cxa#%1l%}T@%souzaTtMC9oNUjnYCVlODfH{^aCwf!I;ZdK0U(jW46}y@pe}$WXTngKuURqcjiLrXmLW$4kGR zs~|2VeU-W71fB6#xzBr8+;lRj2L?0%9HjRlV1G7zMg`#DIH?zL)SPq79!?-*X3>G! zm1_=fwI(WCjoo^jV430&#=w;vuR(>j7>$@Pj-y&>Xl-->>64H1#>Pv0|G?o-G)1Ew zRk^r#-`b3ODhbd)@azrBPO{bCKxvo>Kcj7F)6(=M9WS7BgZ3DM#&P2uVdIXI4DH(w zD!l`fz6c7VCi-uIb9xmp?3C48pkkH3o)h6|QU6WVGF)6Ny0C}C^94JnJ_6bP(`Gk+k`YBh?61T7uU}`vP4lwjM??Ew~KLUo2lNCI`mkp+wq9(qj?O)?N_FXMS z;8EMiOw;ZM3m1PzOp(@8jgXJ3vEf>*XJ13hFS`Mn^5?}{7y@$mKIobEI^o8rxWyIu zgms5iShJ8PI;_|#<1kmU(#-$<3vStyOINP-!SkLc^Q)X%tgPjq-F7cwE%k^ zU!cF-lq`EFK}4DMjfm5`USh2jkBAI}FxmcwnAlWn>j0Om&!0q9S*Gy&Cx$zk+NAc6 zC=5|usJzXR4&YCUB=MV!gJ!GV)jamUCCZ&(7gfx8OaEyH3xAStYbwcwtF)Fl!~Rfj z_9PwsAm6pKCO11XWV*x=R}=xJT>m5)Ea$bq0>W_{me6R2acI8z^%?>k?DtAc>-K=g z*WY1e3~7v3{`H>6c3SW>26XS@WRdrD4KCYH9*q`2(R=CIgCqaTFKM%E@+ zL&)=TRQG$T*)9JP;s`l#;~ zCVc&l&ZDNR8rzDwrRBJ#HR}H%68$f8iwO0ZuI1#L*mRHPSjEL63Tn7orke56o*t+x1tIm~vZ|8%FAz58;&%&XN!$j4<=Pp35Gl z`m&xka$Lb*KgV+>v}OfNNq3)74%yC;)XMf)Uxy#w;7UI|X#2?J19^=YF@sg~C3u53 zbAO%8!56b3Y+nMvYV^0*eD~vDdVXYZ0aIx1F}kzS&B4Tds)g$f;Ap}AUgcE1^g0}Q z4{y-^QEO=IJB3gwXQQPNJ*cZBcpIFd?tzoMbG3b1favlc^kQW?Dqu#S78PnS-uzBI zQ#aIxvr|@t4IKG*vhfAM6_4^wJ<6Zh{LYfg0ib6>IIoBZBaO+l@wh7c8$URvECr{g z%UT3|aVvwVUxwM1=xX*|Z{zP~n!>6~@JiBE^ zNvAbMc5oOn9LdGGfa{unfLL3TonvB;u6@8rBw<{iEp(|lmpW2(4sCB1fm20-dYn?t zxpYZ}y&8D-pD~@w2%&L+d7VR&RLb^~Rv-kC#hTuy!JJX}{UH(OO|F0AHD%g|Z-9Z8 zpu$5gm2b;4`-Gy?29=jwMa}xiYM^C~h3JY-PscJ?et9;>BPl!v25EB?h)WQMfrdGi z=Xrr$UGMJ2V~PL!IoX2~OzMpf-%29+s=^WIoRLjIQbXwJmAQu;)mg`gp8G+J)R|WQk37eqx(1YRfeVW4PQlmnDH-kCk*aQ@e5v;s3oH3QTQ2IG-$1R>=)cu^_#5^&YLP1y)j&c z+4I_*+V_ER(3z<+=}{A^WngLwd_|)(l3|xT<;?_s`{62Sgm(O}ORhkCB%+n{YRz@B zhv3AEXC ze7S3B1^-(h7)KJLM3Io@zV$bCJ$QO0mzKGgDWvS z!m|>xU#-YjTcFTP+P9%m?gKcl@Q-Cg>LiV^L0m0ES(!pvOV}9NW_n(>*=*@ky@~Pt zQWOtW6tN5ZbGL%X%}yh>x`F7Uwt#Pc~yn;G+7ZI-n%TP}77g!CwR< z*ab(?6qgYgR}6b(cXEp*>Q#&NE>LwsL}nc=Q#+{ED?Q|3hXzp#4*ezmbj*}vkQoee ztJ+@#^ueCyXOzF{> zB*i!0N!&UB2C8L#vU)IJioL=x!P5=K#Rk!o$K1=vtKo8F+*S3Yn^SA8H4(Y3cV_S| zp()D$k)GrV$5Z`p4Om!EPkv_xP+E{+M!;$GvF!g$!cdp=M`|CW`Inw-VJeB_@JQmx zHiFY=1cPAL;^8%WA5|nFiRZ4$%3=vh$|R-VKRb()792ckA)n|@b_xV?@95k@ zR%*?Zbju01Mn)DN7Zp*958?{iHqHil)AsKSZM;*p=KY^xPr^mZ!89QPhm9Th1V4k( z)D`3U%V;6`9Wo-d#q`b?99hxIb$LtA&GV%3l6x=w&uX*0FRTc#iu;!+F}R&Sqz+K z4@i}8qD*BhI98 zCfprld;-AmdwBUS$vDo_Z+-;^lp}S(GR+>x zc5-q&|F1FH;#|S7=N2hu?~QM5ZRV= z`$#!;-Rb_z*pG7eQECA*+up4BNFsXdbBw@{x=oUV3o<>x9o(Zof3k=0@9i4@Hi;F| z$BN;fj2RQ%-K2Y3*d6biWfW96k7<&DQ{*5o+YmHMOFtJdsJk*6!NWOmif@0DIiVPj z6J(4(^^I+X4&p?NYX6AZLp5~OJ69sA22!%7NPKkvB{`H;7b;}XyjyU5K$BW9M@XrJ z5$Wn=PkV+49%kCnPb5zziJQU=Q=wd`nW&*FBuJ%FA6eH`T^HCF;h?;{_-p{xiY7dw zCf$xlaIk>1!86EG_-}_J?w-1%sz-7L9sEzQj*@`I!iO80=1nit>8KWuP;*s}u<}{U zjVJfeqqc@RzWIHJ&ym7o=C9$XO4G7{KF~ikr;}EuV!Yx{dt4CU8k~S8lpiYO4~e3 z35xA+H`P(yqe$#EJknmYu-y(uqKJ)WJ!LI9Ld*6z)~4K&uF2NM0k!*rXTjMdX0O;4 zU(^vu!d{dcU!?2HZAhyPyy*b`YG= zdv`_kSMnUb2puBfy2MHGnjxv|KcuSm!bWk1Yp>Mmx1yd_$W52IkV%oTBB`rD@p6R? zfkY|O3nl^eSNW-yR=0e-Qo+CfA9L^6Wm(sCYi5QrY-ZTZux;D6Z6m|BZQHhO+qPZ% zzMu1)I@Mae^|^k*YJ2Xv<{Ik;GA(hllk=#t6@DyhP{yu;iW5`*mR!gdNCls z8CKGGv}RC+;4D)`)QV#t($5w08R6wy-xz`2(^sNwtq{6B)QnH{ye07!2Ie?~dR(Uy zD^rOqgt#r>LSit7F;GQmA=ZSSC7A-VE8axM3lNNx0&;5#BRpTAsc03lN$=9W;@4sO z8_pAK_$OpPii^k+E9sd3;5j`XpIEnGbdp5(F+h!ogKA1JPipYpHTjzo4(Z;(@}C0u zS^1AdpV4rqDR=s)!W;_+1~4loIEHh*I=Cx73}%S<_y8_51T_rb7C~n|A;_Z@o*MTp zKMN$Z+x~w{FMi{BiXSUfN5aHfzvD*CEB3_y@r>M56S&Rmuk3_pXLrG+%P2E8%mPD=WM&2J@O0K-IFbgNb9310tZg?e1qjzO z&FwCB%OF;)*f{P14*O|H>I&-K{o*B;5RQeiH8qN>6dyG;!qJ|OtSq?e0Eh+YbCwRh2x zhAuc!3UiRK)=YB`k7kZARNNuy@93Vuid3mj7|B@CN;N@VE;hP4#5%bl-buC5j#RO{ zuoohej6Mz|nV!^HIV2r4TH|-N?eOe(ba(n!2M1I4tbV}a!bRjWkr|R2-+Qp^)S09R z3zjIiS1j}S`69Ppo$d2RI|N@_joBNuUo9&JtM?N0TQWQn?}!LRFjr#TBGY&8;oV3q z+aZZ?1`x_h01-XJ-)=?LjU8AI$iy2*@&GdQB> z#InR&!3ezS^C*w~hDj|Qm$(rgS-O(8DJ{@N)O4_Rf|_L)$%w>Z`rZ(5JEKMyc)5QO zPMY8qWzh8afE&JgCHnkgh7Dx+{jG5mVkz=9+QxmMN$co_>(gCmIQS_!wkv3dVoJYzb4f{_$#sfZ1;>6pfU|T_uMVnm!&EDo^NBvV(nXNn9z=( zIC(w9bc!vXTnVy|*AdL^$9EW3I)1O};w||$cF2mXebRS5Ovo8ukPs&oxoHa{Msz+S zSyx9NtF(2JCe=&1QT_7%A#jkz8kKk0at4}oiJWBMlY5sQGAicF<%P|5i%lm4cqiCF zNxzA7eiQr$?oms$lt2qxqB0}}ya-cjeM!YSb%vCu2`V3^Lj8NqR8elx+!>kPws*Ye zt3bspku2d%V7=HvMjn$r)6slGM7eag;}C&dCC|Y{mM`_K8mO0|Oc=M9c=8E?BCRKn zNbQ^EQDJWaei%jVY3-8nR`fTSGtn(1x{3qy7ilF9J7UDfak@M}`AZ)Ya+|-}ctZo* zl`3)+5bAh#Ao2Kn9J6^?yI7%KytO=0IK%uDvH+qxG0On9_N&rG_Q59;K}(`K{Qq<> zjoA=!^pGb|ahycq_MXkf>UM|yl6!d=;CYciq;`s0!vy!a+!7btAVzjyhU7{qaLzZ~ zSNPg6q_U%2x$Bp&n<~K1=eIZa%j@yYH`@}jBWcxppiIsZqt|nk%fGqh)4FmcabX#m z&gTUyJ|H|e$m)ITV?|XatALKuwWr6@EkQT&aHo3r*5dtGQe^DB#>;zM#1M6rk`Hu? z@(N4fmEbE$Yu>beqlLND3^1G?X7=~kpRy-YJsaR zNK~4nb#lc}2>#8&zj*h@Pa|mq(O+b_!=o6-_2JT2B(Sg_0=6C9Tp$@2yrMCNeZhPG z<_^;()Zw;g<@QemHf3hiHIb($sgkGCJ|qkBdT-V)q+lH?;qqv3>hu9xplCUX0l2JxAWc9^TR=doI>EU+ zib`@=KD-(L29D{G?gpc=wKM})W~GWq_z*&-2TrWus&SBZ#aY}A=X<_u??%lo@(Fta zJze1+4g^Y0-6E|RW!qcvF%7+=(RMWNLMCeP?;ZrUN6TD_Z6r$BJ+=*zpA!>Gy-OJ@ zR;RPJKcPK&eSwGjTm*f;05-=)LRjXwB7i~KJ(pIqlJ{jK!H5$_9Vp%zwXEO@07ct9 zxL(74n6FsriD_S!aa9_YNU&Ru{+%8E^{hS_0aTc6Bjgs}n#EL2^OtU#{v&3G4*UI}i(3GVN|E3jZ<`#}% z&G6#9oWAisW0-wBa{m2xODGr2lOf6GCCBKhUL4rIP-? z8W!9@z!HE*f{Os$p*#x@?(n9nQSS^Tn`7bY`)SI-w3ZJ5SR$Vjh)2H`K zY~|fj?!}W;L%#LcyLnzoj!(sko4XAkfcvY;I)JJ+E3&EatxVZp8ScE^;xo$#KUII1 z2FH!CCrK`WhI%GPy=>iw#{7Gsg$F;Q(gfIEzw0|qs6`AvlLr?QBk}?JSCbK%+Lgs& zuuTtQSOJo+Nk3}4XN^Whue-n`me$E9W9zwz*k{)surslSQFd&l+;rNNYf1;BXq7KU{YxmIuojo$D@#>|(zP{YRs zqGw5RU^shRE$!h%U6FCo9bcf4)->pe>C#8@O+=_9?M@M-jJkd-P5-QOO)`(qU@V% z5a%`wYK?pFr);mPQIR!8?)8uqD}~$Fi5 zQ|yZ4*Lh7R>NPhUZQC^RMG|L)ITAaQ;TIclunEhCL{QEDAPtbVF!Cj~ab;eej0L?i zsJ4m*KP9n6U>SAnb*f+;JI6Iilk86cgcanNx=R`Pjy1w(*q&IIjDp5;S{F>2f@zeg z-~xL>)1IAi&y#H9_jMilg=1ncCo<`_d~#6<#4mO0Zo^&!)uU=mn zoMTICggA2K;@#;vA6v00+R;!{xCy?uLkC#zJ0g>NzTNHg9da3buV*}yYI&>p4luyf z6R`9ypHw3#d%p8%yPM4b=di<UpPk+VDO#uJ@q5xD;2H3v-k}5&`sgRN+PogV`^{s~G zTc-*cOWd-B{(tso9LAEbyrYyWmx5!_#ni~!JVa4VU26_ZRkP%^UlRs7f7?hp6R&yt zt*xn1Ab|Z#-$7tt0=NEFh2p}ND}g7w%Xg8+c7@`q%h(`OFuC2@5kx&k7`SB+uE+Z9 zX8e2VQ{d%>ql@0}ciZmG7l(|G@C!%xHDhl*Pv?5D&?&U@{$RBK{}%12{@F)-gn13m zF#vhMm@ePWuHTvt@>X8vAH$@7Y+eQx))E0DwKdtJaDsb2JniE^mW}ZKZe+i5hKk^X zCKvx4J}9wOWVt+>+a&*@qQJLTb+wii&#%I-myiOaKW(=*N~>xp592}S5d z7^`_MANf*7=410Gg%g|S4<>%UBuWl6QQIUEN_g=G0 zMo4VI^OVW)^Lr#~Am!C|E&Ho42L?o~TzxTUzji-ljPY8>4r$hCi3OI zY!%Hjoy1(vTPk1=Gq~Uc4hZSZEj`_Xs@q?1`FQ$p_SAll$(p48)K@p~*yoA*^NB99 zR7v994|Z1xeEPO)=r;x}{Bso3TX)#TVnk+KXzrKZ377AQM%#WNN^QHgSppCxi!+Ry z1@{0`A6(=pcq{Wrv%qLTGDRVzi4P4V6==Z+Ey}gVcIEv=ko-LPi_@hxQ*UMgUuo>$ zqZUUWh}F^3pPhQII~yL%RaJ@c`(mQz%jfN2$5sb7?Ukl?d$gR1D#!3q4jQb_$-jIB z*7xPF(4+3hSL<0(o-wxP2o*yU%RdSd99WyrNavXHt6F;~!d~MKuvm~!B|_Ndv$G}> zBFjDiCzu`-P-3sDkY=L1Hf+einp3!ulzidG3_rdOHMT?vn@&ndA@2>@DO5s1d^RQCn3-X zk8G|}-|M!v?mezhi*yEHkPpp8D96h8qvq0}(aifG!b^yu*fMeCRUP{U^WBnh^-Yk?1guDcSVnc@ea4mo_uwpy6f>I5-PoxE)SD6dGvf`M z&yc~%xCJM<&db-YkO1Qs3Anh?KUIi?wZbN}9Y4CJH&vi#>2HY=kG%IYeY0tnaQteZ z-tT&stzEf9Gu*D}21#R*&iDZ2xEYBPCPzMGWXqf?(B(!KwDGr9Sw&PQw3?hMvJmPg zr5KXVU__wY0^Yww1<#UVBn-#zgn>i>@OV8$ZrA5~a}ybC$6VcRQ=@L)Zd=Dz<))f; z_fJ({^^GhzzIp*LQM)%E$6~HFblSMwf-R`FSG=a%u>95I{C!Rn^^(}YiS6H`(@xM- z9z){J-x=ZW4p6Ps>N<~k-;*E#Z8dwZ(JPJCv*<Ef?)Rv5 zDn6l%I|82moIfx;dd=^izeDI~eyJUXH|;BOdTjrVSD17)x)3@i4|&Hia7L{ofwwC5 zxV^K%--SetZ_52KJvv{5`<9V6@2ol0?cdJrU-wc?&W$Y-I1BRIhLLan=8OZQQW(gP zBAQD^{RsR6D2_~$^KWBc)ZDRf2bh#V;v>o{#Cj!fR)f$99L+jZ1-{$0e5A&BVASWAb+u>%ll1!MVU3 zOgj$X;^>~{**$WM`L^Yk&+yJ47cKW9F^VU+-=U!shsA;Gd_h_+pJUXDCpe$JqlB32 za-eP;T?WT@jVX5#qSjisEsr*iiRZZGRJ$roe{=*!N1+YV5l7qMxEXLrj6-jfAa%dhacaJvgLRCRW1G(4v{uB{dF@ONL7&36tX*DtkG z|DtPT_iYcPT^yxCOnW(?_OE;5(_8YDOZEf=gOHAIng>`rXWHINLmPDop_$2uGXSuCs2-?Uu;CP=#A$*d*GTDz_G6VnA*OXrW0u_oy?ay&3A0!g}na&?Ap-?e4*0 z6q}vIIJzp#CH*wU%M<%VD)u)Y$F5$+Vk+|W2eQS;xFdMQRjkqnAS=&hXW<#ePsB-3 zk4xI@gR_oV103Cl@;3yT8sAg)cnl%VP_>SXqM;t!EzGLNea(Dlpm4gx>Xb{#f=sW2 zAmbDm#7xf2b3ftH&kRR(!+pN6XDU38Xi`3b;QWf#69?~{m3QKg;t75;4!+wYv{CI( zQuAt!+sqg6--)4jgf=m)hYXDI*+Ru&6w$IZyIvIhIQ`u^G>l^e6Xf9|T0CfOedR4D z8b?uim)!Lgr<^n{I=V+_-<-mM!Q-vl8KgUm5VX4(didgPK+#D#r z${Z$TH(Qol#8{%YyKeP&em%n%#KkC@Cv;3O9{b#n6Og{qykO>1K#1jAUXt#*Xb@$ta*UEXlUb%;Gf zoP#aYa2*vHF+}nG0cH>Ao&Q<>h#T@pO{Vm;C$D4*j>nPlQYT$<swC;h6KJ z$>s29i=XuWI?nsUdx zAEB89qs&mkh)3QFMnM`{S5a`J1&8sy_i*RnP^VmAvVzaV}$|dOI~=I>l1@C zo$I4aZ-X8O>bva&lZ(zKI;Y1&34Md&Zp$OO(CwQ6`kN$we$o#vX)S9Jp9_HqP-aJO zND3M1{DnhqzxKy!Zc?2L4xVt6Ey*zHjJ`q>Qwc8bJ)TQYf@tp1Sf5Y1MYwX`WTI>} zp$&J?pEg}RGc{#3E~nfOJ{TBvzRiF<3Pw{ z$r8z?SUl?KL%qH?gXbe;FnDs?A{I^13AG`0$G5Wy>Zgj*N@k&>%3en!L&#<1QGIBJ z4W@PBpoDXkmAq`kVJIStw4vW%+D|LcjQZL06teFM1&&ZR3g*iu;3z9%K7Bw0t-; z6jvVH#BM#L^0Y49++nz)gbe{#>Y5i>pOO#CRNBfty7XQ?opeDX?=gz4MNn#dwvpOO3yfQa`jKc;*%I+4hhH&e)u zGYn(-L%96SZQaqy({|SJ=cCAk4m(|JFT41}%Y-bdUN|n+K0jh^v2d2$FD{%C(gWx4 zkX|W~07y?)OW;5plMH!*(ef8Z9XXoEtr@a76S_lfvY{eq^%CglDzMm`E{)BWf9Qb^ z4>lOAnXRw5sJa#s?p+`44aP*d4(Yih;}(()pF%zGD{@kY{)8Ev9eq`A>&T9#IZ!qh zm78$`*Sj(%7Zd9~7Cri+**GZJWw_o77Uu@$hH}DNJ&NKFc~Z^1wq+g`57eQ49R<%j z_@yv$S#(*9gcS;}TBWgtuh*WLT5linN>a!`I0~=KPVx;ocC{My%fFd-8wM+La1L+p zK1{4O9C7rRsWVCG$rU%mZ=)uoU+?WopEXw{Hq2?!SUqQK0V6SB_|?|}#aq%BJP8q2 zl0NEf;VGJ~5qoj8KyMz)JSt9PnZI0!7+x=Em=)&Cn|#{+@)X=gN@6rWoJG(~}U|^*N3>3CS{KUEO^fp*v?`lRcH`-F&{HMr{xU2$UL^{q$B0H@dx&`)geg z*f(TFwtEGgEp4e9ivq3blRcv7lLiPClLqRqs{!NwuK#ef2+A4)v(QD$;+ZlHDH#O$ zPFf0{R@f*UjW5zxt;NSGu`pK$*exa`;VI7}gRfCDM+gy%Qd>tpgeKbJx{-QoZ0nu( zuiN6##zh$n&F7adgJ#92r{ap@oB+c-Mw#5)3DPI)#qv$DiR#%Q_X_-e2#8xKQT&l; zh{F}+c|+U1t-xc`Z!Ka!HWWpOq3X^!rAtZ8H}st0DbJjwuYx|q4skDzt_n-14{9HX zQCbJID(|Oh4PtmO-(HisrNraiY{%smt%M0TT`G_WP1daR zhkw)7Bp;6q(rvu*hcckUOJ-R8@FX&nfL0O_>{8F?twABvnr&_8({Qrr2}HbY{LO}~SGVaown*p4RQ{#kx_#qXwu^roStDNp>qR?zM8=>0=#Q&lyl{O| zBe}ol^@fop=XNgI@7S;nZfQLiiU~6lyJSg*%%Q_71qPHroP`zCB|Ou4L%GR%2Tv zlGAZTBa7+lG>;KJ`CmhT%uXmb?pzsRzf-7AZ=-Jr4{z|p4nn}ZsxA(Qu=rp*vVPQ_ zxTOouu7Oo7wCYik4{0X_YHBNcc*s7rLQQ)4=rd&t>Z9Qd9#bxaOL6E~Lm@4Jcn1$%R%HQAk4ejY>$ky=8%|r_g3@NEL3#qqUcH zZ4;sCkB$n@pC(bt#xg2x63Hh#3H98f(<*d zVvQzhyJKl|M52AD^*=gf&c8kGe`e4t!)I%*HgqvlCO#Dn!NqO;RZQZO+vM-RLpms2 z*SNtVZpduUrPz?3y9F~~Ow_Fq1Q6UJJEM@ZDEZ>ygrqRy&jTi{z)AHO4T~36xA!IG z?grF+Axz{jYF6maPfbNf38v7n?mhMSqP2S}>j)M1|uiLG0$Z0ngWtSK<3Re`8M2_otps;@F2uwUyHB zXk~RHULoFQvIF3BF}fw6rYbV>Tz+T9-b9cHoM`q>75!&s(>#R+|4+<2I~*1uIJv*X z&{QHlZ0;08`k0U^TJ=rMZf|;j>i0L;jvymPB8a`I2g5L49xnVyKFm6}3`Qe26|Feg z@~_>{q}j4#8hwxsi|8+s6wu*1rH9rE7b`m&PTFNeGFxLRS|U}&?`sor3NL!rkx^M$ zQj}NxM6Frf+7#^eSR{w+V=7l5S>l_0te{ei5yxgcZ0D^>T+Znu0zp?QUlX$5{1_;8 za!UrB1Es|SzbAc2=|7-RgiLH^!+Oq78PrLRJDXSAxMDl{^daM!>+PO2!#uBycWUlg zZj@bJbII67ZUd;q?PcOs>=E`#+Geh!OevDOd)F3k4UbXeW9s6q9MEEDS{E^NK%|$r zur!kWX2F~tV26D&W$g1Bx1I}KlF7E~BPTxi@8<4Hczs1&(dFmVpRlNVf+Co{(cigW z!}fk7p>VXOcN<f8IP;+|bw)$a#s6YSqF?V0+accl9@E zjUpqXD#SFTMt(ozb$_R6KaSVU-ulzqlUb*2VtpE-6xTtLvtv(ZMJLGvGCk7UZrGUj zjnO=Txq{V4Q=f4-_UFhMFvvOU(wJzt`m)cvk9jtkFi))b;ZSL&qmQBKdefCpUj^9ojN65_$**FWJ zoNuc>k0D`&KoNN^eFj)yPNT_Cd53;`)kYzm1}ZA1jdH{VDD6kL^Re4>%~pKmsJ)7s zylpc?jN$4SJYK(#OpxbYNCLfcdq?SPY01=5?J~dNe88lK`j}vd$V1hn+=*>}fKq0A z2d>OB2fzPD?q#8~4MQV_`sz(n0?hfGBA~PeE!TO6H#pJ3U|&-hFvl!hl)`t!bfrwS z`_A8x;@{WwwX7;Ds=-zby6mZY!^Ct{EYYl0yHGI%<&UW~@)VyM6I}wC|4ewVwfCB0&`>Y$Ip9 z8TmLp)z{urmP|VMOpB%--9g7+G9x-%nHS+9Ef*hCH#AI}$ruuSRJu-j0z-Ic%u6kOeH zyv@qv#c)n|-~LoEILp+YVq?%08t3qlCknM7*M|%;k5?}s0c+3E3^WcOC>is+w*oY1YrP#x+fRm*Sw3GjJ3=>&cRBZS-i<>~dX`V=*gN+NuMPF=cN+MHoLT$I;wG&y zxt$V)-GD5WoztQ~6;#V>cK{(|C;FqmZxCK)j6#+X!%08~oi=)dCW3Hc-xX|W;zue? zc>kWg`t5^TTg)HY*Nlsu<(4tEMsgQfH8}#8mKxmx>lJkF$W!~d4r=*H4X1V*+IGzd z#>v)XjzCyE72)XsTdVWu=;nOep@iS}faUMsVQnMP5JG8+1$f8z^@tm_u`Hb}gL`?x zIBw+4l5U2pre4=DXM8Kv)8^)_g#5Qh8zujyqoTO_3$u;B&e<`emGDU2Y6bXGS>5NG z!94qZPfp-#jxB*pB$BR6WobTV<}7b-esEs{p5=>m3EShU<%<`ej*pHPL=crhQ?p43 zXD$DI^~~Uz`?1J<^+(-yM0cRR2}DgglF3w;$*9aE*My}ce@MY8(v~MT<#J62iA$s) zy)jF1W~zaU0^xm}zv{&K35FDgOwMXzZWt>OsCwG}O24)kjF#S3Vl0hs4sA;)G;29C z%1U;JC+^ypiJ;X*S<+iwkJ|rs+2nA|o1;a#KwSrFyqIKYzoQ&Ac!?65DN!PoWz@8T z@$2gFU!{HVwUP|qWqPA*cR(LvlShQ=PtWa9lDq1$P39HqX}4Z=tkKJ?Juz1$mxc-lzUmMh zyfI2PGao@jdRFFTUKkjymLtj^P~%iy2Oy^j=sOW9fI1yuHs|E?|~}@4EbV@2`nv z9~SJ<75V@5If8?j%it!kd$rSnrqM&FkKvix3@s)uHT-#mX;p1$trRBD2D$*182TI24t5VZvHPAB#4Q)v@T+_oQmMUj- zq!?&~rxm?7lXb{w$b}0g@E0A%G<%#V1vZ$THXCwZ&%Yh)IoR{czjc}m#B5uOBs^HE zstSs%oZb!x&meReFy+|K0|6ISO)18z7B`Rmh2KLI$#HdNG-D9=p%_cG=Ac$GG@SkJ z^9E%YV#~jm7Lv#}A23FT+h-3yk53NOj1b+WJR^SCU{dmE@?PA$Lc_5=YhGYbu6{aD zUrqlxXgew6nc4MW_?b&x;rd1BT!}f6a9*xV(3~nc5>(~-?z&GAO6y{{7UD~6KtV=$ z*pRB957RCmS|06N1CM=$#xBt6M_B7-sAPW1ITFvi_!=GS%^F@n022$`39cNz^H1O% z-+6&GaX78olntV0#VJ7qW$x+XfHkuoOL~Y(S;y}=4U-{ z37x?WwB0t9{EB?L?JYF+1gr>1oX9rqDBhgDiN&79Q%Jg@Tu-XbJun2TlL|f9{FRLX zhr}?DeS`u^9)qk)LsbwL^;njm$bRe)tmPSU>A+3AZwpp8hI=`ZI9Nqo$^8#D}8r9~UEo4$j zi#f);Pzu$bYBLQDwHX9P6ac0MW+>I^9?8)%B9mSV>$8*8cr#1wq>9D%kIq?N|**EzSWA{4tLTx z_}f!BfT^E8?mxC--aT(+IV^R zx^~tJpG5|W-`5ealm(jKAg`xWEgPtPZ23u^;8$1Urw9A!hh%4sxbfp7l2d}KmA|Zy zQ{=^g+#h+>vqg(gIGN}VNsuzs#?#a!=#CTqQiFf)ltQ=U`<{}u95q-2OElTL-jhca zuFAT4%#=2BU~?(zl9TQW{v3|R809f2?8pb(eBDqKlW0zX_q!DLq}CNLU4TTOgXM1> z6_q_0OqDww72{_G>@jLHQ_aR_a@AyW_=Ox8$U)^#5o7=$syNkWz+6}Ie=5&4>wf{P zZE|m{&+WO+5sRx_lz#D8Kp&*cQTj85UpDT zrIAK*j5cG?&+oQ$TB}8E=zQF~ep*UMsYHx|(BG3gYmUSJPegXqms%R&eWM_0d&z$> zT`u~1!x3kMJvK5Muwh5~+19$e8Vob(Btvg5xR}7+VN84BNQJ5YEJx1-?ovuTt6 z$UBFg*m{3%;dT9KLF(F_^NpG0D5nD@35WRCjvO-tM`_>^p7t7zte^ z;^=fV!hYvXDI2E$Zy6h4Ik`hs&CIe1%GQkj_WRMrHu{|QppAW@0+iBFEYq9^NxD;I z>>yZm=*9LJ$}zSqc}e3~7_nkv);^R(dBG~e+{N>BPae|gkn(UOb<){0DLnWF8S@Cr z$Z`%8Vxa_LY}7o>BDNnn&JM$k4lY!KLMiq10cQ>M=077m^+o-Qb`gKGXeoKSAN)|B#up4?9N~HJI$2l`{S1z) zjXV`_|IjPoo`s+eP>{nn5LcgkvQd$Bq<{ltlZ5j?hGTmK(;pbasfJoKi$$C> zLr_SJNJS8uZORmMePRhsPn&p3*^rGQC4*118%G00|L`d=cK|Of9CC;)c`QjNOh{&Q z2H`l0lb^w`8Y$h4{?^c0`-d=Lx6|E<@Vpt10fv zDXJE-xEm7%2tqptj!)PXK<{A(@*J1;4=yPqd{IM`5~XF-%n_aI#U%YL__QvSDFcJ| z%?*@F=fgez^4hYow(jm8yJV4E(JM(y?*oG4e#YfFD_lq&Bn76c@|a*qe*QwzzVa&v zs~9vJpve$ABR2V}dU3=Jm3jV&mFmI+fr(fWfum>zPG%mgY|~Sx>BOv}&pG+qfi>%= z@f=*{z!poMcVe<8@6aq(f>!=irWHUT`!A6JKWm)sla}s7IOsWtFx3Z3>Z5`5cV;{C z#9$AdaY0TyM9ti41>UKXs_5r%j`xkMsU=} z5&s7nc_e3cwzr&}z=-2?*q%*oIX6-9#pRxaU**$*4}(~G>ILQ&pP&Z=H!#u9{nk?N zI*CerfAkO7^8r45N$Dl>dNxCUtGXsaqzvoi07R{^?|Z0^bH`_632kTGlS<)}F3KYTm__E0!M5=(+V* zc61TW5fsy%rpEfvV<45}3a!}h8d0WnZu~7xtg8&2cMYRuS2?w^Sd~>`WN{x%m@c|* z2VeZ{laeucjvG`=lYHp#0yF!yx6*7#x7x2?Qc;3uF-`6H{?Om;U;<11orHA0 zjKH;T&F*})v49df2}VY&*r<{PNNWZ)G+JV+VT3<(TIz{YbcMYh35gm@YZvV7TyqE? zp-7Mmcte=acP9qwgz^{mKTT%58yA{kC8A&0@V%^)+^bR~D)j66WQVi@lqT)8Knd)h zY+@Dy0d%%zVB>-Anh;tvTFXU6jgVS2Qp-h-<}YnCN_eJf$iB<-CJ)&cUe{JlTP~zp z?XUS0Ts^+ksB#AmEcro7806H1*M5$PbA>t3&UYQ zpBm#K;D@VoIFl#)o$^6+f$yP|*({}CKy!)NtL9x29KP)vavpoDY%I=jZ*^B;-7>=i zBq~@Ep`F~MFZJR8dz%qMQy64X$1N&kVVrcQd+mNPuGn@L=#TBLPYm`;)F1q^=ijgY z^#Zg_84qgM*y=x56~R!61xk~~>d5oSu{k<|5fN*N2*aC~+cVnl$slBJ>^P{S^#M=& zl&X(cD2^dcajR#XX>0uE^43OtH4&U)MHE&5U0)*ITkMVeS~OPLJfrNCCKLoz)|Y+Y zEh$0EedwlLRcP}WS|{$lASZ|_sK{+i9aT(ks}sTrQ|`ItyfgBm|06@ti1)H!r~7zx z8~CFkxwkRQsvjHM;lA(nJRWh9$EOdJpGB>EKF6ZkT7jJ5HzU)L9r6_{W__ia(avz! zDZ|$FMjBP|#uEy-Z{zZc32}KbbIbQ-*SV-MUl5KU14}u zsF{@f(jh_0OZ)-D*W5h`o?UqHddS60!$fc@FdO;Cv2TqTVKPaZ;X!MB1qA!u5dp9r z#%b$=9Y>uAa}J+i^xL7tyJ4LpzF$_d9F};0rf--ozTcaFckjpKqFL!0WphtnRe$++ z=J{ncOC1kHU7|D00VXx0M%G6i@OX<@+2+ot*kQe2qGfP)gt*<sKuarv)U)VY0 z)aG3xO+9*L{AL|ty7vDrkcNI{t~Gllzsv9nX&wEwy>=!5)$T1tytya+%>e{1KE30E zDK6^-XLR@Dxc)H29@Ik_>sT>2i@MpVAh;ept6b_oxAz|fSRsUYGK?t7n3P>>p`CL> z1@A$5i)AlXW>ks9##PyD4OzZQ_ZYrA;&BZ&G`*Sa+V%V2w|Dn@5~if1W#Yx%ru${& z^}=iZIApN!Qp=82nd2`pnjwqbbs<6W7_1M@AOWtlnVx1Yqt~_ z%DdA>O0Dq*IXPFQ-ThjTB$>OnnyI0c&l_#+qQC{FF4Gs6zhlKh5tLzph#8d`BjM6P z<*LDgj#L+0sFB9fa!FXpB)x$GsG|UnbB+{gIn&VMpkfVUV2QPv8)1$xV7|{=6q6@l zi@&ZlEvIxM8ppT%%Mp5J&6<3jN{^JZ+#`Pr9rO9G03w6*yFW5=^ypaITVny=JJ$C% zhCAQxJV0&M$uqjsdlRe7Y(0^0t3pA!pE=W3DyK?Gi=v1(jyU$irf-8f?`nEAv1?Yy za#cZm&t^2^VK$GdS(m!Omwy3{onW*5&0&w1y)~GAgew8xT?Yanu$TdrIKDZgX*CmF z(z$iYgN?sBTG7BfR3}wAnMKpBD}L7`b)hu`w*abdAm9CYD&TVBiSpkW8JQU0Bl#K9 zl7`=N)jv+?jVQFhU^@yvPl3HsUF)+1g6~E}n{`J^e9<^SL$_=Qg4do~sXAdQ=i1gHP!b-lq?*+`XR; zZ7V+!+s|6QwP_Ce{aUwU=3;`{&-^|N$~_xuj-52L(iFd-!K6D*_8r4kTH$5iaQp@Q z_NELN&GfGNxif64{SiTznFw3xt}c&wNU}fp3d7FTD@Hs>8YTob71liI5*+Sj1yRlCFfJ(O?1M;iQ zp~D1E=rr)(-xng-2#TblWviM_2ZANF-elOcz*JSGXfzY(SSg{g&{S9iqa!^5NhmRM z73v-`D+9B?!INk)gMnq$6eT%&^t@VE0J8mS+t5`-hD`eSAqu5nBHQ2V=@+!a4a(D) zl&~KG%~XWAj5MO%T9BO9J%XsddRC4RI#W?SJRn29K^?1C(~QE-YBK2W%+r~vMrqlJb6o(_~kO=*hNNh{i;Yc&dcW$Sygc)z5St!1T|c{Wqy5uEA43HT zS5aE5V`YBpeV{tDQBl#}(Z2tbF8u8(tSkfsNF_pLZ(stj9oi=bfQi`}0{6&GBn}~} zq_2j|sYNrBH7r(?Evq+F<}zUbMO9f@FxO#CB3nuT9;*V{n$W-`vD$4WoGdzX+SkFV%|aJx;WpA_@T|Lv@a5ocd2 z|E+MEF^%nfi{CW;nh?>CF+$%}bFtJfirpcKy=w`*?jt%1H9vlboVaeLx3O z1YOlnSxi(OpAcEs9Nw4WlT38J~^2j(eSr(;uh$cEjDd5w(7l|M75GF znNh|wT}%=Cd=q-QIOCo1cR0l`>ak~!@|QrZJB{Sj-^vKdbVexW+-lX2apDh*Vsz~3A}LBo`bH)^#->s^#r zRk*!rJy~M(AJA1LSZVRQ&!U5UoLl!bEIt>`!p-WXpad3;LC*Ga4U9ltu2L=SB0s2qN6F$lv z-;^yhnT(n=&jT78(xr|b#U7r_gKBtOK!W^{E`G;&9f$$s01-1< zv;UY7fz^G);x`oaXVlmZmhQ}4@gc)lPvI^Y#uYweh>Ti$ODAVyQWB&uDp<7qb_NwH zzKfB=Z+*$HS*dj)6R>{zo7m!w&ovhjMvgP zY9@7OBgV6OG*wH&)`^NDU^Urd&&ZHttt6`vzG-0vK*%eNsgYJ!oS>KRq%52tA5-%K zT18`{W*bwnM7;6~)?u9x>&5?rGvHui8zuXS@b;AZFX8)zeG=3kj=pvn_%J=H1>68q>=sIkrft z-~%*a3l%X2L8of1!VB{gjaVI{s)oaX7xfd1|BB0NM+VF4F%oXtQ%dtHm#6;!O3Eu$ z`YLExL2L8JVds?anjAz8S{}Jm+e5WTD39Cpq_!V9C|cLx31ko#tDvtv#?mQg>8f>$ zVK6nB;yo4Ug3Fj~du6ddAR5a_%~#hxc1K9&nyv|oJ9aTC7NjX;Db5u&nWVxaj_GGi z8wEGmkSY!@RND?L9~Vn7g&vhWJcdyJg~hxx_Mtuk28CQw*{yTJ5*`dyzvq_|lH8RZ zm^ql-12@4&1mCloRy5*6@}&6ukgl< z+Mg+Gjdu>rR?_{jvWU}DG+l?HPlYnf5jZS3i9YCo8Y*@V@vV7pWtjv;@c$&2^UeT; znrURgI+Bl4`~~>7p6h3x?@HT$8%A~|m)FiD3p-hsqTmO1Jw8^Zs+TOBYFO>N`|fo7 z|G1JjqeK;t6WsoVi|_nI^+V2UQJbcAd&^xR>TFqu4ByrjvabI2;U0+}94oEB%LC$S z<1r2UJ32WVO{Y&ukf;dl$X;0m=?&5gTWtF`@R7L}&!vzKuc>2X3Zuyu6Nj_0ycmQK6vPvT%WTD_?bVVH^`ZbDNIx1^H)XbwAw@oVDoaztNfJMzC{ zp$rbk&Y-L;jC#upuLl(k$upcz{QAkJ$4fKWNli7k+d>kd0HJ?@Emyas0pOSDdjE+l zoRK{HtzxA&`d*${0w8pN+Y|s3MOKNDM3j%uH?sl6CvCMG^V9VNfM+UbkZW)6q4M>* zQQb)a51tiA-5-kl*BRP7Kxa-C4so2z?LPKE@t8ZuDWG5OxTKaxw2JH~9XQ=0 z-ryVsj-ey2G+wVmLC&7&p>EBG#1=f+e4e4nE1E9Iy!htsEz*(4yb$64eT&-6i4$3O z_rn7B<5ysjaN0sJ=g7-*(H{9vRq~b2jLh+6{Rs-erI%es-QS;Aomsj9nMk$9b`QbT ztWB4AD1)d(&$iHnSGpsWz&EDHuu=bAh=AV;gRA4gbq(=(>W7d-C2Kjdn*I4TX%Pv9 zB%uY}flN)Qk)|DG9!*t3N&VNDKzdKicmt-SXq3G<=#-bvpv=wGSzFLHGQA&Ca6hT$OqM z+&?n?ZdjJ4DOVLjpZ95@kFb5S=PRsjj6VFBpZ*@hPp9@t`+e0s>lu<_3-<>T4R3{f zv{||vTiAT}xuq-w6@+XhKR%Eb_|y5zh%Jpt<*$_+DTRBUv=aqh&Ob@c&0_I$2R_@O z<4xWj!~aePfxv_e1RbucN2PRlL>ri6nc6isx+V-5TxbxWB9(8|4w1KtXI3vYRHx2SM}^M zK7SukqKUVl}Cltrp{1%L(NHle&lP zsKquB?aVHN%|RM3bG9WuLqIkA$|WKVCca`MpT1P_tecdINa5P?6_w zL+EQNA8<;|?=7s^Y6dOh^8-%Zu=d~K^T>^iN*iV=*_r4OnNlIKX{0^X40thdTM5#` z8<{bAm6?Jt%&XHm^*VaH^e;!eW9AxXRH$~TXHJS ztNtOBH2<9f^xpY`UCoEU8I-dAEb9ueFo=Tdg(szh$K7_fMpF+to;Z6)@m36&x>tHO zpS*;g>U}eWJVAZ^e0oJ8;>}t|D7wAuL-R8aif=uG(KjO-0Kp>m#-o+!wx;%`LiN?b zxKi*uV+^wO@@1Eyk+q|VF83!Y+Nh+ln8uj1PD4|!nv0U3j@nC z-eM{Tw7pvVlZEG-{Oko*-3|sMsIBJnLu}2U+RrAo$v<6Teq?2J^AMjU@ah|@ZRygQ z`BhXY1)}7&PNDw${$g~YI6EXt|B>#Sip)Vwimi4cdzoFotzM*eAbmS=8lzzwSoLP( zd(4W7fAKWJ{YKH>_nQy9JKBD;6}(gtu9)pCqvrXFZM+87`xo^x=Qy(gcYI=w8fzcx za?3L^0`Nrs^)WrrjiC1EAFdk9nZSB|Id19QhC-uT?I^cy)ApE!VzxUiZy)sSk35|RIif;!uo=(($xh%d#@GpCn zyj{)z6pucC_Pmw<;I`qoFL2=7V@AJIo$-qYTINQ?3AuD^7Y9TgA|zB0Gn|kO+471i zk0-4Af(f0vy`9=jF@S15g>Wa+Gt~$OHf^JyBN!A{?-JpPf=3ZQ#@doAdT-0Rr8M56 zr~a$MarN}$L0TrO%g`!=w7Gonn7ZrU3o+kn(q&u?e|`ncbg%0pWTY|rtYW!+Pa>C^`M@0qfqx)Fi~R`RVCzc*OwhH)R2pPuwe zi=m63AEGl{seCbpD=H{=)SJbr3^S|ygx5Fa(8zS%@jvb(?`|*)g&qe>Nf-@fsA#a; zNgZb0ccV{XoB{JNs#Wn)Z_YorX}zsfSG^P#HvX@aCJ<$pDZjdM^Ah~lK4I5w<{)=U z+C9drY;<#HW@K?Q)U+V+ME_*cUj9!@?L|U-F5c=&N#2H=c@%g_5F(?pE z0NPvQ3>qs_HC_#Ch5to=>pIUx@Vv?{(8;F_^B1u^(J??#y%�>P5nFTz-467G!?c2V`CwirOF2~~tna7yFZly(U3sE$jH;2UH`t2Zz@wKv zH&f*IY|e{>9Kt#43b`)bxT5a%{t0H`O^bijv8-gq{LsVuf1e2-m0B<450rIFB!RPi zW3`t=HWWCbCGp^l%#K~d)r!-Zg{Q9j@k-;hJRAMDU|ag2zr)#%P(00{;LY5Y;y-I_ zw;%d{i+X9?8T<6;i@o7T>z{VBO9$absmla0uF}Wp=bO z)vkV|KyY)xJMsfgGyI?>l=MT}<6^R~nM0lN?619>OhFXy?G|*3e(m0R91mM#J4D^Z z<=^clwr1#4m=Y~q*FRD9xPu-F#bhu2s8O-Dc|-yWRg|(4Vhzz3H||LKefQ|ko2Sj) z+lF6cEjgOI+pT`yxf@*ZC`_2_^*d{_B*ZPa@E417w=aA%?| za~(Lp({J1KXQk3#RjG=Lbj2T8C&k!KQi)UQVaMNn!arVHx8;JK*(`d_D|Oyi#1onx zI?G@3y>~rbv0_}*ih7=3C1vueMqfY+O`R=oVjJ?c-F!^V5bar>BV$8#(t`QpjdlZ) z6SE@SapW~Wh=yOq6d!g6pN54&KWFMcqW!S)PHdyRW>8ecBEhl9y>?yywoh;oDV^;7 z#p*Jb9&_rzkUu3~266P!`(Y)mr3+!AJfBq*r7R}2_b%&Fli~ubvZaVm|94Hw>Q~BR z(M{{pQ=)AAZKb0T@jXA$VZNqQ+_YeCN`H9?`1Yw;*H?B<%Mp@A1hFdl-G)b~!Vvv* zCv{@t&g1e*TwJqD3=@YEaRM=C=b5WeKKZQbYO3;`wUSIeJ4U>}`g19Q(HS++ z5OsPAw$ugQj~*`%^3c}xvF3MGGx(l-Mt)UNFFoYVj`b|eH))R9>vg@;wPuv2o;CAw z=TStbEuY`@jTwm2|HvjzZourw!axQw9vrNv3m1zm-BOG*H4YcM*{Z_|6 zz8EXE!0R$TIlbMx5dL*z7gFw?yMV=6K7wRxz-}Y=zX(8C_@GV45o{KIgA2v~Y~iThueZix&X#CoYv zsN_5D!RKiEA5~+?_l}~AvLSs3y2?$SqhoZJjfq!2{%pQ`{hwzV-xl@n@;vxkS&|7}6K zJ#j%R!w;)#FSfknOROv9kg?w?6y)U!9a`ild5= zF#G!tKn=meqfKmlCY|F;FJ275BV(RvbTXD^C;ZYjNM&wwMaMbcQet9YIcUfs`Juiz z4~75Td?zV;ruFEmJ~iWU)G_1u7?eG@11uCI>x09=ITlFtO+ z3yPac-#n9pTx4xlG3;C`>YUnFJJ}hGBqD-Fu7>$K3jF!l|1}@`=3;ew&vr{~cE<~E zp00EMA5VI(vXR1_z+qLSA)TtK1n_V2*!xJDr48S%AFLX@jfuQu=26KWIW%N5pTLt} z$D^$gRmAaS<|xyqX*;O#L!CkO|C%}V2-yuTcNEe`&$ic@C6Xn=%FO_!b|a!lyD<36 z|K7)`zkKbF=&sO}MyKMl_eA9_t0K}lZ=6ztx_=M-hCYt3wFVev%;5jdD0izrj^%wJ znadma73amwDVAf27QaFaG~1Eg+$OJuLNoHiH32ed?2t3%CRVXqiItcWNh%*2%Pvc2 zb3W13tMUDH95y!Q#nck!-4%?~LUp0|sctZ=61Bh5IkemL!`{teO&I$q7P}jhv%f#% z|3$h|t_g<~e-!lJ>8v4HB@Yav*s~@ih3t#k6S6tZAVs=CUWYiN@nuesJNs5 zS1-W$l@6u7(AF{SAnu9lW;SuO^DRWU9(CvskuGL+PFM|{R|2yqs2d(6=#@ldPWd`p z;+)pQ7f+JA{~joLYZ}0B>z3DTh+~E_o*lkA3yvkKe-21x$>s#86}6} zFG@<_zZDAOZ=*`hEN$hvqF2PIt^t+K`fYYbVo08C4F?5I3j5w}~){K|CRTCTVQi43rP-DAR z#*J_;h^gKtw>vu$baa1gQ{gvE+Hfv*-T`-9*uDSNaMYx;sH8oA+2jD{d4V(#^lyN> z1>4T7Z4faUJs5(!wTt_g)>T3_MpNFFHW?|G*6LlAF~S`dJNPxV)r`&LtGm>1i{E?& z0`ca2Pp&Yt{K~8OVw^qh5E(5=isLvIOXo{&MIL%wDIXsyf#~=Tm5msu`bU42`XJwv z+XSFTNAZ1W0%V+CHt!sbxAChvQ}a2;^y^w^z4+!BlLO)R$6q~-K{qNknD1RT^Ju2y z(Sv2C%I?vg&M#!-#QS5pyTLj*$v!{nd=c2Wj8Au$jB(?}w)@;dlbT`1VUo|O5x2_n z#Mba1#lUIY;)oWXHZIc6@~x@of@{7iW@H-a1hLa6k;M-f`;884G>Sw+M7gtdGjNnN z=M%~Y2?NnGWvYd-_7s2GOvR%ew+j+c;VV$kmRsI2dnz* zzi8vrO%pSmd4z88h(X~|o_22t!ZIsyx?;2@6%7e}vN?NxG7AcpUuki3zUGH+a$^oxLUG|Nh>S@kB zNWR9ki8Zw2Gj&3auRIQTY%7+_-yBm}8`p~cREGk45TtiX(H7eWHmdn2oTEj!Q-bfzbWrd`#*fJ;qm&Ab7$ngPB_Dkc9S+=)zV5 zjf-r?CRoSV?fhceVdqJZ`O$WC-72xmsG@kIs;Ak$;@E&s4&_3muHUP%=`S8N#hN%C zv~7)^(Rg=#wcu-hKQnQQCWIf_`IkclJZe;w$8y8WjHk%iu@-n|mNb4)E+qom{RI~H=;-34+5`LcQbBWV9)UjHAZ=L>P|{>xW=&Zsme22ZcnAJq%4 zL79CkQLlVT;e;wz99L0!KH(GW%&z02uY3^$`QV{&aUSMBW+vzx*#AVR2cApjPjI3a zf*p(bEm6P>C;Z;&d4vA ziEkmR^kS<4;a`^U1SOJwLyeEaGwvb=Z!u?0ALS zOh@qF$%jEAo7Nc)&{fPd)X5X-cSOEIPppE#zAts!=j-}QW;!!djAUD}W}l-g9nLLn z(4K-b;jBMAcrc&;QB!yWXLT{4ss96Rj(b95>*J&2e$8xw?tyG>mZCVbHlb13X-mSy zVpyi8kJs(+;4puW@g&dr%oyC@zkD;waeB+M!TI^`O2S9|2DVYIFDfRraj`_?aTGG3bmT1U!8+lCM&_5nL;9qfmvh6(Vhm3%{$jCv(yZ0B( z7r2?17w*MY_>e)rVxTG$O$2jXIwbFd42H*y5L17#CW0Ha@I!=mAWF`|+#t=V^To>( zXnk=QhFFrY_x)hyu5>U66zlu@)=C1eW}(0J*`z`9RW^kgHYJXS%qeg?wimGYzVASt zJv!YZ=@3zrKHlK_9?iyWn0C-KZ#t81Hgh$5iP3Ck9w)#&tM#4buPu1{wYlPmNL(wj zsm0hZ>E46Na!E6nR{}L!E&1@mAzjU(POpZxA~@AeeVL`0p?R|!%%J{}lOv6^x&Dwb zBpu?+H=5j!THG!4$1c^o4mAj1jO$KB>hZt7YBu@Wr)Iq{JM!Nh;lcVv!*^QmDIb;8 z+)spUW{6uF$mDEWh~{_ap=%J!QqG1Y?^6y}*cj`KCSd0;_{9n7d&6<#A%|QpsAgoL zJtocvpRmwiSmzjHuzgI6MZ2lyn~Qxn2V*d}sBKKpc36)>)>Sgl9bp%eJLtNjj5}jI zxi1X0q{8Ywo2GQeP(Hb{uXyF=fZFg!{!Qxzmk@1)1a}x92223N0gXJ&V&%p9ARVkr z$4f7&o#os=YmS8bXv*q0;QNP9O1%nE2Zrc;|82h#`1@v7qyzSg^Tp=E8lq)jB!;j> zGu^fb-WY=SSQLpM&LMqGSQ%q)T!bhg6vkM0vf$p*fhz1JyHL>*aMlai@PxgzIMLA` zDfLEa4lv>;dKShY7WEb<8PIA?=dGNL)bZXJjdir#p@1LqNZ)6cO4INSL1E5+j@F&P z={)f>0tU{v$(g1=m&}~6Sk<4P&qMl8yL$8(5bGaJP&xE+=YBZ!agw`FMpd8s`mCmZcG&pgp!-cTpKjLfCgjGze9PX9|JY}q<<~#&( z(MdaoZ(zUXKn&*WlPQL@-}ZI+W($M3oJ z&nuv77xiMvhHuN{AF^lu>hAu2Rf+>njmXkC81bmc)WB#w48VEVl=NLNcW}p+<%2}d zdJQq7n1xak7)Gt$d!o{P3vW?6=O;5w_$rR+*t^InlH0Yd--wSe9=OE|osT%k5tmkk z_TKSS`8MKyZn98%mVa(gIrw7%nx2SyIrJw33fCNP zN;~j6?z#BEdQ~ouOmKc?gADVRwn;H*6aN);baJ#-N z0gvG5mz1i$I7c_(#4QOYP5HA!t~BJ8>}_lc?zO?_`FW-JUNg(4Y!jE2@bY=E8G!5X zbB67Q3$k8#r$;2jPnpkFjND%nf$HDJ!JA`+_?e}DHs;>>wy?4dJ&R`pC$x~cn+7+| z$35}dvvaR~UN!%AW^+p(d!HrlF{Zd4s|A6dRH!)@Z z9h>W98$GmoPo+zJkcGXk6}~lJd7kj4)OBB-bmN+yqYJJxFm6-=94|@|kp2>|HutYP zj>tYXDd{{@*EoUV04LEU9x3T@l>imkFLb-%_Ql-!8ReM+x|@rxQn!>TDGvYbV(P(p#3m=&kc-=Z-lBG-XE8iZ#{#D zLr+I59drU|o3vNa2kVkHgB?c=9)agewDWm;5pu<}vQUee3uD5dIIaXkf=gbNRe(yG z!8Zt}=eFnOH85O5VdBOHop` zHjdQPqHP%mObEA3W`f8)vHj-z(OTrw>dgtST8H_KJ6Fb~8*ROdkOv4)4vW_TsJ=Xl zqI~pjfn@nnorSkahyxV8dK%6&e_=Maw<|ZH@0oaT;3=zR)#LSsdx3*O2vC@!=j_EbnZ=~@nttgLEsFV_r*p@#3xnvnix8i! zo_-xP#)8Z#JAfFpCfPhIaMDE{vr9Suykcalm%Xyxz3^K6>#b1*l~2qtoq?2)nw4+9 z%}14KqT8lG%mquy_B3JmcOzJMaogkYp_jKM&SbV31q+Wmi_e!eGR8G(277`rq=+O?XU~yo=rZAhOxl9qYri3)Cz-qiISLRCVGH~|i z4aMG%-=a@6`lOe+?~a->jW-MW=}q|k;VEGdDB$$3-%C2Hf}h2yJ=rSp)rb9{m)rF} z2rP0LobImoX@_SH(KZ>=S{&ZMIhgg-_!=x6k0!bQ{V8KyYBMV0gJ?HDRjWV9iceVI zGufQ-%=4g-`LXv*LsE*h0KqCwh(Mim4PZLw_KgQ3x$w2j6ISNCx+zR@2Ey;=D{2pA z2zbG>+*9-Y{SAC~2y&-|qzZ*nzM6!3k%U@&gvFQ`p7a2ji7>OR8izWm%!u_l)$=0A zt=G}o&Y1SJ)MMpJ4Y!xKN31?KF*?h11JP7Z8jGx7b&%60=#LnqcL#7<+jWXZ{QdFzGYhc-tou82sYs8ir{uCH}Wd=^S~c$9UQ^1N^{&I%;q%B^7DY7wCFagW?81 zq%G%}zWB2+?uqg%3`g&n%Xs*x@OoO50t{{S^mK+6vMvSF;XDEtZcT_UoSW3=Uz|wd zYb=Vo;zfLZLoc)zPImC_*meKn2u_iW?S-PI0pF&6Dcfhk@DTTHaoIx5#bWyDN*D7W zyRKPcSv14o2fNa}Y&tN;7`1Zsbl74RVJ7HTDd4}c-Yxq+f9rU5VdL{co#L|GnOV9N zs_n27_nhDF)Lv$<&%anL|7PI=-r{s`W}&DQOAu+=dH#I4^jM~e#Xnc}sQj+XNsPsJ zON$tv(+aGAhJ)w&&UXc@&+aUY4Mr+JM&<1TGFNqQH!VU0XeoI zq7-|^#fII5hTXRq7ruv5wx_6d*v6G_rABbQ>DA5pg52NFH4q^7NhWn*ibO=bsyPpn z#k(=TLyhPipZE{DWf%;e#-M&+(8EQ#^SdTK-J>rGn;cd?$SgTE;Bv(Yv8erpB#d{` z_V}JY^U!w^!HM|uzso7zPQD4>^U((RvdF^u^Qc9=i-Qr!pQ;m=&7o}g#dZFLW7Rot zY>Zw;%34`ve%>BM=@63n3|d0%|AH2t5Nq#t+8wMWi}S#li2i~n-s?WM7Xc4YuI`GF_qcdy;{GuBBj@GX3ALa zY9OVm5RK5bvSnz&& zFb{eE0iD4>`C?Q(|GYJjI;D%Vm5m9l5dCOrzU7e7@i*bsF#h9bzyj#Ne=EJL&B~!pD+5y4mF;AI@L7cgODgNuKU^zp=bzw_5oKBGMJK>@hw=v>7c^g z@v6%Z485@b|K??=zJ_;-SAmP=vk>47q zaY*NzJiyn|^B@3^BK7Tg%{fu;-JbJiu3OPitqpcT~Yve?(#DC=t?>vtrFRQR@RBBXb4F#D?Poa z{(yhtyHW5!W|=xFQk zXuq@IzF_1t%quuPZ9AVQc)ky0rE?Ob?{+Z)|9gAAnps-Yw&|~_O@mRqAM1w9hxo0= zWm!g}T9XLnvxB#|cLU3%V|4K~c3V!{Lp3P3eDVc_WO$<+`AqXQ!7?VogIe-3Z(7Fo1m>gZ5j2wXTTz7v|Kgji)i?1K! ziFR@*mI9WjUKt7L8%Tk&yUs0b)Y~5!YfaaC@@_7Uy)etp6fxfi82s5Av!mUbbzX|Z z+~$!4^nu|)Rg!73YrNl)oDS{9c|!g9(naRX0$y^iz5)S{?Ql3)b{S)j*)oiQ=jJ!r zferl*u&2K|m=mvu^PC+Q;ePDfLX>wFsyxgNI0&!KGjM$|7YT^--mGzvmTuXV4#-x6 zzwt=+95xW+H@YwCHpO4R+-)&R3*~U%+xC@D!X6F{Cp^_yMdJwF{u?fknGl$+XVS!& z$f-nBg$-z`iWOS1$P3I4(>y&$v)M<+{=be2wNu(fO(} z65~(MN|zeN?iA?H;l9_bMekqKz;Ug73guh_S&wgkNSF9c>&E;3?ge<#Qk@uJwx(S$ zMn}gPq6oi*6(|JP`fI+~cZtn#rrv+r$g^eHHp*$v8CxvHN&9HZUh*K=f4E!3;(NsB z`iwN#LEgaH;ieYmmm9bF)Mo%SvULs~M8*df83@iI8s9aT%G)8gkg5f{`?Y0TFEjY= zkJmSN^sRE{Re3l*mc=kJx(%oI40zF!8G+YyoFIKyyJBDN5~K4h9&fQRpe>qwzcnl`HO`F12l16eH6rD8@6e;uCeY9c-!JpowoICs~}*i-yDbYqI<%M8?>s4 zcVO0gSmgQGW$XY!L6OAwHXWxoh1mB46Qvvs=dty?*27@zr`-~{3D}Oq zcK(;POb^g|T3~AOS(Fd#@DG=$5x@TMKXOj$tUUk2xsOH2F}gI%LD`%d&Z)^;nhrgA ztc89sf@WU;_xLht-7fVz{TC@FBN3OBqmE)(KMwOQ_IGy>O!u;9GBX^Kg;tyR->d=s z7Pyr0TRB9g{s>_KqCGZIXv~|WGHY}(%D#6J#ywV4w9$8{D-rgFK=Ps^VXo4!X$n@4 zur$7aI~oMXYmMwRUoDmcNg$HgK_IrhtIm&0)lr#9RWLxv?UyOLptm+0^nr`;Dc!P9 z7|xTky-vob+KNFN2o#9V3|O{i)>maBKY$4U@GvM*ot}Jl19)ggU`k3;_C%6HkNO=u`; z>Pgt{27ZAn&dAJ|&{XukApwCJ{@F%)@xd|~DnvKcI`*$nZP3s_fJZpjpVprPe)6|I zMSWbrmd~SYH6tC*SKnDQ5YLuu5mk#{4WQ=&gp)M&N&Fr$qgmQ^ZA5o!qjgA!im7Di z#~g&_y5aDl7qPFR6xDtdPW&|m>eCOX{l{y{I1vG(e>7! zxdTCf+G_~{aX%vgeCm{qJv6!~oiYgsC}*vDO9K)@Z^TX9e}xk!>vUQ_aY zo1vh;eyh-CN1+H|a=_-kH9y-}dc74ak)cdo0b((~Gy((mFjpExwd$+k>U91M=Zy44 zmfXtZHJK@ajV#hGysImXM&m}phb44+I~CayAIk?pP=MLx78I*!I&zsJfq`+wlX|tP zZo~I&S7$U`AE(Q|t%W>Td`%u%hBa5|2@9TohTxau4dw%dQe3)gF=#YV8w#sB8^b z3lqox(7bnxl^nblUI}S<%^3#$hr$0^^Tkndb~=UViK9*3_DhU zAdTSMFz+*S6=093?x)ABz`xAS&aWFEnKTS=ByE$Lyp7Hk0)|Qb&#(zHLla;a8yA>2 z*)f5y{=KDj+)WMvPAr&b#Tn-)JYljgw*>zU2dwYX3xX2A)Yd=mbNOWXS#~Bdjjite z7|%U1&Tz0ma&2N2C-U_$1IhM){n9>IQuc8M^a^N@{PIRWsakSq5h+vE34IAbNL8nH zYXkF!d)VU|whM%$C1L_)4M)I+Zrngt<%U{7$+3yK;{F0_k zT79ca@U7s!XLnH?Ds|7bQ4l15XYJ>efNKQ_Y7YSPPY|EsIyhbbU%deCrr5M(l_7Uf zu1&R0O?jv#`JM8~r}zGu@u!Lwt3rL%?}%9N;7An&C=+LGUQvaTq-m7zI4@iSO#qu8 zaE&AM4UHz3DJ1c0kgKG*u`TaZ3QJsOO};sIkvTW7l=Qu6H=d~dg!(%1NFWLTF1I79 z){^M~*9G0V4Xp8(pVwTyoy7)!kp>rS#l^8uQQkD1Ys&&+%eY`CbZKqT*Zz9oOiJ+x z(S$eOt&xKJN}deCO3%6VUMGI_KI4v<3^6=)d(axU$H`#1L7Zp`V~A0Cua zj=uC7PnaN6-Qr);bp6&Agwh;6#m$D+K(Dk{ox*|p>z}TEd2;!HHiD>men&ts4(3%` zbai)y>E<)cj4XzQxHn2gdrjV@*sgw7@4FZi;_howA4XyJez(=CXyD6Z&G>5|`pa#i zMjgD}BgUqBe=1y#OFSBgz0uAP14L4p5s^auqSltUoX2vIyu)}CAcOYaLtKK0(+ zP8v=mKGIH~+-=%wcK5MIhER!pUCtOQg$`f&+BeAG-$aW2EbC16kZAq~lduvXxFLP{77k0tuZeCfPf~Xe@+j zbnxJoP}m6*Q1X=gFpr__V@*^#t9yF$$P9YXPZ6Zt-BFG z`ZR%`s;Gn5ZUaG5<&Dmkjk#l=DPLUk4wbxatv!;)KL6w54M7eQvkRE!o>JLBiGk4W zJS#SBCG54;aH00%QIPaCs`wJb#flsi6$pHpohjjtRk|P{Qpv8@zF_a7WR*u8ci97^ z`hZ077c6`qZjc@}GsjA;kre@M7~r?G)KcfNCQ^BDY5ZkDjU&1v8wnMOt8Wt+nRGq8 zB56&@EEhGdhk+%8c4r_e>YI_5A>?h@;H2hr(@$?!Vjz@Mfmz_PUNKF%5IRTw&MW`p zi0jOB+de(tJn;|Q%0GcS1H(zfUcV=ODpbz<(4_`r&x=$2M)!e84qcBuKRAbSaJ1&) z2fmi9n4LtCf@(tn*vh7&P0YCsEXIC++%53O{!&YFUC&QkaaG}@``w@F4A0!-tLUlV z7U>JT-+UjIeG8pW);8TdGbjBZ^%O(#&l5o=sNXt|cR3By^ej+!jE6VVTa=n}2(6_f zC3diQg_Q*4z<_D4rq#2DMU~LpRB~oZ%Kj!wYlXWY(@Vry#_rM_aYdN#<}^s0uk&Z#0=?HI(RZNFTxl8i1bJm-SY*5Q|_;F?LIHJg7 zG425Ckk`-=Jfb#2O>0v9;YtA6C9J4d6}C^%d1QggmNj}@{8!L0O?{Nq070W-+{RG= z_D*Zr5A;a{>QzyQjGWeX=s@impW2>GOQHhk-9L0;_@BvAjTl){hD%)L`;+*u$*qD2 z-OXR>-9VOH^=C5qyh^gmS7g{7WgBqB^nu{La!SZ(eU`W$>UIJr3ixrEm#-zhuASXo z^06Jz49n;VJc^GCstJ$!d)NgBZ?b?@%UfsnTig2w9*8iLg9c^)OUWOSD9KE;%E+bx zh|O1aH>9)2H2h9eTIDn_RzqL*#JK5PK7g#U;?oJ$d(smv6461BR3IZuyPQK)BHDjQ2 zbnJkZx@h(L9PV$AMS60go+)j=p08&UEGaJ#;D2H%@d4@wlY2hm-8{UHUHgiJIM{z#6BR7(|FNwXeL~$>bsD z)D%7awt-3Ytt;|Jms|Brizmm6j2$cqY*dgSf{JaV)~t*%FG6U`TDsusL7)%9W-nO7 zKRRW-evz$Vd_a_bi&54M#3FHNtg-CWFEfIaS5@%4VXRZx5{rU#F%_MiO-q7eFBhb4 zU9FLly)@DH|6p9Z`&S@7es}(pU6fyGEm-K}z;R-(wnOUirj@f$DeYI*#iSA=b2#hy zqSfW^TvkOcqN-eUNdg{U4sVT94-%q{_@(ceQd1I4#~ioazs0D_)kVX372V#n`@L+^ z$k#q04#*5Z9?&cL`Yep1Ew*3IGiNCu{P`|({UV6P^m5AO>^=%jo2jjc7(|eKd=pE2 zIS}TLUokMR;I08!2mlr0nj>tohjUVSH`IMWKV_Quh(Ig|r2%(ucel+tu#$a8b#|=u zwWKv-nhbzIEK*tee$KO%jDETO8aBf6e$mR-SNP=0Zuw)`6*^^K5X*zh8nLAoo8-5M zWf`L{Sj|5j9ovq~)nqSdnb(i2x#Z^9^4_<3%)DP(@@qf&hHmAnc(*jNE)vb34!Xk# z*d)jyZpVZ2#!c2;c5iIjqb>$veEj>jxYnachnm56TcU8+Sw&F5(myy4W~r7Uj`^i> z)_8T^gx%Raveu2_<^3>DSt%NDqnXUC;%;l_WT92GE(;Nh?B#Nd@4!DL0hs|}_wiRk zE-AbwKIm6y`q7sfm1nL)21yqjk9Z2-n62iTvF22 z+%KpDfElC#Ot?(b!%N-o+!sr6>aUG?jv~u+i}PpSmX2DVf#ly`F1V$}-)Y7{XUa<|`SwJ~ zu^~&vEfUxQia!f#$Pae96Z%E>V|_cIf>`%Y>0!!1{+(?^#qw%8ry0{~$2rCkuUHZ@bAms*YkJ2^hDSA% zX8oLG;H-vyrq9<5e*|b|b$4xVvi)i8((*Kw8jueE1-kP~Boz=xg1QUaAP`yAu zlpaticp}p>v_jNww>>n`^}QSDvPKp2x00yQo`2 zb<13Do>qoQ5XtWVtO67SkoW|(@8o9r&>Xx3@l>B;+H4G!ncJL@S>(&MFwKnqDiQ4r z38MeVY?^viQ)6HYxSr6#U8sPWmx%2>QL6&BlhsTxZmWO0fXh}-C=xA_*Li>J&~2MR zWQ!ZL#&8+JGrLlACN<&v9CI&e2281y6@qda8lZ(UbgJp?T~ZFwRO~hAeBqO4d=5%U zF&9vtXochXr*FUc{s~%r2zqUMxrrayr^MK5(_jc+vU$0$xf}CGpVjsYOrCuJ~};bUwH+7^v5|o;pxH8YH0Xkr>m={ z@RqyQHvu3b4)r!H!mkAET&6Vlgxaaur&cTcxpgfa<806(C4oMXUiId&l@cGvi&+L< zlNugfhAD=kOszmR1JIoq^F$D6P+ek5*@wEns5)xgq$oZotsf5@Q-P) zZh$)AI3R}qOa%eqs#{C_smN09NY2mRwh!L@px0x9V#rtqY_nHfK%z%m*I4>yhzYGdiMs3~Vp0XEUQ=aQZl}sF)0iZ0jy%^0+lJjen6rvb ziH>DDi0$8aiTE7c?(l+`2rVxnE0jA3@MpGhS<0H)I7gR{cngzv)slBCuY(Ym%$syrPPjkd@C(&u=8EM@$6HA?JITD7*FRW1K9H)v zCbgCF?u+mjXCz6xPN&sdKL;ES!(sV3-Ri9- z8uR3><9?)=Iq3H#odX^F?rtAk6Rn1~(N=1%@_9EXtks8ezD=i&q#NBb@10yB1x=Cy zn+EdTgJ+IwDg4+opAlzSzcCe|KZ2RViS{sb~(v*!Ri z=qFn?WTp$v6a+>;3iT6m$Y*&*665C@Uo9x>BgIfR0Rl-~KBPPdZ0yz?2wZs2W6(Py z#=U#WzZA(MD||4smF%SNYyE-_^z%}D16})?vm743(e)O{>Pf9&h(N2xG?(o7e^UGV zDpR-Jq1LEJq4WbPF0&hBJg!$k$HP68AkdwkBpa{I<3`c889tRpk_rqji@sLn>#ihExmlm_Dw3_$~14Z0HP7y1LW^_Rgi)oZRIo#X<57mm0l% zQrN*z+lj^uabGdh^^Y_3;v&ig`m@#aJJDX>Mm8Ev1{!BZ0OgEay-d5v+b})N;08$L z-+LLyqy1&uKm}yE&Iq{OS4JjQp-PEZ=jc?=c1keP>}b{_f6NJzd1Vp33aEUEB19U0 zBt%{TUA0|dL7)Ks%Q*j&WQ1tgIVq$@B&hDy?(RMLX*z@p<=V%W_2r9iZ?a%#-Q01L z-UHZ!%}W+B`C)(vRDG!z1&GD3eH_}2rnKBY0{>Y0Q?s@fMQ<{)xP)~-FgeQw(fMym zt_Nj<08_bSFQ94ltcIt1=_jgNY(piMoaLhYs!~okM{#Fr#lDp zZElbHI!OZVFKcceq@*y>ev(&Ew^RBo#jggz-BeItlqTG9+yYAC@lWJ`9~J<#6HXze zBhBu+*gZ&ONg6nA;p6m9urXm0N4^=_Z9+H*;AXVjM89`LIg=+-Zz*ksZp>i$d;x(7 z2!9Qf;%exm@3`yMS|OpV@2u;|FFL7)n^)u|p+FnXwojC?gP0AS133^geA-pHr&;Z7 zfx6@7B_Bew$M~)7w$kdL<_Tj&qUBE8y&JCvP|2W<)ZtazA4Cev4)R5T`ZhhFmKqGa z6GI}JewH(^dx%Bw)a8W$(*_U<>=E&7uPdNp1)s;RkH>BWW9}HoS7il!c5B@V5WU2X|XaeP5)D=J0ZO*+vz^B=Z&XDWS>oWo)b)NES@P# z`8CAkaE80@*8A-S5We#8tJDhL+QJ%fr5X7bBaVF=lc~Y|+Wp`5?b<>4nSNvIwQ#uqpWEW-DxW_9 z(`-F_4qKywLj7A%u%p(V3FX|vN>_c6GKoHIx-FNioW;VqFC`ezP;oj;FQ-CF&GyWs zd#K?v>I7?4^@i@D=#roHAIv!p>|+dXI4tqWN_S3^ssSOUm`mpxpS1f5O4Oe~>Gb@rzn?K1?OrB2zO{_{35>_np(UzGIAm zN?_!b5U8x74bkW^hAK}39y>1%a^EI6V0=+ITfroDHcIuqTWA|goOMceT7cl0|olfCbCvzW(3W|Hd(IvbjCRuJ*% zUQk=F&na;zU6G=OCX?raGE4I*I{r@4+bF0i@g5NyJCE)^wtW*Ga88{W>gnr`**Mzw z9en3Qgv@hO!l|hTffm&GCZ`bRhjq_wvzKm$=vomn!`=$^clV5Js|y)&r)js0mCvI4 z!7p1+U$JS(eD9$NIwbRLSM}LzeZ)#QMz7Iy9durd4;CMi{9XxY2CtsecYH=8zkfr1 z3R)3DwHZO9jEG^huNL56-|p3_ap2Q8#^1*G;GfckscgPI)*R!u+r$eO8{&Bobdv9< znZxUWd93cie?^(Cf$R!Ql+6tE714PWE%{3v4>nmVX|JlJsbnutUFmAA+1c#|u1Cud zZeQekM>_ksC4!SR$>i79vl0P*rPC!h-mwp63HHVLW(tY~hRBHVMgl8p((NJ;b4bHB&g3_HwoTs6Mjp^$2v+)H@ z91>1sFzMYK0Nle@zcF}ywVk~q<|v65y0&1IW%Q>{|4BEg+X=l#oPHw5jELXnlkm9X zT%wxTmjMR*vL;<0Ig)=NG`>oahn((R#R(zHc{V5!9jK5tD&9Wr=80Yp1;6+_4PrP0 zQf*NY-m=r@s;LCOM!M7Izf6sGcW)q?@_L*ZRHo1A^UDakzRI(!2un%;U@5#<-%M?$ zKcGVUz^rva7#>7f0g7o2%S*iXDb#|N9AoZ)y8Cp*JxaA3jK?w-7rFGR3fMu1GVIqr z2RqOCXqe(F;P7NDpSBMgErQ~Y9OKqBH?Y> z&ywmlcr!ZXf}mEVCd$r}Vx=O<&W(rjelvrb&fY>A?hYF4PY9aFlxk_uB;3KkeKWN6 z|9|0FsSC0m)1u!hr2Zk~Bw|KtGE0-8F^Pv#&Q1H_L`nK>w6@$65cTyA6NyTGyXzUWJ*wdr1kq@4c2F0f~RQy}HS`^`QNY!^_^f^K37` z=m@=J!|AJu{%PDax<(%o)^~skP{qmw=~d~kH+zbwu1I9%N$LcLT>}N4m#gK=DB5Yp)YL z`5%bP+TNhj0wW8d0?qY9w)*&aq0D*X=JAN1GOt~2S}dFPP3$CP=+)z7K740rI>J+- zGcf^xg^G<~^l7FM2SnC;hvrak9&jL8Egj8G_G|>9VAqDknf8%;Hc&#=t zBPtZ8Ut&wMs9|$S;9vGm&JT3*4uhDm-*9~l+rBqw>6P$`f4(9-AOB|Q-0x1=IXZYDh~;q(p7 zpUjVFeWa_Z@7lNfBN*DjnxDOd%FEI!j%i}k*Thy#8TO7?kmlpqC2I@mtj6cRqd#!k zc81<=vN6G^Kb?wq0Lw*>)FahY9!V#kV33XecDmsF+;ceu)zt7y)bXdD*k& z>8@qF2d2?4HNj$~v5!@Ezjp+qbTDYK&YD~A8Qo-<%Gy(5pLQ0{QTt{qa0M7)-LT`_6=0Nn^hOneZzvx zM1DG&Bcde<^Bmb2h9 z=(wWLO$BXw??=6w1VTAdi`~L8SG>H`&D0akVoKHvV>ga8}c&l6CN6cT8+aK(lcpzSDIOhI@!95I_M454?)dC zSV1sFwBaqej`a=L;7N0;(^3yOHqww)V6%JEcY6(Q?YK)i zk|akTw5Hf_Q-Rj3qPcB5kDfOYs-1!iRp1ZT@&!4aXik{ouV-i=p=OGud*Hsqu+T>* zg4=g!8o9vp4ph>TYEfOe1tTiz83m&kZL~dm7p~UEvLEv-SiA$O0_A!UQJfJxFqIw% zo+vC)t@?KQS~S;!Op)Xj>Z0?}5+Ic;3t|uTD>Ke=LG5Pz*(=e5LH=67qM5Rs`7#d# z|8(?vrZ9ehd)4n2gMv(}@%2M7-~zwlpfhd)>Zjg9_oZ%!ZnwL8WzLe^nMw8ij=VVn zaz9Dwskkyfy5a%qy`5be`UwQUzIul;HbJ7dt6Bv`hA6--SkVC%kU=%|xq~BJ2Q%gH zPr*mI_Pyh^<9*fK*HrkE6}7TwBr6+`xX4v=yL0R@BHe0S#gy#^qf~IilzFRj0_XG% z0HGmr$clf$zUA%qr~UaIyXowwD;q;(_NK@g;}tPM_R6f~jr$XN+ym1?QJec8n_GRx zTl9ntvg>>|157=9E^0;KAGN$I^;BDhaonNIP&u)XDj3w^00@T5srU{JtqZ?ksqBj_ z3;0WBu%v3b{TERIGEY}?m^(2vxdOuE1LCw;E#8AI%9sG7D- zzxm#*H;QRdbv7MozTjE+xCZ+$R{&Km2lPo8l+DPwK~eYLmyi0S9F3dI@ej_k9MaiD zD(w@@jCYLOP!fF}GR@*u0L|*k#A@twm4NZ9vR)v_hHR@JB>qB|oUt|+4&|umpt@3$ z?}o*=7&mhan6jot2Kvz%a5BsquB;aLUxOW6;(=zbj30eOH#Lp#zYbqKpG5=wDe~-Z z;Z2;@u&EKz2VbNXWTN43)cr_K5C@f;rXE5mCp<92f9BnQoyb~S7K^gwewg=d!k_~M?Z3IesXNsJ>(_g3J zD^#MA$xKvAc-@72$H069D2)U9T1}hHKyq%4X$71Ptb+*16x{`#xbDnU{XxG;R-rUA znC?AZTWUQ-X?RVH`Jy1eEcyd@D%`lwjOJ_nH(klHYEH*7(>mt4pi{Rn)f{J zN2=J&kwNMehQT(M{s#C+#)Dp4cT{}|T|cOkwGqO0tfHh~OdfqnDsS=`ziu*oACzC% zTXKn1d^9W5N%nWohHf>)kJ3WNUukc@LQfUN(7G7U4^kO-%FFIdc2xjmQ}WVd5Nb*5 zU*BzVbWrw%h_cQIsi?(a|Oap2NgdWYOI7~QDv4b@=Ba3RB)4|)U z`_8<;@l*zrsvxzrnS;DND&w$Y)$r$vyyrJSttdylmGo)l z`1YC_n{qX)$zc{f>1{TgVq@`C10`;dz2)4%@IiTsZuzZdzVJWUAxAJP&~%6{n=(7j z@x_aP@@i(Jx0%*tHN1TmLGxaGT`8`G)3f?LCO*h;N;%o!x5rtG%D1>vYgZ_Hi zm!R1jc~^bE&n=D<0ZNluEHCq}yli4zEBCtF^Iy`iBh`Z-ycY5UIy0wi=lNd^sdihx z@W0HIdPyVB$|>%Bj+9TUU{Up={?qC09+nJo zk*25hOzSL0YABAHgS%%AXSYbc57TUmo=F5fwRE+c4x{DbR3*5 zy-i&}JMfb$fL8#d-^h;Fpk8o=Y8)l4jS6jMrhafmX+bQ}@?-0`fwpV_ZI7H&sBz_E zF167H`f|bH-ckbtJ?^x72-f`whs!SG-^O}LZ)kX`?-78awys54skxb*VA8Y44(DSN zi_rxzm>9&9DZ5?yk>T@m);^Vi(T2?Z^AcjkvVvZ+nsWy&A(82j37Hx=-sAa~X2wpF z_Lpq!e;&V@MhZ*(&j}R$xxiYD2JYVh{8S95p9RwYjetxm(2!N zBkHvq-$TKc!2KXiGkG!u19>Q{h53_NY7NIKQ_oL2LnuWG8cZX!M0Q~!1v*KttEimfY9sVP8h$5gClRWhv*uNNpD@@LxN-yfX#Ur)U?bqNN&LIPp$gY)IHe zY!C`|FOtQls{-ay^2D<;RI<%i2WwkK#NoKaFpA@*4iLtZvj2c$5C=y701!9uN4+@q zMOb~4zA3A}GAnsl+Kk&@HIckP0hi*mrh?zX_)2@1>;?Eo7!)`HoF#3&YXC1H@wA2h7obr-fS!*eP_MI8lxH`Hm;S+)$?ta+Wg6@9NF6s6$!lgF@p+I=Rcw{&g|HOAdJ)>c#gP7PqRK}$#dJMI$Pw@wRQrPL8YKG z9vBov+mpN^-%QL~_K=lpLosIN4i9$+ED^(QLG4rS37q!jfLU#Gw7o$G=-8w@GD=gr z@$qa&C9AuCf~3B>e%;@IwGz)aALdkzTIJ) z#xMnpC-}0}hmW2JQgY5iE!mM| zPq}n|ki&yZr;I&r@WBdqydr>zCzB>Kv5zW!7ZEAH-jMD%xN63t$AdOZwJ8+5Sl%}k zq0SinJYv^0(^Kk>WODP;JzWX?rG|bPH=*GSu%%N3L^OGDNEC%JJ4IJ$RlNaBhy}QC zg;jd$o-OF}loBj%%VISEdD@{&ZsC%*SL-XjL9bV0v&$;m(no_m`R)X;VTko(5@j#Z z=+Y+|$w*$=R+{6@SK+l4=4fK?)Ywe@%!*`o;g~}RO3gW?6$L#7ZEy8MKCme0_%KWb z84iHx6VQwTDv7!mTPm5sKg2o#Dv1AVHf8OqNv>f6?!rBwNh<=TGFRlDv0^O(Q%rgQ z5`d5|vfc?uHX#$W@4u7Wp6%2jq(EPij?otZklEaQ_t*rJEIg0dmC0=|a#WdTpVGwi zg9w_;U;Um8_W3It0KxK9n8f2k;_V%F>^^&N^wU0SD2ha;i*-MB3{+|hJ45%(NM*}y zw+cS?)apV@Z|6LkvlgjE!I=CJ%vWLIx!*Fkb)2?4oH&{^rltyg&J9}xA1@u()VWe3 zIaX9=m7H^Tsj4*Nny~um4ckjFvW-;|U@F()@7`}ZuPUwrSP3$p=(Vp-vK|TPjR|Lf z2*_`s)vBJ!ZG;2(p^j+-I#d1Sl&>(eNik~(Bb#&}gzmjo@FgXEfH1NrRD@By@s+_E{OBPdWt0?R^>e zehXos>D8GOK5pS@!kw0#9s4uK1B|x7m@)2YHk$dJG;emR!J>|4!+^D2O~GVp62(yG z0KTiEge4WLg#Na(Lt!!@x!1}dPE{rOs^!P{v5-z{{&eMGde#yf$dNkaB0u7S+d6I- zl)YS4alTURxfVhR&YhyKC#-jPaqh5_KUy`V-E)oMr78`J284VZyIZv!EIb-)@$##8 zSaNw4|0v03U+wKVQzmle*r5^(U1r#GbumbYmWoKV-1TWj!8-0h$c%xlrpP8_C(E6Z zK3RH7TR>n|%zHZG&IzbKGMLrbFtua3ocm9be|(%CPXYZ$LaRJKKDK<1z=xqey#nS0 zlf!J$HCM8zyYf&UY%`2%&J;uk0T|7_^6nCN2o1KDMJ?^fp!mjFUoc<1_IO7~3PZ>P z;Q4mjHnOtpG-=BCJ(USQXlGCdF62Frelyx5aXXebY=8Dp`>C0K(Q<-A@Gp-lK3;J_ zFx0y55ir3HO;Aj>Xw%jQGZDunJo-HyFyiy@M59%uqENYIPraAngIW)r-$?w;pEA4K zAD4~p{F8Ysb_?b|_xN(OO1Xqb+!du(jEavIg4;&^Q!v3ch~WTZ-G9}_X;{Trv^F1@&c1-}r2i>hi(KDo0f)%pY%w~!95PK)c zK=Z8G19Yc#$;=_`o>6MU52GqRyUw2{{X^QVq}}p1ZDu$JdpQHchQj`h{~86ZBxm@V zYYwCeYG$bE3ythFV1wWS%&-3pq=bWid9Epi`d%PS9>HvtWTlp`h| zSLPm%x6NyEu!DT46553cf-{guENT;affQK%hdg-oAC~9lOQTdK%p{kddwaCoaTH;N zzShc}yOZx7(1BZ;jiYjY!)=`&if&PZJiZocM{qE;Qu*AZh6oUM!QdKlFo;R^nd? zz{=6jZ!Ghx++CH^1H3Wx9}DiZI)^|d@IOv-9ObJZV@Vvv|AVT`+IT?fe71lCnvQu? zzXF(3YEZ^C>-S11U@1=&918?@#RQ%%JUiOO_V(Fu0(Q##N2SDAnch;KHn^gv`1iN4 z_Q$2*u)`5l5|*}CJ^^Lg9$)6ep;KPO0XRAXTCUrjp7;Te1Fcm=ZkhzOb{KTf(ce4! zM9TYcZ~*X|KOViAEuML1F3#Lw%Zp);TyP@lFH{*}GE(VJbZAL$e1aOYbYtar0@z8; z>Pd^=$3uONH_S8*l6K!&YgV2=@|43jW*E23#Q{$Jl%#OM>ur<&&z$&&zzH4XmVpy0 zC*){S7eu9O75bEYju3mnd1q$+AY6!bnO5N1Rt5NVUA{rUT1Q~63US1{jyYkSJH(Rw zh!JAd^Fi92F!7VhES9q-V9Co$_U+R4h0+3XJOFY0q5 z-*!|AiW2)o5-~28A6{I{C9C3eut9`!#64@aN0s7DPUGYg@`1_YzBg{qT^;vcawle8 zrQOqcv*&B$L0ou93;XX-!JGV$#Z&xK(Zj(%rnszCt`@j+$buY!S!2+gmDcpUr427V z_Q$aZREFc43x>XsKgMu}om*-^>M*NSyTg6!+Ro(Loo#T+pa~CS%9DG|m0-hGW!IFo z66Zvg^d2yQfpch|T2~_Pe@D74idXNK**gA}Eyj?9tz6-zK-&cD8qrDaH3cdGVlWD? zwdIiKt^YM9y}ajuz6@bWrHfW=37eAYT=#YrfDeW8Sklg2!5g{~YcYqr)jqvr)Dhx$ zE=LJXH0!_wCQ7_#jm<94%#X-pp3Pye%+_=`@v*eejp&o2jJ7Tco=|A{py3-tEU++Z z4m_mr*b9QE)KsV~b^U^S#?=2&H=uSl=wqo>Lu-Fx#{D12{E+U1^|5S7h&1}*+D-x% zI_=Bwr1eUoelXP924Lxn4m{ifFLpdF_A;eQBA;jC#lt>l`UwS)AAxsN;>K2niO1Xm ze~xjn9leV4VkkV7gu&>b>{A>k$58N@fEe;-Y_sF=Q-<_Hf?+}%%jaSfI1m0VTRj;5 zEOjT|wfvVkK8)-?)&VzPeCvfl@2!U7vf zL1ZflCd4n7U|1RwZU@TG9)R#_h8V*|4h}6+=UrhZKz{*BVZDPuLW}skuFp07%yH%X z;dTDiTqIg_DC@xYrw4ENxjN7$tXK9fAPPG)?^#E5d7EJ;k+o)@GxO5(qi+7_pG1X5 zG)!R@}~9hBmX<&k_F$(eIl?pH*Eugy+ZK<{t{#DP${| zL)udDO+6R&-z{J@BeXYX9Ev=yx)x&qtL_S-0t45sJ}eiNwS9Gy8zE=J7iFtw{nk&4 zz*(CxW6ou9ZAm&JR+KfEkPmn6LWT~gL7r}R9GKf%9V%4AS;!I5s^$Z2Ye~L)*2uiK z&C<(XhU%+9##?Je2QG;t_R0qr@XXb|04!+T{<8rfl4b?+GN1dvVk*JTRzhpLC6kiC zYun3)JkH2-2s>HrU7=JSIY!*OGc)AyFm~t$Sm(mB*Bc1#y)L#th#0-in6XrCx9sN^TlHZ13>T<>`#QTfECg8=QDR+bjZhGI`jLHZ-7)^){+CtZ76Nh=Em4)qYjO_;JqGaiH=+ ziT8@+YM^7DUq{gQN&+A{vTuiw=)#$!AM)I|IV+eWrov^Np(!1ckt1_AsiAumarZrC z)uDspe|V2$BNGxGj*Jd)75Q`mXNnlZf!cWG`^{=k298mzrj!^t!j;U#H&HI3$imL2 zuKxI~9E<-OV*rhr?2GDu$OA79KH8I3agtY0d-%-yYabtBWwd)`G^no(np4i*zc!)h zKA~7)s)`l?zy@|DumRE(s0^bINSrxv2v#%Qk$6cGdI>Hp{*@$$$F969nb%h{1vaUlS;J2wQM61MovX<`$Wk3c13lj^KJsCVnRFc z07H+8A%qaiqoHGkxw%mG2}NPk^pq7|bLLE!&&QP-khl)KQh~S>`^H&rfw=ToQ$wqR z-G1)owE_Q10uzV#0eLs0jt{%an~>d?k9XEWkE36QPlA=)Yh=JoP1pEfyeD~v29gqc zPRpyI&j?O(c-T60BP;T+PV1GBsN6>2JxrBo;T@LL_2ztKD+6oVlX29FtMsIYnezTE zu>l{2{ja$$pCgwb)D^Xt0X0M}Q8npLb=jNPV4RJy@f6oxHTGT$L`4daTmj)4}cGZr*S;L0foG~iOP)4bbsl$X=pe^6qD&{e*1qN zAye?M|38q{iVE2Bl#1f)O{HGq509Jq%SYBQ6ZysKJ3dx;t>7T}i)XpeH=RNxvLV|S zmefXh1(wXX!co@3S!)-=n#x$F#>~vk*nE4T%6M=&k@AaV=lc(5aoB* z7{itM_jmb?)L%D`xOBDTyjjw#$)zcxD;r_C1q5A<3xH}!iX^W!Kysk3q3i8&I7eZ< zXWz-z-Q9YH7ojc%XH#E5HxH8a&s5?cQvVM?TE}ZpS4+deE!30>O4~Yp>?EzX zx5p}tK0uTphw?(YBeO%UJp5f5e<|-KQCJ7V<*}7XVzvqZbOmqz z;2%Mm%K)%$654?fW*7t2jDqf%W1oR*Fj%R@71%AFxHVWL-7~kM^pY6`S7YF5f~yyv zv^AH`we!S+Uey&C1YDv?d4{A5K&e#kPGI#{h; zXjQ)@&JsJ1!+*7Y^ZT!7jxJ6uMjF((kvgA}cLqHr@}%(Mh|!bOS=Q=;e_yB5Dhs^$ zcK;rVpokR@mzlXPJeBOa#q}a;BD^eX9b#&m&6uYR-W)mJjZ=E_SlPpK8u&y`8fG^-~vH=d$p;G}-RAYqtGW-kl!ofd9UI%sha7iSW~2SNdQ` zL9P`n(80pOqDI0MXC%_iGiw<&W-G?;O8PYHyph45wyrQ{^z`0?a&~JBW}0herkHfG z-EhDshqHln5h26E5<7!iLl719Md&u0j)2xyhu1dj4RdN64g4^MSZp9JLzF&b>XQ;C z&yO?sdRn&VOYP5P@xRFidstXXM+{$R$SW%9(|FVNGx$_*{9i9X@Yh*^H0IO`7sUgA zl(@9+anY6%(qqr*anGj<&vP=~629FaG%d<4{tcyh#yOb};_Bd&aFP3px;8}BQBlS1 zxAWh}PvN|g-gK_*y!L=6XyS`z#^Y+%^GPRxPFkyYs(yO!=D_o&tv6A{`X}LtD_|+N zZ6plY&9OFHG}hQPCA)R1Ce>?{E-v9gjMxGtRV-yiHtnK%R*yknh!-;69m`3sh5T|k zaKiFR$H8M1_keU*K1Ho>@o^km*mMp{V?n2b5UTZqzDPU1UK+W(ev1-)=aMjaigH~NCGgY2js~7i*Yh8Wd{EB4Vu)x6y$ohaCv~Z2d~*Xjq6pUogu{D zT1MFobh1Cm!vzeYAJ?zRsjk@m%y zKV_BP6Wyb>Hu}Miu6y@sOmoLN$FNMZoJtj;%VEl8Ppn@_8A8`eNxprW8*({{QJz|@ zvpg_cyes-QJderYNYYANtCvo%(LsW!(KBa{75rFaP`NpWX`rfNUDx@QOSw3|b&{1C zyrI_FK&LK%E`1f4&D59-4g4hAy}|sUQ@rncv0Eu`*-Hca72-J~Zbe15Il5}#5RM<- z$Wtd+7VZGO#4zi}yGf2`D`D@|72fbcgu^*DzI_-C(g8Z53OTnP)4m&Fup+6_o9`aU zvZWIhrP`EcOG!qqg}wb+bh0>aeJl1=Tw7JWtB=KRie#*-7|#9hmWZ($;q{haPe&lj+L^RQDaP@%=$jg@3kC8 z5c=G(2j$MAH$oywtB88aWyV#1a=xhM{mku^_gQ8%DypFu78?~6^U3j}%pUQMTRLP? zia*A#;*;Ghy?I#l*SD)Jfvcad)~TWNX0E*vjnY5FiSeQj5Lei_8YJ+WQjXRALex7b$5k2Ee3ka6<}9E-4WGJ0huHqYm<*YTojJWS1oU89ynU_g7hfC$x4a=Rr* zwJEth0)Em^b=yl0<3cXx&yml5=L2MFUlumD-C}^K8N}VcRX=mbZq@!0wZ8hPJniVn z+VzfcMpJJfw$r{3?m>&q#`9&@GcEB1v-Y#5M%JeKa_QcN^khT=y7qn|bSnvmk4F7r;PM%O} z9#fWPPs&DZe$#?~-H-~zWaeAsB16IVfNF|W_+dryQxcn{bqZktiDL*{H9kS!HuFrM zT36Q{3-dPNLkhu2gZC4$sH-WpCsDBzB{e2oFcJ7L{(fm{L*A0QCkT(x5%|>y-$mNN@qXR!QvE|;S=_#%j~?; zr|F6I@-=6)&sOh~E%FRjm%LSfv?UX1FxJH9A$p4(>nYvE&csq9w_~Pz(HT06cSDJ+ z(?~eQVdAIN%3ciDbnm3dsja_WTc%SgO`hVYDI|DoQ?iBeUpt~q8bw{VYD>mA5y^2P zmm=Msb4!0c8KvndyINN;gB|8n*trNx@|uYyD**`!;~4$ZqTcSMeCUUsu@CmNGKm7_ zaxO)pA~r8|cxlYX+U+yf$p~0#_#vYdwMC4!i%X+vghd$drQJY#BH{cfIf-(IP#NEh*3^cRxLwUy{t)M`nMIlTSm7CfCQ-oN?SSIKC;b@V99m}y~+xhfNe za+$W(b)#OTkvy=*mA1D?&Ev|7I%`PGZ zJ<>L>m=%}D2bT7pnEj?-KBok0`1Lm&+M;x&>Sx|gr`LB~RMO@JC~4F`;8_k=9h|Iv zoM*E`TH1FVVOx8c?o^@^}@*xM0yk`RCn_24{7mWJ49z<;pmS52aVVC^hYVog9>Dj4q zm0ds1&S04JQC6XA#~tKx0;jgyOnK_yuQy{S0+3pbmxzG=Sz_b&Y`%<#_!X0R^s+zKInc|I>NQ=C;RVf zDIwLf#A12S+E=Xnf8!-aKcbQS7J0cx159b#^&4PjQ%}{bub248l{)m&x&mz=>#|jF zdBC&d_ptkW64$MlFGb7m@JYPiw*By-q5KY5Yv82`+G;69{iK`u^v5BRR9E!^7UHlV z4F2-HsLSqC~I4TTuTGLCYr9Vlnd#i8x8Vu~9 zbYWlff7T?X+1q%m3js|f&-ne$KwN{?Z`5M@ZETtpMlY{DoGNynmm5lPy$b*VBVk?7 zJ9XmHb**P|=S;v3IQW=Z)o7l3Qzx0bg3h z-XLw2;8-Ag-4JUqaOwsrv#HmLGBIUKcC$R@Pi|B(Gyhk$PTUY;hpz(Yd~0XN+GMT) z4vZi=e*jT$)uN?SIrnUw46Ks=Ls{bcAGJ-FgNCU)yL>+o74dNRK?O1&4R=x~o&=hPXwV_kf`sT#&@9Wf^D4v{c`q|-Bfk>J6DzrQ<6Z&2 zym2ygX{}SF)MC?)ExJUgOoR9Kk2AzpidHsbeJKE>{vys45=;)fneZ~AND@)U&hC~{ zgC}1J232YIH`I*id?^DsPGj=+wlKhJ-@;4)no~1<+p-S_4u#MCs_B1*hQR%h$_nEnn!wec#pvIqkg7XldAGK|!~G&4t+)95m? zku^MBumnlYK3xsob$X&6A%Pt`v~j5-?|WeG6aex1#b1gjWl)@>opRv!LQ^}s2nEmk2kp!i-;w5DO|nL#&rIj<7gRB`n?8G2j#zohL&n^m*=lOcquu9nTEufBq@5u;oj#!;5}m# z(wE{Hrwz!M(5JQ@d+Fi)o+0!JeEGtiz>wJO2l5uk(u;tN{QR316?NSb3Z8X87rwc| z?L=ws3871oGFXtlq^E_Ta!V~9`w~@+k5fLm{?O>Lq9Pg!<&LqPR_u)R$Vni^?!eN* ztzT5%QTH}W@Q!R(K`Q+?Km_OUJj}s{oLuDm=+&imGXp+xw~&$$6QN2?9uH86QpW|y zQA_GBuCzseE~`I6Q}RbgW&WZ40>B%K@#4mIIL-tb&BnJpkeeF{7b~Z6|g)P zzL?UK>%YWCu9a+okA(zZcEVA!37#jRpt07A3^@E}pL&^(y^}39>f(mm5b&KC-DPq9 z?7|Fo-7n_2_FPr7nRd_ftw91g^Qqe&q)yoqwOw?+kp^YyCq_0J`_EoPWv&H6tEnL! z^t`vrZhqh|Az&KDtbZ1l%uN$nX)mjlp!(6s!N1-~#v^)Turf$dk=RcIN)oY;*cl^$ zdoDa-wPBi#J2$%thDD3%71|7k z*~M1aiwFB+dqDd{w1zr2D>#8DT}rPjMRm)>#guUZOg={CV1pbe=48o_Y!!vFm92+r zrOF^zy?PfBM+`^|`p)a4C~`bvwo$4F<-D#%>I%3nrQ+E2lAoE@3)Mavf~{N?McMDJ zyEs#VeF2K{ROBK%N3S8&I7An~H)1sOl#AYNL9L6-rV%_<7EyxX#(zvG|caAp(@I4p!Q(#F3R@(~2{@xThov7_wy0 z2fv8jqYbWAJ%{p|e%<)?m>5mzuS92S_zm3T(){!SEGOfb0eZWw zd!v-*zTdds_Qnk;^7(d!cMNVb@olmn=k+c&z9ulIlE>6kZs-{Fl%)A?)l!>} zRaI_1J$O%Xy|yyyO9KSnMHUBIW?g3nvYg?z#TI5*UQp*Ser~K?Z#UVoSNb=OZN+!9 zHtuhF)R%Oo{?PT{jABHdiIMi(qOBWD|#{I=r_;&!r#a$-hv@( zGxFCtf`E~9Ucz|?r*fLSu)8Euu5L_TcbnuDXF~iS>!<#5KnB}9GFln>KrYx?W1sgv zAs*~i!U!Y{2T9Ek3rh{P15UhB4{CVI4<7ic)dWkc^UZw9z3FW9h08b?x}p|G5vx+ zmc8V0OboFHFC`R5sV+ZIg11Ce@tftJHxiVq!wd1k)QC4zOXkk;Mkc_uQb}p4%|+~y zBA?gOq&*U&GKnFGVBBuixG~TSLe<|lO@c1{rOc@TXTMKTU-9wx z&7UvWr8&QZ!5%2A{X_RCsOrDNuV@j zAO?I5IWIh+wDB_n&*oEEYv#f;15wL*vVQUFmS8hk)C+@)E;MMvhW5Ui2j7PE^B9Qy z<{Jk|`(4Ox>r~kpE6$VXZS09oT59Iyzuf>jqf)COEyJW*`P&V(b2G$_2N&f5uuc;L zZ2aH>bAHifz}6S!?<>K-Yr0UwcTRG3lg64R>@i3>D)u3Gz zs7zW&epB9LhGmHg-a!j=GeezsHo+xe-R>`r^fbz=R?7K-L1kik0I(mwO->F?qeU*Z zKGv#WaK%bIlpFx0RtdN7zf0}EFg42ntmM8ofj-jP9%!U77jX+N0R|AsqW4LOcK%gV zF&47Ne5Bj=vijAR0dOQ=tmEA8QvE2qa08-8SuO2xG8d)8F9lnjU3&=9dydMDCzQdY z!{6H&ptP$Ynf6Y^k9~c_tuRz!zrU-q>)3S^27XSRAS$+O8Ka87PgM0~<|U1YR>@`| zK<+d#d$cNwwu}!TZl{dPltKvVj>6nIMDW~=xR4e$@&U}Zy12PkB%6}o zz7bJUtdoEYMfYH#>P<31{AIG$c}4GikN8@Fr!%HF%bN3rfJ>ZeB}!Yf(>9)*90{+q zgm_H}v6XI~*H5lkf&58|_7Bp)W+eo?@BO%;xdzou0cxKwv<2EOJPfh7>iKWE#6>v< zT{8PT)5s{q)sTPQ>~~+9U*rYwvqT!yjdbQoC<>6C0=P`1T*4w!ln{>)R|8ytUJNSy*>;WIGFpKT z#lbSg2-z4{mWR+g!Jz*c*-uklEs*sM?i4uxvU73h6KKr`fArMo6|~1OG3 ze!%_Y&2wYEgGuPHmgr`&Gp-yPStQ8(9I-qO+)wlhdmaJE@p8%Sfv;;SnD;$@KL;f+ zLCB3jOvwb)I_n^$hnR1k*w6nCm9k5Ds@Ny5qkrf3w3+i=EIjJBpQHv%^Cgt}X`z^^ z8G;)EGWj24=mrj6@|3P(xX%wQm}QQZ9<`6%D0b>1CaP4=VLB&VMN#omk~4%~@Hjf` zK(Z?B6kSXYu&~~FDH0@tS`y?@+6RZ-8 zr)azUw2pe%J*nc~ZCqeHkvYuaDGDdQ*K!~aEr(mpeU zuZbv2B`EEo;KtwdZiR?4j;(ZzexZV4O;FcyE)YJUP=788So!k{k$^V6K$Tzm!C8Wb zua1-y2k!qLm!ddYC^ntcYf>v}WEyapkDHZ`W*ff*!(=+8?@3QWjpWYX?@p383+p8fz*PAK4lcH@d<+ zJ=Ar=s3E4GQLy#@ely@(j!Mh*wH-&Da~)TLroi&(UYVhDmRX4d`;smp&Ch#2OEXx3 zjlm+l%eT;WCUg5j@8>EsRP#}OPxBOS{vWvQQD`{wQWc#PCF|px7WdAyRP!({KltT| z?`qFJ#dj+Q#6vFEEDXJfhWZLqOBR|Eu%tBgixV`d5mJIimp-83|6uDYpte@a z6pyt$!GX^ATKr>Iw;K1~#R5EL3oklQw1RAXAyPBd#X-|aMr{HxA_AF(#*V{wWiIW! z#&1!P_AUwk{ft+l$*e91Ddsu!S-eX;D7Y1T%%-)l6j17Q#z0u5ktM~afyu7w!mcW* zs{CJ?$xrheap5^)z7N&nn>^j#-ohto=f;MfgBzOph5DT>LMyAp5z8bkO&&d*EDCIk z2zU_?=~BvxZKh}CUS1VWFv8VX!^NV{x6fNhsL&~4Uj6v8RVaixjl^wrbN&ZPd9z?) z*X)wC?UEeS{-Z8)l~~xPt;TTFY4x$H&F~ngP~dK}+_3bE5w;RUqVKm6f(=(P!(jmk z?zeZfH41>-ENIM#;qP!_uiaqR+sKUUQM_jF<~&H1pGs_2v#aA~vG;>B_{)31E;jUr z&Syo|$*{nMN5&F^cr+-W`re-O4)tO?J+8Seun2gbS+=G!PA)`!8H}$nT&QZWhUnq0 zP(Xdv_NE*Cg?;9M>Uf~wUHm@d6PQadl=Frw&4eQ|Bo#; zXn#rN=TD0Kg+BtT_>u)#cN_{ZnKV+Cm7gdv?5A2(mH8~cPvQy@bNIT75Gby-_l z4NX4b-6+e7b z#%MHjCCE7@3~(oGITmV3BuG>!01m*?_y5xZd?hk?1uW76`R1!VOiQW<=g;SHVx3K_ zreLA%=q6N5u_amTYQK2b^Qb{l5W{$rzP}7usbAb4EP^RnaJaKPV6`ggjV&lz@TS6e zBB#AJ^UWu^id&1#WXGjDwA$&<fVsJlLN@C7iO_L-44K)HbuKu9H3`L!X@9S zsRg)FG_W@B8yG8+H9N8if$zhj3V+ehl0+<|bq|GlJBV`ma>8T|R+CnE{}8<;hu@)# z((Y}Z;I{1#&^dt}1k;vyGD(%)j9MUQ_#@^@>*7&*qJFKRUAH4=N?lQl|0il>&pGP< zLQv@CzxZj}H1ex56ayIzf`hq7x^tT=?Vq7oq^sv zOD+RGE>dT{#2E#hTD)N#1m4S7AOgI+3Oj9b7zC7W7`p0I%xL&&*sMt+?k89h>Ewem zNA2>pnSgQztHYm#d&!YQ*=nIZ`&@>;1&dRke|jUF_AHze68WIsdfzT6Ss zYnFPh{0jft4_m?>sOChhKocJJeZaFg8uJ)>=4Au*S=v4i%Gi^iLPHyBpSB9YaBc3B zBj}Y31=V%D2+IVaA4o~X*^VKgw$o?w+HHB6U)M}mA9<9RJ0H4|b)2Y>wQRtQUw|_P z5)-y+1Umxr{V2qEm?VyUa376;0j8GU9DOVMMXJ!EGkt1yxrsX=5Nv-$Z9w-r9KE?q z(KER-n!slUN=c%!MrA$<)&{zN zK*kJvTV2EnnqY$S#pO(hGZQIKHiQp*A2U>%o*+|GohW6LM&?iIS> z5iRHh8JkYuxofor?7E8o)!4oixR$7)5+v$(x5qkA>HwV9OHXzz14(erd(*vc^4=2- zE=!P*&@sNENSN||s!2}IR-^$RBnrXSd4;W~YOhA-==Lqo;N!+HZFA#%DWzU5}jkexu@ z{rcIlM2tQc2_VWE{|X(|qL!q(|0*;4=-jzvoa%1rS|mD*y|Ys%7l=a9JCmPaEHDlYdvz@ zo(RAkw}&s9E1x9y!IL@T52^(p>1N>mWN^L~U5ksrI+a{Ae&tjlJ*RrO2Vb0nR>QXo zkkr}RjPmCPH4j$sr}ao1%R2;6IE*>;_41ThsZypk+$*pMLhFqkg(9%1-bu3T%IZ&0 zgj&GrS>n{b05?^}@po(f@IHm+nP zmjU~+P1F(*SmX;C#Gee?_Yc1ZjgoB+s;+Mb!z<_$3EZ|&Q-_4%4FWRNCTI89pK0|S zAu6FrZHY zRf;M#c)34MV1Tv*^UGzFzZI}Ljrh)|=%=cQ?K54Gu;Dq22S#u&I!F~kMLIM`^CQR= z_e(Nvi*IV`@*&I&@$O1{&v?3Z{D(^=?vpu9*8V{&u_KL?wZ7 z=1v3iMp_tvkcXZ<|2FED z)OyE8Hc=tOChEhB^|}~W)%eVs;|vsCT%_4=S@&t$9Mcw4sbVqzaO*PbE81T*tas-z zl0Snq!91LpC@bPL8mg=Nt?_vT--zI~0^T{lSP&tN4!?o%v%mEbmPA%&kC}{dEf)sq zv##VPLg|6&Fu8f`5*qRES?8gi`K_XGdw(H}9iHC8Dslw~>Mp&csJ(@(63QfN=I`0? zsl;?1Tb7^kapO58VA=82VGt0a<8&3S}`zCw*Vz z54+~N-Yo*_9)AE-V(xW$m7Fl6Dzq8KsND$0C=N#Ng0WB(nDv&jCfCD6*TYf7BH&jO zDa~AQY%0%RW_COs!X#6v{;)MIwc=n6%VkB=R>HT;1QR+DM(KJqv)0Y9;OesL>814K zPIIO!dQYv+VwJGKCQ|uHqJ-homFy*ze{OfYH#oA@krk(?xp>BM;Y5J|8X9k4NJ9}C zdkm~yTM{!De(Iwt3JVge}waqE+_m5ibR=o?{)i{h7u-l(32oA59e2^2C7H*m+NsnDCB`V!y$>=kz)Zh=Euq{{aCWY4qGPTTw; zr(>9TWG^uSA;Mb7@d2bo;bheF^?7P1Owr&f>o*bG`*8QqAytv(X#h04H2j~5pFQ|` zDNyY6l{q?E!;hh@@;K3lEUqT0B{VF=MtYMVd6Hbhr4Iyla^+0hMD#9Z-mZr5s1k$% zS%P+uvF$woX^!#B3qJO8kP*USc9`cFUDEi^Bw?P|Fb~yrDV`E>FMOl4V>PV+!f!0F zzk@Xipo@5|K^^*?$4Pqu0yj7#^jViYnxTCYI6iAzJ|i@nAaiNv?N4v~-YKHm>A8Nr{KEfFEb5 zq6A!hFa^}~98wpmH1f-b{$7%pW79iI=m!iS4UCDTZ^aUaYu_Yh|0Aa*p-Gq*x0!)4 zl%_v~C4~NoJ%=9x_SzNWb=crVEyVw;@=zku=_8Y6&b56VI?Qzs(qu~&*eJKqj(Mcp zz5RZ0mc4T^&u|P3df9SAM<4p&ST~|m|L*1ReW-vE)70Z#TNyde;}34I)tC}^Y*9&3 z>LbBe*V1f6o@_Wwd$q>G)|saQjSLJHl$~efH16R7e%6a50t~tMwUrHxrB) z*5NRo&i5B<2RCu9lO)8Z4a$AVm^Nwa+HSjk!V&zjlbRi+>|#BDfy4RGV3H0>_lahb z&iC~LH*pS7Hf`Y0sha7*3R2~7&0CF9PgZ|C#MLUJIzDvJ__&Ih?^IkWw8>g`I{hzr z!20Q8j9N_7gWp<_q4sZm%#3-ypLi5?cNkqK0P1}b*I_<0hQCK|tQmGTg$+~64*6+X z|Gc7RJam8Kr8iJ68MbFFA=8b2`T^xU#733P0Y+#w-XwMok8RM5kun~Dqx-$hG0>>L zn&IZ@%v`3E%&Ox}dS9nC;Q5*TqI{_%K{j3lFYPp$`i!6aa`}Z=7%1HGs7+Ck`-n&% zZ`1V<)|CgnQx#qO%$z2xMv!kSU;TtRV-5~5$hz4W6-R2N)I(E8sla~KZN2LBQA!lf z2R|_vlF`*TfptxEk>4=HQ>iSHhXf?gJrFlMqb3b)hQ49vKrc)>9324Q=6UIKt9Mnv_8<{LwTiLW-1${J}PBZ}gi0}e4sP{)(Ob$t}f-$<;8 zY5+e`YcOtTF?p3+jiI;2-=MCAmvcp!(4I>P)--thud}{d;s6dxv_jC^D`rS&-y{HO zT-fXDS(T>vl!Dl=G0NWMEs~b;)i5n{9wSSn!iWTF^2Lap^Ur)mtYUWj(H8q$p&{`S z=OqV|SMRo6;iS|fs&-(Rpv79edT^iIl|!m_lD>RSq+`!I0m?lHUHen$2_T9O!xW&9 ztMD0!nE_$>jnPM2H3)hXuoo@NABy3?YhhomuH@`ci?V?3j6Zi`RCu>Xg=REhqDM3W zejq91Q)`tQ@%o9#hu2+CsGxat=ZeJN%QMidR4Qi2z+MVhYby!#KqPejn`omBmh$f)FeIYW zMU?C8PvB?9OBb!8z1pF@&>mc&{h^A54~Bz(v#!VbdkXf4=7vGP-|42i~$T2UwQXF2>4g8e4&RM_~704qSG0}1_ zoGuZYpa+P4j6+;N>>R;dcn_1fam|>nz(PZQE&0br%>av!CSX5ZBzP(*dH)QvuphN( zPi6Cd9_~5Bs$j&hujDJ)9X$%5FJ&h>GoX0iSWkZuQ)3$#<+B~2quE7C^^Y}neRnZTb03%G&u`8*rxN8MMCi=e`%QH} zFE31elB`e=u!b=K)uZ8 zckzJREb6W8dpZhHuILK3?gR8Zw>;#^0<5|lQzu`Htpw5F;R>v&g*0}K?slQk^v!>Go2cz%A1R0oQ+ zjj22x5D1&P{*U@P->8j09bXFsg9EGtoiF?71`@I*w1_sY8w!tlY5}*ycCX6E!JFS) zEUL)ipZqrTm+&9Irf2iTMw4D64N$>K zCAL+6m2IX6v}e*J({On~s~NzE-3 zw~anuhjdoKcbQ|q!j>4it81n$aVr&~z|obUf15@fK43)nf`v@i4=c|U`eop41PdAH zJ|Wz+8O_Y&UzMLvo#l7hJjqpA2Ij{T4i34ZCYvWRs8=dik1B|apzuX`g0N9nxU??D zF{0dWQN9LFBO|BvRN7OY|H1F68pOsjz3Zab{>-#JZL>Yibc-r|`z|>_G(LXi#RJ5; z27)a8xa4%cxuwP1>v*3++*d=c2o`1&Gz;unG(X`kuoLn2Tj{u)Pm&~VJEtL}uH+0j z#D^m%w@1;ly1(mOGC@j>LoP4qg&p1rZX;9Sr{*VP?)+Y?tKoWqH!Y>UeEZQi<&KaO zWS^O1KW`Fk1JS}y8ff*38yGs%6WS%zL-MxZ8m)W=n4kgxB%c7P$#f?v zSAOc&6=;w+OP$gSyP%sc{9dkqO!>om{2GPHf>707e$xv550GEPCb}hti1Htvmlmnc z^=>>Kgf15_Tn|zLM^GAFOYvQY=`Ks_3`tY_HLdDp(+QmBUS1;>u2cG)r2U9s(Qp)0G|mg)rVEAOeN3IFjnnwPykD_ zsV5(z6&0NfGesMJQa1{@F&m;Zev{w+EN`Jn&}{LWdP&pdonA0Bl+wl%%BV-aAj zf-3MXh>bK=pvpw3(6jWoKMJKi!F;cKwB>36z zXqw7seuUK&4#rT&&$l62Tw3A{h=m-5{j>of1U+%5%vTwK(@ty~Jqbd4I&ISIdTZh1 z0-4hksM8b(dsw-nDt?HuB?UTmPv`-ptXr`9cg&J>EvT$8;`uoifG~sSWxt8d2qHE# zZyrU$b^2#1pG0U12I|O6_=Sz65-4Shz~Hi{<{>s-{9Np4h<>{Ij;Exq-Xp}COSv~+ zGGhJi2|65TKfJy^gqD_;Xc1lTg3XWc;bHlvMxEaSp7mC(Xx|Vb2H_(HYd1g>#h-`h z(Yv*@G?SF+5)BQc*fcvc^joS-fxaZs)5A2ilVb7IJ-bqk5e(^?IFc17z3@=U`q2|i z7jIMU6Re{;=($l|YNja_zCz6l8w$B|T+FK%5fXZd{Bje3X+(BzhD}3v7C`U(T-pQH zsn{R|x3`l6J1L)TPnNDfl9QA3`CQV)Q;Nn*(R4>M2SZnJ=|pCbutc>Q3ZaJysv}xE zMdUaIr7B1&zR!Q3JgGtOqfA1zxabq*VY871h=35j61O*pR{$c;*+nn#9 zc9J0lx6qGRv`3Vfk+~JIEJYpcBm`A=>fm!1{6}xN&{Jtm2)(y^_xf@+ zk5Z?ir-?&KX)ZY#-hfd}R{}qN>&f>56%F9!I~7&Jy^=CWWLP&^=;kIvtelNu_I`YDt>GGCp(p&4)l)|F%l*PerBhqjA=7zQj{ zoQ0U7yu3|blIRU>w`lin14h6ktuEKOEO$a?5=E1%RLV>PCUvr zA~pcsiJ(krF7wF#^FO`;dAKONnu!y5$Wf8Uvhiem5tU+6b(j$o$Pp6}b2&!)4?^E+ z!#EVPe@Lk8tXHTbIgeFS#{NI`dE4)FOEjpoLbnkc0d2#R-tp|c2L?DY(%v_ro1TjK zVdV^nJopziRq#Prog4KVf+|O3mrY6j-8aR_hfs#DPAeF+G(&wOsKEByAo|ovjfXQ- zUe51aOXU{%^^U~C`>XOldz=lew40p2O9-ICNx~d7<>cfP$PB9JLCO1+F&Yn4)nFga zc=v0Hk&uBQZ|{=(?e*XFaZk;40F&7bE6Uu#{^6!pVepv1vldCwZ4BATiWZau93zge+q2EJpd(^C~ZFC)sk} zg@g=Lh|6-ob%`jR=!C>E@wmW2d9C3GA0C4_iPh)ItgX{*lOVa zM1UqCQOa3?R4DUqSa)AnOD|+8rTtyux{Ki>=jZJ01RLs~GuNKOE1^Y-;;R0ec-k)u zq*%SAShP5CX24^4$^EQNu2@prC-{LWaf}IV7Eua&Xx^K^!V5 zR>*!Ak}X5l)a?7jZ&Dj1g9WvNg>rWLnSaK~)3E(4)Flr5x|HlN*3jUh&k5CPz&Rhz zFcp1fk}90~*1?7w)pg=YiyMW{yPgc~b+!t%xQOPY!Di7^X(Y$EhS2bhly)w&eL2Ha}@hT9Pf?B{J-yUYduCsdl><%qY`o*n+MV7mO)flW2{Esv?GT?W58R{jRWm4b?--^PZxtO*ZR4Gy}YVo zPm}u2KRX}bx}qEFFXp=;>oy=aR5C?MF%g{pz8B-(B%XXSkRFU`8Ts!uj@Q$wchKFh|MS1bs!qa&W z5fJ9?tCpUsXMN#bEW>(PS{ufMAiK^L0>?}3-B!5Maqplg5Z?1+@cS|)?<9qd!*Vd2 zU-sjywsG7UQJ63l7 zKUFNygh#FErOYTe1$4ZZ{-YIO<$q3c>_YHb#XTR_5t9?7F@Q^C@w$L!=0R=to z7dNnxYMzg~QF@%PHm#iekSW^VWU?-fIYNJyFQ7qJhOZd0vYRSv#DQF5z4$E9Z5Mn| zA_$7vUQi8d9bRhr_1upF7P-vP-l#l#dB&1p5o_M3_uo}c>p~P$WTz5%lzqOAf9uje zYsLmY40aB3zhK$br_Y4gt=);Yd5gj2QMY=dMF4L*?|Vc$$Qhg-wA)VM*!d2=|EiHL zRJXRfE&TI7`F`u9k@hi!lEttKy;DNlAP9Z+#c{~-u4Qk&-Op=yZ3*hOJ3A>kdwZX$ zSaAQb-6O2BA1$HvmDV`|b!OgBji?W_R3`EN!uI;*SXEh$9z5g|ZmG&sOGq%nwpEhO zWS*chEpInw37+DbzO324;QbB+6dJaLH+h8{y3UVc_@*bcBTt@~I5-UMc-KknOV8GM z!*5NbZS=H^?bw}g28Ff!?~C`p!2~#>biVYYaa^36PjX=wwW|)UrnTcEdusCfGCFFh zp*lDSsjRKrZ5yK8phU`U4INR-&A$fN$-belJ?s%b8bd;c!OL;m25{D`0AbJrgpcZ# z47xy#)c}2jB8s}U^BeEQ6nGsKq-(_3w|!>s{i>&=A6nE+Uflr)=q^(+?9%h7CL6%# z^|9QLOWxdW&T-Bi)C^hYv&=Wt3{sIeE5kWBG1gQhbg-qlfkl^CNM(jZP z$OAlBOf^Y<&!7$u+y}?lSb2&#ZmmxW9@Cd@$C+;$WjBPL-<@|OUB^x z*=>?0)fln_Eah(#5CWoE8957xygnGyh#0Th!*)*vn=po|F^0-bz>EX`c-&_$y%K=D zP8mh6g4j1VzRwD1pq@7L9ASph>>r8-ju->cSAi+vlq(nLqb^Q7G*8PS+x5tN|EC3D zHO#9mi|q|>>W3EFAloSun?b>@Ugk1=ayBe%@k{SCUWG=uQ&{VXCw7gCw5Gk%{X<{; zLC0pqJKz&AHhzM(@zf=7^St*h7P9ddI{S4NBZoC9Emh@Bn1$!H zwSMvZ2ePBOzTPgo?ma-T5AdM!K@kP5bwa%&uEApsc=I8*jeL)SFRbvalN?*RzN}-y z>{MRS){a(Yiub-{8Nrg?W2oB`#n zkx4^HMT3q+p4Pl~kH&)^QO;MKx(p==beASH( zY=2UQT7mUe;u2#Pv(rIru~{u6tHbWrkLAYU-7x`yRkWaE{rjoG(=h)VLFb*4H_Du+ z{Kh=qJ7J-7Rj+l8s(6P=aNW)0TWa^rynLQ8LP8$=qENj5BO#fP3(vUE*`CYEo=Cz- z)mqrXn?En`651c~F3x=S4H%Z%*@OuJ?v8k$Rkg&u(bM2= z;cb8byd2X1*8I+^eQ!k0@YPZ1j?;MHO5|LjiQ-xNd9!uE%`Uxp&vW_hgwEILkvQk2 z8N6B6Xox=Og37qGGj&A%`1AT)pprG(R)<|Z3TFj^VX#r|30mgY5NN;7+ zT_o#+dow#P^_QPYz1F#TJMh_?Unedev7gyr`3k`bMtHKIK-IP__KRn-1fma)_;{nL~~HQGLS;boROW}D36~i4Ii1TVRTah1aSz*Q!SWg)rB_aH5eUm$ppy8xfZ>PBNjU0 zfHM8@{se1Q>ZEKb^K;CosZ6!{LgBI<=Pp^Fb7R}n2;VyL;Q^lcN9Q4=Q6XrJ%MvIW--cz4C)$?_q$${{bn5QkyXo0;klc?g*(yEr zN7pkq?x#G>4f)ADe>2KVMczg#YZ-gT7eg!h%Gx(l)#Hdbd4mw|zop+b>(u>K^*CaJ zTHHnubFclj-a4}tFM(`yuCX#rqE{1?o83R3AQC0|vKZ9GP1Icp|4`HFe18s0=KWGT zMR_5C+m2#*4|M_0DlE%BqPtw?TKOn@wZ>s?UVha3fy*waY`{4q3rcV2gO5v)=Ra3% za8Ip6lI(Dr7yuQFz`7^jB#k2v`8+2AoF z>i8sd>r3?UdhM*6^~{I11LDJGbUUuPp=^k|`+ASK?0+P>!Q3hurJYR;FK4zNbJpi~ zb~b>?`@*^UX+OmGS$z4XUv<;rENV;g3?$;|)ZFwbre+FHY=0Of5@tQHbxWe{dIj9G zT8*CZ1$(PC_my|~@$BUOdWl`S90tZG7Ij`H+O5W^c6t%DMGc-$vj^b6-LK+1ww{E|zrT2t(KvxYhuIW;{pj1; zns50j(dZmb?&(ev2ce0r1;vf>m17YB78|rDIO)_}{3%HO(=c`yv(e-on3}*K9wrie65WXE()WF`S_F8zgle zY>eHTgIR%p7=`8rW9$R(UN_eof59iVP7&g38HF52OrM01U6}2p@NYn=O;!9wVUK&& zA*7th_JGSn$SHr|Yi;)ZG_7nBXb~~dH#cat!^!;EDw%KZ!LX||ck6!ZY4YiZ2+Cys z-T;6+Lw0wAcRl`1|INs-L}TBoajv8?PL|@;%l~XPR}U47TMVk;5?FI)&T(!a72qnO z5Dr~_?!Dhq7VW2m)N$+Gnz4ZkHIb?6x|dEq)|bPm=8*@t1b(lQB#Qp^u(RiqnKOu< zU>rn@D#;_<2(HAGW1}fPIG4sYH#Nm*)_)^gGq@7TzcV+b$6ldLot?Y%+?e(DCyb^O z2f#pyKhE;a;95`WG-k3A-DZHIgx_Ss=#bE-$(r+N@cQa$+Ey~eII_oe1_jIDiN5V| z((b%dR3v=Fc(L=^~5o_LQ9uCMX2UhiY> z@9!>~o()xlKnL~08w=W%LceZ4wOxYaHyhv16*0cD_a~EwVb2C!V0zCMuQIXCs6Am65%z>C{=_ zSgc7dqY$pG@gI3RQSX#_p^Zw-Uccl@T%MaUicltwY1wxoc|`MWX^~gYGWTubzWXf! zP4c2gq0(PyZAO#tlO08c8&BETS$CfH1F-}rYwr{xqY|co5vl5xri|-t{g!+NN~l z_Do;j7Gy31am~pGKPqo%q79_k1X}7T`~(97;1I+BXm83W>#?BVc%9p_ZQr=+)_+wVkM1#WPF zxQ01cgq#G1fM3;ni{TR~(`k#oV}5$Jc7~AriRX&QA8Y$Q*O*J?lk`7@+d`+O?k3I# zrK$4^99W$QjIy&bjM2adC~(#3a_}So>l>Px)81!)625kT*~?9ws)W~MeF(_aXLO9E zYw9opkDpA)8)3SWq=(t)`eN3JDmSFp2hHbN5`n78Z_>&UzZkPSRjbbZUJH(~JM7kz z_Zun!N#IPk=*C4A!&Y3YR%bxBA6t%Z5`5#!0pn$wv5s}tGjYeo9MPse4OG4OmCM`H zFm~_xMRcQ>h&3Q#S^jzV?S-i0Vp^7?BQfk(9n~_mnFv9*nVzia9Y0P|hhw_ANR4o4 zAWvw25f#M>v(MN8-(3;fix@N5S*jkTI#y+NCwS|)b|aCFPa3D= zYGUwt0vN8uh34Q=Lj$X2>qzKU*hby>VauY&|C4$$Y}^09wSpFCkvZ797Jx3M4DE8! z*9|RS0m9t2qn01ipDxZ&x_H~dSmo4P2KT&8tOg9qs{e!~dmFPKbL45)mXp|Ly{7+# zUqf|!x}vLoR^fGvcYPd(*IJU3qf<@ufhrp1uOI>ntVD#y-{i4|j3?SKE-I=dn29v( zTnpaXTF$e!Gr=>VtB$ku3Pxfzjq{ULsg!(nVVROm4lQ2zxOfvKZ>$D9*zYC-LpFy%bnnreDM!#a3v68Sv`1$ot3IoVq^da*199hd}RedlU0tB=-9s>{Ng^NLxV z+5L7x?#&|gmWBAiGOF9Xowowpe6o~c%FdO;jvpcxuYB=>xiiJkqV>*tZMpV@&JlJ;V0~B0kSK*H_F?h{j)i+YdAe&>`nl#8 zkm*}FYuhmOFL~uPueid{Ija$ISjVV7YHS z7l-mWIfQ0xuYxCyYpMg~wJ1K;ET-XeD^Bk%F;>FItWLJ~bbZHmiaevGSmmsG2hY@T zJ>Q2QlVeDm9?GSezOn${FslDr+`kD!3UhN~YFBMSppmx`$=qKsz0{l{<3q7m5{f=yTKAwb#o z&!d0t)=YE0a;aiqN{BNw+sS6-j#@cLt3EEKAQAcV!Bvx8t(zk1r=8aMnNy%Q7%Q}X z_idhO4hkz@aew)O=FxtEPy1>*)z?Ri)qIkX=_*g*@e$tqWHzJUns&yqD}aj^H#W-s z#KLU+xfnm&g|PciH;k@LDXDB=<;{R1I(1o$n=%Zu^|oAeD*IrADLg;u5l_?aZWI2} zYD|LZLl1y3ywdBeWhdc%pr+3{%zMFxtq*KTp`xg8$W_5Yqxm?Mb6a9?NClM$HFWIJ zsYo^cQ=n`uy~gHfx7GRpV6{kDQ8y0kps^7tQ&z zYt?C)tS=oUN4vR;yzliJ5qv0f%)JQW&N^*ek>2Rr)4gvBdYw}LD8 zt-&~OX#8(Nr^Qalm&qD)Ie{3gx28=5WbluJ_lSW}Lsw_{l5_C(*`Kl#W!Y%{9IO6` zQ!M~KiGEsb%?;S0sAkyU+oQ~K@l-xnZ~{7TC-6%_#BJnrMEiWNB`aP`&IH1`OuaZq zpAnfmfKd;*sevEK+}0HLy_7+~iLLS<2-Rj1mCGKz>n&7s6%V9h+G?6%-}_K-%_MXh zUD$bIGCTzD<`BU>aICC?T&JI~@bOI$xm5WP1*dg6w$Op2DjU1z4uGX<_8p|$?cn@tB(^%kHR;&+H@38vAedTI*xp2L=>P)8zo-j{zx`;;!DWK ztCvPy;sDkOY*cHXYB|)RfX^J1ub1TI$Og)KO$rO+{r-=qs@pav31;Qb`=A|7x|KV^ zx5tDaRH7T|areM$-LuPqHt*MqMOJst5hl6FISiv&q@otlbC`GF_HeIT`{U+j09mZ+ zwAzOc=V1|FL|o|tD1G-$5-JP#DJmZPzn`us%4-q&Dq~k|9W0j^e-B{_1xQ3D|Hhot z6KApOF+qCuIH&HU#E0`W8vm7(#`}2G>R#E-0ro;Af7|1Y0%JCCt-8Ny{B;ZnuG?ih zRsC6~B_Wr2Z*#SDx|Y1b9^lWhUPS5BIa_4M_ckVDW4Yh=4*XoA?zbrSm-Q@3LSY=3V+{bF0dU`pFFN>3c0vPG;(_k9Jkw}5M#UF#^JAbpQ=D7uB<~>V^xE4huM@#i`M#alBat;)HexH zQR}bToGov&gWQ#w_dCXRqUy=n{QvNE;L8c}78!~{3#!P+o6DNfGQ^-h5Wc|YtC zWJ@O9hK#*0HgM7(<@|he14!8o_`f$5{$O5_YCL)yW<6^kTkJ*l$j}_^{nh*XNT*`= z_4arnLTUC9uLW$>nmNBuwP_aY^RSh>kkK5{`Dz1$(+&Lg3%dP_(FDv*SL1?5yLAG3 zWo4hf{=t8|IYRCVgoP)0Zl@8=y$pDACd8M6{-HC}TxN#!YJYqe37F(=o_t$@Je2h` zXqL;JX4BiS+64Uhd1LxS!hIT5|J98xcS65^e3Tq|=u9Nwi}Vu#o7+T$gyBDJ7^7Wh z#98VsKiySVS0kN02~j}j@@r_7{mKCK-y_JPtK2q`A=z+5k1a*@MK`6nbFySC+M6hl`FDNbw z!^6YS#OJf~_ul88o}P1LiBZeC0*UJn3>V~riot0AjZ(b(HQ>I@h-Pz3Uj&?JtpFKb zY9|dDmeNtG_%~{%%sEyp6X=9~<=a?){c8QScwbt2zp4xglnRsj--eCgAFoA}{|+wu z?J6H@ZsBonUbBGxPA#b}wN6Cy@8bU0VmK}!@bFCRA{lid3{b$|G99I56mFy!t!04m zms|%0I*d&(!Ov7;a(aq-F?uqUzW~u_7qIE9zhGe*U$Hb=4dL`8BBxVN-3v4|^3u}s zQ&NMM-bc|u*ZALe86qzdB@Nq*FdT_e*G*W0f^^7W(_dcH<7DKysr#6uuY6t7(zZS@ z_iKI*F8_s+3qdDTym_1Ckf-}Mf9Nmp1!0lKT{bUk>~4R~NY=m0;pYG-nowCrz}I$) zTDFo)YrcOU24FxmoOagMSZ8A&G}H<&FGBE=kD`nHe?yR{GnHM*{nqMn8{=Gl7KM4VD|3KW@$y=Rz=?z^`O=^I8|LH zBdZj;ctF7{vC^yqN$%iNE0E~Fb&;L3ouUKRqCsC)MuqIxwPu%hU@Y4Od*T=S^yg;| zy-HWEP(TD&yR7V-FWWmiWfrzP8ck?t2lp4QL>AyCM749z>%S#(u>g5{{c7pb0*Z&+ z5omUApCwFL_HJACT3_{AS7O<}VwO&V^MGHR$vENMQqkfmY#K#PECHh2|G=M|y&wM|jeG1+t z;eAJn@4{{~gPJ8*W=N9(zc^+cFquWaOFN&Yhn=h751; z^9M}YFoFzi^l+pZS5P+8|6PSDO?ay?+ zeGC9zUG8Y$6G0Gb;)%OlHMKtfNS4%e`6!Zx4inNJ%*_}XI3&m7=@-+Xvm_F7V_Ye8 zU0RA5EaG&!Yp?QvX$L;H@zg4L{rmMd-2Y5W0_6hvyk*7x7=rymEGP|q zPtdHjg0zcRz$il8FB_dogcw?f*XsTp%Fd^qtR;XnxHjbF84ou?lx=&g1y%(L=mU4? z_A(opV%l@Qzfv>8M5D&wd`~p$Gn$9Bo0Oj`EN$>2a-NA8P+KZ5H>y_TCOcly#5?cF zEBJ+M%v`1?4Ave4No$t-1$T@;D1({& zFZVtEcj5sK`kL}C$qd7GjzmwL&%x2$%yu$Q`*|UivQB2;7Lr+eo8R$WLn!M2SQf+S zg-#dvs&BX&AwffqE0IU@QC-y>Fwy8}^J&c)%b28$6T<`gJ9I6IkY41PSgmKc3T|VQ zK5GP)*LgU2>vJYWMpLHz5{UYZCh~h*?4vV^>SB_z5WVmL@v23L!i`-q&w268v(Z~g zaKQ|EkFpMmyJmxJ;G1yxieMBLrfj)u zFjm=uRR1{n_UL`;5c+^=^$b!C$pGpPOp_g_wRos|OYRg67%-Gm^Y#wujF6VaBP3UL zfjCzDxM0=n@83R~SCMkPJX@>$R$SDXCO*juqVA@w3viQrEBL+3(ro>}%rr49!%dQj0RCy{;u!KZq^I|Q^Hc)5iP2eP1}Q0(wVfRpXb`=q z)>jeV6%TBeVQGBO4N|7%39ZR<_I2A6wLorWpx>*N{aWE{k@|c7HISH!IBpH(H6+LD zEo6HmNn^|>mo*~=cL?YIAEvdmZ##}^$`Qn5+GE)W`%hy2FRQp7E?11*+VKH9u8jzZ z{^;Tx8ENj=WiC{cl-+F@z-+yKa*p;GDjGJ!Z#!Oh!xApu#uQKf;J_q!)XOhoH8?!( z#Fp)Fl8eM<60wZGbdtyExLPpw=7ikECX7{1SLq4{v8h=4qHU`;<%DCti&JZ`E{UZ` zRsWxZLZQ}6sG`i8m7Sg}E2H8i4VaQpTJbYE%?|f_1$*C~3>;OJ=E8{rbS>m`%Z47e{2M3$BMU^(iE*HZpC9JJcr zI`zS;`fS$Y*e>1IB<}yK?JI-oT9$BecL|=2LvVN41b2eFYjAgW4<6htIKg!%5Fog_ zY~0(oxGw3SDUCVcKgznJN zhVhpgd-BTh)o`7ikkp9gHt889-1*U&Y5+!W_u6j5m1Wj;QU!@r(CFQ&sWmPtaP#*! zJB7@}+#wr;Trg5rZacLh{$5AK9_PIA>zU@$a>ggVJ=#$ zYte~3Y0}>wY4)GrdUe1@imBKH-?;V6ku>7;r4pRzPgINH_MD6e(~jhN9Rz! z@4f57_LeUrW`h=3+dljfK~kpX^0_a+O+R7 zG~Vpo+=zxGgIyz;khO5IjoGToPZ0vQ=E>sqztf-J^(ruHn$%u(Moo8Nb^O~!OIJ?F z4>LB@PeG1bs_M#ZPOSLyGf5rLv!j9$T?bY%TuVPO17pK5=-6|73O-s6sVV(@X|z^S zO?lDK_54MH`EGl=ZsYRvUWSC+>8hp;7cb905`a-!x6G)s=f3XYA`dJXqc87{vM z&p--T^ni?Bi4$Z)8re0OiLw7MItJVtjJmkc6x`I|$VK;7O@^uYmuX>U10Y=FC6&r^ z#XLA(abR8K`w1~VH4F8qS!DBmJO4T#6!eXbzDG}c@I^k8wx;ZtWutME<~T=ecZWbz zweCQw!S1?qYb^{MR>~r#ctW7(|4_)EyCgag2o*$5k%(B!c>g>?Z__ zg!uD`E5VnBfL?Qo4qtESe^x0G1V@pwM3{d`FJNTvb3bDEM*8nSEi&u}{wo(`i*I`6 zZ!_m@Q_Lj~rTIVA<&*wnv;U{ML{8QCZP{uoYmChCo7sMLo9K*!h>zC=cGiW^vFV{iIlrS zQ=LBWpmq6SDJi&`Kq-iC4c|#fu)hS;#_A4L``k-i zK3n3X!)Mc{AWk;)YW4>Yg068n*3GeOpfL1p`7v`K}a%6^>JeKpTh8=s4 z_nsOH)%MiT1Kl){_0+;`IQPpGdq!Z*idaE@vKn@ck&e0Zqs5Pl(pT1(Wzr~+cL1Q& z&ay3HLval#w4PNBKi_4^q~n(^yRQK6$lNi!mX>ifjWqDE1FFoehjCAb?@b6Y8P3IL z>w1k$o*yESE-6`W+6Hb zTJ%7x=;dD9i&7Ik`<;X^v+*{thQ_+0Mq0gTQRu1lP z=OIO1Oqh3ist@XWxj~%p? zDuBGYBQpP)f_JO=P{C=(zdP#m-TJT~#H{7;%2@vH^`<4D^1XOAse<@oS54aU9hL~d zI}Xwj)j7d?8^_NFEF1pyq&Uf-=TdV0_Dik9y>OV29~l`VZFP?L82e#3C7ht=hxPLC z^9Fl|mojqq z7aE2~FQ(BTHXM+cO;3&Kk8M$eW~sM~lxDh%aFbjZr72IH-VPePUk=#KD*)?`=Zx*E zpB)H~#g^H>B)wbYdbqJ{7c!ewp+|h&y+nzyM@Gesopi0A-;k!LvcFQg4w%%*7ZPf+ zzS;t@cyvPybD}~Shzl*qc2ORtL^8A;dWN~y%`#|q-+ak2-o!$E+>_mNl*d9#O4_Iz z8pt@uLjL-t_z`+;d{n8PJ;#>8`vey4m%ePX(Kgk?Bm$ut0cT)Vezfch~k(%X@MkZ9tMv&)-L+(EPbh`jnB4{+reDoY)?dLXNbJ> z?b=)?a#(izVO3dB<*UGtLC$08j%zbMnuW4uzFf6adE?PQ=`4R0^h%lQ8?{QWB*1GY z(qSkzzLPuo&i7+ezh{FIhQ!jI$Git(xQ4H>EoFZcmdUQobOyHvq@cemEDk{(|bDU@ra20N}p zkWci?w=wpHY)FBnJKM?Ntvdsm=Kd2hrrM|uGlRODM*p+Tsv3ur_%-vxf`Z%}qn|Wt zA>ccR;C69i+5zKBi<)|4W7aUd7rCI~V%MOzIDoj-m2fwCSCOG7m$t5MXIM zDBIcKI_<9z!5Jp}sF}}*2#A6nXQJH*aj)>H8=yMJ8=3Mpl-?+b1$+BC$8SJZbU~@y zyI?IUO6v5R=Sj_rE9@druGqX@@HxB>Kb~V=5jP2SY`&iSV-F^ltW7SvV`~+M|E6s3 z5l;(amk<3~A2VfgfP~=37$XuXBQ6|U`F79}VAF5_3yOcql-c_A zNHCwz#}9MU9#UtdQ1W^Ssua4Vg6l6|8!+7W_v>?*!0FQ`Ht=<)=1V+-htK;=XEidg z7qJu=P6GA`qBn!uU1fpthb2wZ=a&EFux8FCq$7Rn{Qw|mgs8%59txvk3(BjdFz_u4 zpSPdc$TK3+C_Va`ORFY1c^VTxb;>YNGU&nx4JV25@)1sKD$I0X*?m5RKjJ+zSfn%~ zz({HuCQFO5+$K7|IuNUMZ6_elIF`E0qQNv^lkkUCYG{NTtBr2FVkn%tTjI+KABu^7 zp1aSKO~E`L+ZwY;`tvfk%`$%gq$3=TIIIC;$~K|qfjBWPkfA?+$*re)kgyl{lmxpU zythaZJ)AqYSuy!(DOHh(~CXu|b-z!_Vd0nbo=aLJ6R=I8b=IxMjG%Rp>1h-^|pUG2iV-n{c${qgmU& zT()SI9;DUab67pTPhiq@?pR4d9tw)m{Afpp-=^0r zYRbeAyXN(Y|G?;Sv>ifU+IVysGE=ep?%ILZkFSce+P?wS` zZiRkRXk)H|8F;bE(hH(b!DP?LRjw!T`?{^U!h*syw&E0Xd1y+g{*N64ZbKexq;GK& zW*ybS4?OXW*n;OWSWkrdr0{OXVe3huNAs5!Sc^m%S?^FJU^^Fd=BaT^u5a(-+7vKK z(V)qo;Y_kxBaV4D5u?A2Laq+uCTGHpAF~07R<%a$6ak6y5QJ3psq2vhVot{?XP84) zhY3wT_UGTRVEgX_KMT}~p(1og5Y_0wb2#~D2lLwrPUJ^VDR^Rgc9s zcd+tnl(eS{OYf8r1&|(~S8sIWD6~@ZUNmddPy*=V`$^|CW~=h>S@ZRLmzefQbTMfT zLq*kpK6^Fl7-zgm(QH;WlyVtM@uY#5N0$D_a$LYUH~U?Thg{3TO`p7t_BKq;PWW~} zJ~HB%e1V1o?gGe1?qPYm11nAsR**Y;BhjP# zL4w37t0@0jI0))3uYk%2FI^U^NA`%AmjuDr2RySviHT}=ZewF8ZFiozIQxa!b^S1q z2Oifgn!2K2P;8Q4Z#+*<*K1p#R7KJ=Sg5~zPKffbm0#){x}2;2u66FisXsP!&8bYp zw=_X#AnEhHf1zSWuALE*pL8(d^hPbk9mV4-ws)LRopjRQ z8oIKe>Yx30s!-X3W(J8mLNV_P3*s|HX&lqJ(pbW83pT;k6l}vm-2N0qLLT9qr?8k# zyQDUaL&uL{+hEkvDX@NtZyBcIiB&4-#r_@6>d0>*FXP^x9Olyakzy2|eH5sb)+4=h zdRVo_*1}}l)0gPs@;VpqE3OTZe9PzCN}pFpKb2e)F>Qz_3nJNE-yrBfyaX@su^4>o z2TlIy7!ALk-9o#)BCN@jcu35U#W?a?FZWL^;ILP5K7v>8sNvqsvxARmi?<~!W*QUx z3ut9;u0m2^COJTi2yMrGx0=Lq5t0ts#S+}2j8M2#TsVJu1Jc59Ci3+XH(^*6d5}C+ z&hdclX~%~+ragplELS3j$H3%`?bznE+%!=-ul3(1+&kyq;QxHY)zO_ZVwc#S`H`8_ zdRt)_`n1IEAviU41{l=<<`s*6`J~;R^{nP4Ga@2Y2Qzm#kdt(52wV_`ClgrH7v+y zfZwx~pUv7Vc-wcVCl3QPB9TMBy8`OgM({M>Ut)kGPZW83HzFfSs2DC?}y9@qWX8x+QW>uVZ;19Rb z=iXNxWNfQggB+g6LlR=ZnT{?Y3}b+#FO_Km(h9^!Y6tR&ohUg&ERqMNqmZrvIRr0iBM^gh&OH&=mzV}OD2ef}F`XzYe^+4vgvM12QF>_P5lUa-}p(j@^PxqE9xa67`O~9Lk-LA83 z{nZ<6F_*vdS)E+!ySQ)K zgH1>t(-ldtR;jylMk*gI>0kL8pFtc-!4Y_40q(B7+#ob{_ZDA+udcff=%=B zuSJtNVZCz?_t`5Gvj(v5))nzCj`dy*z0KLaHD`;4)a`U%{gJK4i?<$+zds$^#<2>p zhi{)EtMx~MQ-Q~7qff4xkHQ;AR*(OhBw`AR59UVD)>eO|eY2O27okpU4OmX=v*)Wj zGjNcFVXKiyL<0&Jh_s?8Ak->;Y)=-)-u@r=h|O2cfP3@ z>gv3kp2(d43d?n|`jEy*U-I3{4Tn^=5sQ1Fu zVmC07-nmBc+ar#9?1AjwMEKV1Df5X1j*3{)qmvsoP}4?@Cz~)Yq1lY+p+wFv<4nEq z`8+@Ea$G9U)oZ|O;d13Gj|r2p6t{Cd&DXqqZpW8T5Zs~2B`mkc7FvlHbQTT3U#u*Y zEPMHp3|^Ov>fmS03LJ{GMeL{DrHI#kr5kwId?>hJOc_)$flJyRE5H(tFE6W-T?vpc z*7XsNl|#XH!fpNmJW9abF}9(2y8igOmq+-CUr&0m(M=ts5}JF>LSs!8qc8`SFKy%A zKu|mgFxVfd%!*v*E&?x&#=u; ztQ_`CI;H;IO~nKr6#|B5{TMdFw_$1qF4H+a8&hZs90p68D5naa);OZR3t*U0c`lnB zUT|cEofX{}$v3azrNHSD2fyI=(}?5pebD*+9^$Vgsn;`jB3}>( zm1Yq)rVFvA{aH!~kmnQlFu_9P)A)}o0mzlvF zIsh!=sV_p6D(MLKH(pzt1D`nuLlxN$h8KCOj?$igXedW1OnGKqMX_vqWvSKAwx_fiHjo}|$sIXOI|E&7wQ+kL zL>nK7$dyWnZpB3YD$-u4HN#sx8)Ym*-zYbLM=3PP&7=4NVb$vvWgJCKTjbZ;um&)e zq_5%W7G*8}ZEyu^ZNXezUWSFkZsmZ`)(oXnJlhAQd0cI@#`w$%?X{q-uJD3mdsck4 zkEuPUsY20?y>}NB)K=XufA7XvTE>tQQ4Kjl%z^7Hg*8BtWC`vaJ?i%-qqo4xXYKdI zLJXAvS3$_IpDLZ!Q6tHK;CXI$-aqB5NTo8FuXG?m*#V^YFr8b|_3tG=@w zKSKQ0dR&X;IeV<@GF#O$GvpDw)jeQ<>21+wXOeVeUEu@Whk?5&@ft2G zoCg7pPNhT9irW(2dy&2lj-cf$GgHR&u|Dakd9Mk|(f1@OdNeR!3Sa9rFlTJ|hkI_q zQY3=gxj>m8V4`ONYP>h^O`alUBF(1;edt_S=#iSHk?|iV@9(nAcm&ODAl0v8-0!uI zg^i7;8fI=@<@&JT&zZq8r@u2&!W&AbaMANlACdRLmBnLvzJ8K#-a%X$O@DF|Aen_Y z7w@Rr-ijS%(~ija^k)dP)AplLKKRFr>@;|A&(Fi|LfQ)d`O!C*%9SPZUUJQI0Pkx~ z`2FB6fwMyQ&-Li2?6PF3CR@2uO~ua~V<{4=Ve)%*CXrlkn~FNKj;bcq?l-pdKwH6x zZwkby8p9HEP`yf^alB1cQ7Q=h8OjfWip>i%)4tr8%6w-$vb(*OgcPR=n1=D_Hb%6Q zcAb?u#;MvNJl5P9cdU5~Fv~rnvFWA^b4Tv4Y;oMFG+wy0&u=ugA2O-<$N&iwD)|O= z{^&4C8}_y>KILYvb8+7Od8M4R=jZ3{` zMl0{#3olJsQ*b5ZAj40SiaZ5oR-onGo`RoP>4YvU{KeCc8TeeeAdup6I$8Oe6OzDZ zdv`ac%Inc&qi zpPT$pq3=5&X=&j>0OrHP>$`n@>8Qgb+}OxHPs zdK8gNc@>j#^v%lUykVm`!^}_dQ809VluJP8yCn;j3NwxOkY94kT}G+b{+)on@Xs~8 z0RI47HK6dr98fej!Ns!LYTVU@!zFfyXr50}i6%nj@qjCN3-W`<&Dz+->@ z>lxBeGiS%igzx^5-ozfUYRbL@-RbU;bjyLl{V74> zdMLv_=4o_+DxE1nI7UlQ<5J@l|D3{lrhQ%OrwSd{9}$Qy`vxCxoY7ft4?~X@Q{4Q28EIggfa2wofEGj5DfC*;CQMDp zW5omVG@XgvsP*$td(Xr7cCg;J+sd`RxI-l!GIjUFe7C%Eg=$MZiIR4P4@BUER>sVN zqbi$>8%mI$n#^9+S4@K`Wu;B#y#9FQ8-YuE^-8epXK6CeLy*Pj(9}e@uKbuoap+S1 zrY={g{fSQyEXa<1+czOX$a*V00a;sJUU%%~sI)u{ZF$tt1z`n?1Sj zK~hl-B88Pt?!mzIck}ZpBKCPT*CG+k-(fX=L6Bc3D0EBg?7htv!)q$jE;b5EUg=jx zY?^|{Lr4Xp&A$tRL*p`|^pLf#&Y9&;6X#_H{H{6Gt5!ZrI|{X0TbvzQgA36+qU@CD z?%cj_+)F?4SulErD)^j0AAvJajg;;x^7`UROn~U{`re^xhqp>6m3cgu7CS&k=C`#v zATH=Neh8s{n8NpB*VKGlS-s_p-sS3cbM6J9fQ0rEC|>;3x94WE@EgOCOV#L)Ump~x z^1z0}_sHMMj>LWXA8t8DD6dWG%7#!WNunbzi@4n%6>y8o%NNj8GD!H}M^eAYkqNq}1{kiONfgDXctUWk6P@{C<54i#dThLGzJN|C*10xV`Ui1xTlA6>AiunG# zko>3`v`AB6^BT&TE`B$DhGT2A;+^|x$8M!>+3~=|n0n)>U3%dhV@W^ziaQ8%=v5Y*|C?bYv+q`S9TdGI!Fs4;a8;awb7&mC1bA)bW49CAaKQwvAxO5|R(nffUZ5a`U(Vjoqp9jBhJBDo=i zvX<~vzE|Smenqp=YW_hH!jJxR#ao;@fkI3;E%$;_uxa~Boj28AnRbp84P=zyhA}zt zV(NSk$|~wvaZ%gcci)9cm3z**R(ygVvG^DZkn0w8p90Btwzo$CN$fn|Z6CU8y)Nq6 zFkj~JB%TBAX$zT8^rqB6R7?45bEj|*yNYJVc&{6C1xU5jhD3fe7W%x&EIsSU#=pxX z35fWki*x;l4*K;a=PJw2p`|_cKEk<_*=c@WsQ93}xAnsnFWw`Km%~R3oRC5wJM7$P zr7&9{pYmDo%f<)nyW&=mYiD%bEt;)rV7he6gtU!-n4KogpfPgZF98vDOMg8 z2;hth+@#m!zb4q(O;z9h$$q*UgY2yeg#3*mS$g?c@6{*C@MsQbv+Iv{d6#W30PPP! zObI@NIf(i4`|dROi2gR9Q}Ctmb#%PGr~FhTQ-$Days+}+&ZMd9jx#-j#AMFVrM(_r z2k_jYPwYw&I@Dw$WKS#&$ymcM-Ev95KhS6Y`V5G+IFZzNVl9fv>-lxKN21aBp6ZBU zw52M9YHHPFpWE}Vz~ag7#N)o~{wHoBiBgwM-KeJf&5j227b}=ffCs^l1|Z>n$JaDP zHHa18Bs`z;`4aM>DC0}Po7>cXJ#hVsi!FUZ{xaMZ7@zU0FB z!8S0dgz*QKx}09nPHUjNMxOoQN^=l>_JXO!1u!{=gpm=r6jzkp%yZZILai zcGlT1y;JtO7AhaJ(Pko&see~2@qbViiy^gXn$j>63OlnAmzX6dV2oojJ5VHRQTpB+AUoHLrs!DJOqMZk!H%~>@H(VvJ z7=Z#H7~J^tl_s37{=nY?0N(HM=t{s}=kHs5M$eXhi8%;*^% z9--?{{(*|%%vk7y@>}!UZhW7?o&0UpxfkI=TvVYX`}@jp|BUp+4nZa4yfweHr(3<% zAiS#E3lRm=NdN&$?zu)^4&(1diBM26 zv}Rc1!!#=8tdI6(vQo=A&D+5{7H65<-KU{Nle@yW+?wQPpua-?zE2xXhV~Vv-dBV_ zM-~3ehyt~K)+z==WH0ew%BJCp{HBRtO15t5f;K#=eELZhwTv^NbkQMxGm&5F@DscG zM5^#tqLaM6_5Oug50r@>Xa_vJLY++nga+dV&Bz01NG1RARqlhpVt^+agC2Zulz}BJ zq-!o373~2vIjZN=-M*Y#94MP|6W|JQ-L`7Tm<^Kk`WK_Mv1LrNKlvyHb%vX8eV%0F z^Q_XH1B!fiv&+lSI~|&)5St@mDMv{?GZ@C$J|1@ai}g;qJ5|p7-dDEnhEU{)fMPF= za1ekA#TN&DTZ)AcXHulKQqW$I@>Cja(V|~&IjPz&Ct@+vrurrh+v96H~R%(EpyW{rVjLysu@Mfhu}|kXQrCI6?GV8`+v`2doL# zp`GdvXq-Y}YOrkeRzxaOS^qgp^A~e&;Fuy%?{_=TH(7Em@CspVe(B-i8Huiu29c7C z>=u_Sy^AV@52opq-*1|+(P>N5t6A-hQ^4lgyvc`YaI(mk5JkAAPzWmK)@)h_m*1R7 zu!nEjL%NWFPxhZUJU>9r3H>fxJ=dgbu6I13ukfZH$4uzsW(Go(hhV*i1pXEkB4An9mv=H#247$^{P1XN`}uwz zVGJ!2EgXeJ5@PU2+XmZ_`wljr4O^|<5MPG_m^ z^2&xte)ot@FVjx$3Y~)O+jGL2a6CErFbCYdB2Jpvy`$_iB3kHWO)+`sp zS7X}7cD;HN{_M67QwvRx=lkfpb>DRGibn5!hzⅆIZ4w=jB}?|F=_6z}%M6XUt^Y z>vlhn?WxQh#lei(!jLG_SgRUocU#=d7HEjKU%+EPidspAJfPgyKDgTeR8y}JPPxlq z#-v}`TT#CC0@63lEuDOzYHM%~kMoN|odOW{|~Ya>c{Q#d+p>#iyCY zsP>!sc9D;`@K7?pHkxJ0vhETSOw9(=*3@$5Dg?j+YBL}vjef4@>G^N-vEOgV<(VD# zPE!jH04kDl(9d&y)1OBi@A@0nL(|4ih z1X+XAgSTL5|=eG}{+35Ha%Mg|J-RQ1-z-p=w_YlvbkC*XmU6cCFH8 zzrq`KU&4;r3d>705}!lCXF}b-+fZ3wEn5(A z(3m(i(ql%yJ+g^MH8V4|sYSB8ql25b1_t>Ykj`E5`6d#pxY5Z#tA`T@qAV z!t%<5G24N`?7{*Xfwu8B4gZtXZ*jql2khH)dLZrk%OmAfjZxE5@<))GhhlJ$q=NO` z1ZTPSecG~{wA&Y?3c#H3T`k|OPw{vcbd=j}`C2b`L)oz4clsBO?Z^7*XOm#QTi=@B zq2z+PY7D!eBE%cUZ?wtjz$bU#W39SC~sW&hHtIk8)@c`$)Z`bVbPaA$VD3HPYw^W16B%Eab ZE5uLpLb+rjq>q2SmKIkKs}?Z~`agNJo4f!3 literal 0 HcmV?d00001 diff --git a/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz1.png b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz1.png new file mode 100644 index 0000000000000000000000000000000000000000..a7efaace35b3f0543fb1d12ed40f9b521d16822d GIT binary patch literal 5818 zcma)AWmHtrza3OUT2eqtq&r3$WRMxUySux)y9T6%p%De7L29UBXru)hKmnywQu2-O z|LMIi@2#`e@0`2OZ=bd9TIcS&*G^DZg%IFU;{pHx0tNZEng9TXF?y|!gN3f`$7-qQ z>4}|;iVOhI0L8ntz(hYYSjlUu004n306=&&0C0_l!nXkcA3gwJ*Bk&4%LM=^-3vN2 zB+wgJmP(MffQNsh7+#ryMzFmVROGO?@kq$YiIetmO8@}!7=^bo+Wt!iD}LVEHq=8W zN3ap)z&!1D#D?L-Ae<7#92OPF0U!RzVz$Uqo*9|MaNI|ciQ#kVWY!oM>^yQ+nc>BZ zjJ-3MBqX4~qRz1LG@Rk+0mkadtpfLVYuT5pf?L8z5|{8x9TE}}?Py}q?T(OI2L_0Y zoQ^Klw2t@u2$Ts)Jad-|&?L?^FfgdNHi`cu|40vqar~_!E(phhg#rSl3z=~t2F3Se zvZ%b5IQH3D!)1)l)0f!6!eM+HKuk(13kG8~G&C?9POhxbIypHludL9w*F32uUU%bV zVZpMqv+MBQ`J=z*hH6b&TwH|2){aEb6lEfpE8+rz%ms~K(Am{k@#N^jk@?j;@9>J* z?0s5A0(2@(PgSGO994kgzttovpo}+wSEvho?mG@P|*SP7n z_+FmA92iFDHut5XAVe95QIYNSYl^aI{r#4LGjG+9KTjLPeZ#9L?%P`3)b2bs>g!v( z-Dt8n_3jaO5{*!8A?Ha`XkSk^y;lw$i`32uRt{%ikg>6ehmQ|(rIW+w{pI=ubc_Gx zwg6rw_tru(YshYxT2hOaX^@G@%1I50JnH^Pu(2%t!CB&MX|g57I_)+3TV z1&pNYI8=ud)4#<wxMO^a4#W2a;~i;#H2p6g%%gN{U@kQ46JZGH0Ue!=|lc38Fk z-xZmcwX9`8ZN@ee`fKSmuw+2!!2PSU8LMzke9~P`cE%vCvFe zhaZ@2=!={7b(KBjyKxBq3W@OX`C9cW8;&+CAFHXfF!f3GDTuBDygtJwX~BzuBUZT@ zcg}G-1B2JEZ_@O78g!eN7`rtoXlw3u!Syvz(!tgBIRYW0GmZV^XYg-akD$vxUW&K` ztg2koQgllQZtB(?tE1wksp45j8B8a5AxEf=(){e5B=U7G#W{Dp1g*;JH-WFlSjX42 zk=?=d){-;}!J}zEpZ5=bwbt8*tC0Z@_?#ZBAU~ivjo10eWCt?DZUVx8>-2Ok>_|yB z^bVMGualpICv83Pz2LTGMzkpyf1^i*;c6bL-(idC1vwvJvXnYfSsutLfV8~McghKS ztS4Lm4A+IWKptPG=8ydWR$nF-&&eo&ND~sOrLycNA~LIWL=qby1%AY z7#ju6b_#dg-!)M20XnDD1MWC1PW_PS?Zf!YE<7`IlBD%xkXH=T3V4 zJ&rK~geKfrl#s@E8N(pv`yt@|$?jzQ7LEF}4D{O)te5WSSP{nd`k96enBi@v+l$jPpU?Y}ffIr+)cB;p0AYw_fpL z?mFc_=;oJi^_F2TiNr%3H(kC4Kd?9TOjfu+H$^zY*Hz1EX&ttWFruPJ>41g;KhM7| z!bHaN_9KDhH8efFy%eVU?8W+eC06zjW7UUDGqA$O;t~NH9Ku&@po5=nc=i<-V7pCh zh;*}c`o$!T8BJWF&Lxoo_SDkS;5B`_Qjbyn?Q_GWxWA-%X2) zSSk>vr%x~c-NEOT7XEUjFft+IMkULmGX+R&5tgcz>vr8MaBuMIT}2$OBDs*bQGM^v z=7f^pfPe8CpE-}#D&9Nc>o17{cglxVT09_a9M{adfr=>dk*Y`_OfI zwn6W5UH9T%G=J&NaZ^~aZznII#=mJ*7H-0XV4o0?gliWV42Cgid13I?y|2%WUbWn_T&^W3h?XDZfFxy>;MBrB8|xp`R69#Cim}++y&6`!3Bbi=A>*=?kY7r)=Kl!?vPBR^ih$9)5%Tn5}wTOyRa~nSM-`nv#Kyu_n zN+uz#y@-?Uj#C?ehw!?83I_CGxCs-3g3Ho!(_+CI_3AF?&pHLB{T7{LM;4#7!;A&qBD-n-uTV>wO!XNImH9Qn1K-Y)nJk!l(^{kf-;Z(u&o zg68g0ffo}MYT)US-`Y9)4pz-K@wh+gm!gKe=XQi67P7gl*H9ttuuq8ZM-Ha@voJiZ zFm8>eW~r4t5kzX1Qn&3)ao(${i>tZ4-r|IkId;3tD4Y{LEg_K>UEMiqu}rgf8SUK; zr07qPI^|=y*50={8fiLs6ar2Xoe)vIzu2%*qC^1?_x&@c(}dzwAty zS`!tgM;;s!a&mr-e8@VNXg6Z<6n$_A3I;7?IPP-n(x%2vSjbx2KJ_CJOZp{Pm_ zW(QZ>=!PUv3+Kd7H?p0eS)2Zv_GS<>%evwZ!at6Q)6Q!=kQnZiFC~j<7`FPIZbBSj z-FSBnkP4d_dKrDy^NJahF`6$!6WjIcCn9@8FC4QY*jVrDzPXFj3fri|WPM7Nz-i3+ zC!vHi6Q|s_C!f?KIDAkif98%vitay3TD$MuIGlxv0q7?auO!L)bKS}mI9m_MRO_f! zezf|0GVG%za+5B^rJ7i3`m1CUC)hBerHrd)fpU_1j*qo$G{GQ1IV?6gIP!RBu^7wr z@X%k^?ahKk($gMJXf81*^RvLtTGa?Dx5;>nW-s*_RY>+@!9CC5fw6H34ZeA2T!_>* z(yItL6F6$C`u48Bwhl|{@34HwtrvzJy%^Ky^n9Aw8J9)6WmA*k+GBU$ar*GR4<-0F z7g#Zqwt6-7zBS-U1t-yCC$b(o{gHabxaWV@$p|YRcVH=t_=i6waNapX2Dq+vjkK5` zP8J?f=q~CxB8F``MaX?(%l25OelA0zQy2SbM~oTYQgM{Mi=@9}At*`DC!AWF_I-s| z8mRZO6A}$Sv3#D9V^7s+i6M*n*1Pgk^_(Rnx7k)|g=f-w$HWBk!Xr`5{yirU&Ix4n*L9BN zmXb35fu%1WjYKT?f|ax3ikk4t%?p~x*6trvzfWiawOS_u{3BH!E4Y$2=tr>Q@1 zii3hC*NgD8@6Yx(C%ZB*dCQ-{Em&qLotbYHNkk1fje|MTGP30n<&b37;g0^V?Xy?= zKcqdR81YgnNXbLEt<$fAi$xiVFV^rnk%d2$Z#K7;!3bBG+nON;I4X7GVW zMc68TP0uRkBsT&=&lDaFy8QCj7Miw8J-N$~b=a&r9-2kkot}<&4RC#SOP z4)A2BgkrgUo+FJWwi&}OBO}|V0ajihxt)`T+3wBQA&XtY86UW#rX)Xl(49N{42Y$b zzSRw0b{eF5?V9=uJNyL?tt1%KloL?xBj+p>ZkfA?=M&lu3e91FXslmheCV+`Pn$XrOOC$MU zbNq2n+urW!^~cJD!apPk1flz(Etj5}+t#cM;(M9LB%XZp)e|i9yIDsH+7w1SCaN#} z2BMzSMn@D04k>trbkr|H7yI*!8jL&Kql8lMFnlDgd{)q=K0CF_mL$yf@lj7t>>hIw zw*mSOn-(y*#z81lbVa-O!#T7X_EH)AfVi4swe4-lb(7bu@&?<5lU^fZ=K1jSsGPcy*^K9HK}kQ{TUd zYRU*;VauhXr+qnXuQ2Ojp-dn#vUt(*QCl=kbpxt(bRhF&hb}-Ht>iCRzB*)2^raI} z{eFJ&5L9W9H{3JJFMiuo_*VTCHkoUk0tnrqu32)jQLfy*}!Cq zrRyZ|X3g7ND8Lh(#H8g0Z%9~KR( zn&WE%i-DQ40jZxSx$PdTI5emn-TPG$6l!DtKy9zv>Zv%D+6l60@gfoX!X%rR>F$X} zYUXyI*~}QZjhu=^KZKESJi%?O(<+-EE@R^?SnJ`qVA!4ehbx4Hu<^zW$nM{3Ydc2* z>P%U0eyC0^fG1=F34RT}Z48=l9&GuW?c(*Nu{3Pr*5SSOnQk^)cDBBh^&l~$qN0Z4 zLpe{zW4(zY7D&9N)={I^nbP>zVAyBr)XE0gKALtC9Vg*RNYBZDQD+%@ZZ`Xd$Ser* zY{dqMy(JN4)OXofHGdpd#kBICuy`f^E|;nq+8`5<*J8m1r6 zo24q5FSvgPFBshgE72}4q1MtYlU_z}jy`*8Y+>6z@FP{$$1Ns*(=^pgI=k>#xm?%eDTS6agYersmsbx%36Z46%)v&fsGtqa)KxKUP*hG=7 zoEJ3*`}JyBz2v`>&@UoBG&pg5bMWJqSTsF0;;);G5^Gm*0YII!pdq%aUfV~=zk{ls zw8zTLlC?ub;-_K*_0ZQNLMzm+(yqZT%v!mLi?d?^c?FqFPLj6%eIcOf`e#)$f#5Sr zZzJJkvDe54vx(7{agmn=kxEcMD!xu}t0C{Q)ny)kioMOvW7G$J<)yu`{09f9N@%a+ ztep;bVKMQ;}^0}lz)_OCcNa3PQ( zO_!l^4P3z1WDzSndqQ+{G;7E{I+)bOio$?EAXR#Grd0>IFWNxpC=L=EjfajV<$wMQ zDF6TUmgusmv}38nvl^Yza(m0^d&_#-Sa>_QxiV-wxYz)|o(>HBKn7JeUj_j_0U-u{ z0Wp4lF(8mZU4=nTOPg1JeH2Y({ztU7@U{`N`p32b{OjfB=jY}Z(H7tr;};R*7v<#R s6XWA6DO_pz9|RXSYX{qa|4k4O0}B0z@G|)QJ(>VekW+nI3o?)VFW*G}E&u=k literal 0 HcmV?d00001 diff --git a/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz2.png b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/RViz2.png new file mode 100644 index 0000000000000000000000000000000000000000..a434ad55763bfe03d7b2a036f88095b915540e8a GIT binary patch literal 6344 zcmb7IWl$VUlU|Yl3me>mOM(Y?2^!pGkzm2yeQ^u!5Lj#j1bA`xB^x{tg1fUgK?4Mb z+xPC*-LLyE;au9@lSSWR^W9Bc|~004lar1)MN06;TFjSYYpDB6Cik%a1A z*h;HO0|52OpnG$4)SS*zQCkfFfG`07p^*TXV7rLU!08A46s9N29uqN6*i=skD#&{~{8+!V$tt@I_|WzG$0<{*sMDZ4bA-GB64HntY=Vp9h?5~yr-wf&D*;~DV>SS z`~EYB5lSz_d@qNpEtQ8=)yywttOMNtYu|cSl%lQWUg!2LA`VSTYy89FCK4RkFhem> z3g)<{%9!(0Hj_D!U}}N>_|^oLj|-1V#62M-vA+&x&dKuTyA#vAw+{ROJ>k;2VA>=X=jt(-t7Eb@ez~O`-UrBtlB-^3$>TZy6-3c}&q5Pgr zrE-0lerS62{K5CQcrd%0|Lm7FXs&s+>6K(`OH@;6>U10T=*dm0oFxW(&6x|@E662_P@phrON&OcR^7+$-M{BOBH9CW zU2b9tY1?spK^xKxmZmQ5?H1cHxt(Ii$H#ttWJRjYdKWhkjOWj5_JJ-*Pm;!PB{Qr+ZYN$qK%B7b}kyOdp6q z&Hi>NKyNu<~9Jy+Ne)XXDlkm$-fiaPCzHx=!bMuPV;JFfhq330Jge$==hEofS? z{3@DjI9OM+NF!N(o-K`_}5|vHJCI&&L&zZh46^VTEs2;81s2ks>qs!Af zgAaCf(+<+;M(pf?@npjjs#i*JL3A@e4c(5X<+RZV$LjsITJuKM3eG^mHY>v?d(^K6 zCe3x`2_CPh<JzdJ^-3!ACNqP-YpZB ziTr-{tn=Q!8e&9Of;%4`e!7J2^EsiKo$wH|$5t;!NlvJuPA?PF!wKH8BqZT+Ky*ND zIo9NSW5lqrK%fy*TLF>EV>#zBb*il1h|d7B538(TOBM53ci>M;NeeIac6=-5J5b}O zPZb`a)Y8x+rv+TAqo3j_^|M*GdAYQdiih$H?W2KREF?v$T^pUnkY$Y>*Mvh<$X46J zQc;@G<4XDQ^kC%s)o}XS5O#Gn<|BthSpf9BYRx@jaE8<@$15nh2bV%Kk7ebr3EQjU zQ-{UOoB}--J9jKQh00K15_M-3f#!*m^#&78wLET-w?C~{k|895tP7#X} z)g5Gl*eosI_+PrjER{>rW@-@%H$XU)e}{Qhe*oq;ld{iQ@Lzuw5_m0Cx4#TpLyyE4 zNnsUFlz(}4_K$vTQH@EwTJ?wdnOcqIWXUwYjb}qxSSdL z<`>+2eRW}A7;XNY4Cl){WOK7%W3#0MpQ!>|1!D`b{+Rpj$lbuGPE?<9m!me~d{O-75J#;}N^~fh_IthJebA zzb~-WQfIy6TQ}!D?WE!~c+4%a#rrf}@1o_>h%Coobv1|sbTg&~JkyMBMo$-7y z@?uj)I)1d7wS8~+Xe9ormsH7ZBDfger#@2 zJ%S8OG%E25=J7It7Q6&kn?RQRh{R^}yJTbO2$^ni7r=<2PmDVZ@$hF%@a!e#lX8h} znME>2$@=6+ewEvdUk&4VEpS!;3V8YH^kmq@8m*ag;B2|JrY1i*?yTRW-Kp>gvgt1@ zAF8Ol+C)EC+nJ7)kXUAWz^NV-#!Ay#-%$iT+prC>y3clmF6r?@qca6hFTxCTw&Sf| z)>>cv+0_D`X(z~ALP9HshElR)kOy(#iK6#o+0qH7$qKD5A8n%_55T&KOhMKWMcF=y z+vRCJgVgL(A%`-{`G-oXs`Q)^v54Ae&rQ8IzQ+=D^b$}p-{SglySl~}qZgHdOtfCw*?Eqnu5_6j5^}P-dCWncTrdwJlj!p~%&^xssuUAFBuU2Yg z$PmiThcHARNWXt}+7OCYvY*<5AmkEpM2-3=9lFL_of0h>O)|-8WV71GVH0lhal-O}9#FRraiRfnxTI z(KRc~67*^80Xux~E0)>aQ|z>XN}iRR3a4!DSTH81hY(xNsY-yMxDWQ-yNG?=Uqcto z&2fBD_g?o8gYxQ;%*7Suea1_@_csV47yf1ffKm8jP^j4ts)47vXq79ZqMuttZ{@(B z{m|{a%vwJZWb?2=@+GZ!_SePc*r8l9N4akKvfhCO@}Jj!8RGsim1Z#PwZQaq3eM2n zbTDKun6HB};0c}}UyM(k87i+;r^%n!5iGW34oZPIk5)DW+vbHhKR-vu!B(>xuU@pOB#s$?aYU*-!p z)kFcSmf~5DD$*s5T9Xa6OQ#eeoY_B@#}+-g76|8%u2Y51o;9k%>DA`;K{IPCU1wBlBu{i_3|U`A0MA_0d4!t<1v9R*&VEgb#Aj#~ zg+lB|g0( zlhW6Eq(VnrQ|<7z3L8(^XTCaX|G@L@;*U~6kigd5&Rb^M#tbx$2$q9Pyptm7ro+~l z&4pWR?02oR!S8R1Kz|gs85k@tXON# z#tFEjt(6&FW#(&dpYyUGi8mH~pJUeMckqeXdSDyoO&3f{L-X~G^Ll3jTsILbcg*d4 z)_xX;V`w6{`qlN)L$px{yWqU&-Gs-8!{2<7F=)`wJ)?C%glNL16tdUGq9vi|3Pa3rBcib=@~EepVd2xtS8yyEO8F zefwUbgBb6x3w3!2W;mQMxX>q^EbnI-%^?5Y@Qzuy$sD`-;(U+CN#WKn3cp<+_nA=U zKcHOb^@c$bd?tN#yP!s%f|JAi&m%?P1L9bhV=p1Igir1O@8gb?nc(PSrsnHV^!}X7 zt*#u#A=n@e9)fN$MC8-wSVaA{F5Aa9oZ<<73L4m3^}UPT>AW}rJh#Qe!r9A%jpV&~ ze!j<7fx4|PC2j&wYuBPh;vwdZNR`hfe1Li@{)q&*?9jGv~3bbgCNA(}Pap8WPX z2p6%(mZ^MEsN}Whnb2{r$6Z&n>DgkYU*|dwFzjUqY&JTqJJBncwTs z4*(623l0F(nq`bVvgG~2?R`FL@j_1fpNE~?!Eri z(PaLK(XmPT-8p3tJi5h2k$Pc!Q6p`bHE_T#^0N)QvN76o~j#lO*kW zuxt$%b??0oV!ZSETxeC7KWC({N}Qs<`25SWgT}Zw6>+-6kv|?9z}lLJ;-{DAy|tS3 zf#;HvPSV}=fsAoxOMSO|O3+7z#Kf&&?9c+o=wy6wGYB?2oScuLSvBD=Qlu2fAVW+k z{KgCu?>3iVl}hKL`jL^x~@uFl_pt=wE2knzHyKG zacTNH-)6DMj(X|IdJho<91@Qu^$(ut=eW_S;i+H8 zE#Fe|r>fyi#?_utQ7z?M$yX!Sx7`S}k!?PEFP?;Nk-v+03X`i?YYN|cAl^E;LgVVj*?@=bGfAY~~8f>)M>(`$%>FwIeB` z#6~ohtNZ=WtMWs$q))KNn2m@2Dwrl{R{?g!5%>4w&47|_+Xc>1MBE11c)0tZGGFkv zVnud`5nPS@c7!JCq&A4WiT<$N_1T!ERu%Klxx^yXA6BBecyx7VyH(BC+5VP}$ZXSi zZbFD1j*1YB{?=NIPzFxgPzL??nGN(${Lfz7A+sxw?O_rNOUu}Vgup3FQW;>Qho@)n z!UDOZB!a5hax&jWzs6Wvi}=~|=W7?|q%tu=$i7%2mN=P>o+z^poOGME`uh6mDnlZ0 zW@l&={*zi*SlA(|(xBj+P2856no8Ir6Y~Vm`>eZN1oiVwb8YavWrpjl;^8ri9U6XqO;C!=AyCl5%YU`T58G6-<^d@(RHL7;zTE^*?NvvN(l*Ef<`thVrpM>GEY_5`I5ryGuXvX>x^)f$ zx(H_LFiKjDH(gG%l=kBLB;~W0@xcFTI6=R~GUmshxoO~#uv0n`J33ZrrDj$8kr2xb zxl^KYn~Dm;Hsp*ZZC#L}LMdZNU+Kzgpoek*J=qt{a)+ip{%}PjJbrs4Oh#&Ji_?#s zf`;9Xu9PXvN1lfClFE86ij8b0?HZdg8<9e+-Ja1 zL+e7VC^uLpDZ)DH@1_BRRxF!6;hZ10T6DMFwy|rB8gQ_jKJpJ#gFcS88r@iF zdFE->`MULWPe}g_AZm|$QNzubiFxPiK3q&d^sGwNPmR&jZ&xB?(X)Iz8|?o*U!J3K z!grcey_CQB6XU#?=sK}&GD8^qf7@V#!Ehq?1v336dB;7pl;)LkNlScNdJ9Ji7|cX{ z3w0^LTJFq>F)9}~5N8&5KHurxkbaShK{E5~@QB*Yt0{}T<_GwVTNIR4__r|~Zvrqv zxv;5ga~Q{}7e-sCAGUWHXdJ>mgh4_=xolh=3#XKCs37(W9S~=2MA-(oJin#j6MQ&LYZ* zzI}52xEWx}69oS*r;*k1jN6SPZl*XYOI;b8K|l37iA@>nVyXt^uhOR!D8JEE7OxNV z$xKa2T4T{sy}P=f%qxF3&s;WF%LhUv&Zp*idEXe!V(CLtI(Bkd7eHLMI7vH>ZaB>1 zLDqgIoee`u=aze7B|%lEU=LT zjt`adNoBJU55ieBX1mCG=Ml>JypFD9t;%Nk8v)j#C61~AWT z+UCrAW><9cA8?oqQM*;&Ny@oTe#x8)S^b4AqO#Uk5K=f1GTMI-0MKkWZvA z=ciD!*FhDFz4<9{mRg*PO}ijmE1#y_qVRiO)G|Dw!igFXw#fj^nQTDD`RdUVcJH-_ z%QsQQVowxAzL+3iJ*(J972DX>)^-#osS!)aXgZWBN*{Us)Mv-<@p$i_m!I!BoupJr z4B#~TrmCv?67?x?y=@24M;h*XiK3*e+Fuou7I{QaYsqXSyu~6z{TEOn`;X|2q{eR7 zr4h2u&3h@pi_7Cq2uM|<)`D}73JX(6%e4) zRHKvA(d9Bg4x@mK{{pSdy{tto|3zB^{?+B+;o;yB*5&09e1eB6i5a}-IhGpqcLPEf$q?eSEhGm6^ z@BQ`OKks+uoI5jj<~wuG%$Ymie6iY^N`&~d_y7QaP(@i@7XZL8e`p)y;XK&(KUzr- z6_%rnh717EkW7HK!G7p7zgE`O004qH0D$mF008yi3f~0){P+QY-_`(tL3qaV0vROoSDbU6Fc~)s=mZ3}g zW){H_SCM79P}EcT1zd;i_Amg4s0Imb*9El4@{%+p?<{A>+0u$=CufJAot0Hi0gq*n zNz=EShk5XVl$7+x{sqNd2T1^{f+=jnLzgrI8ylMf_0RFxoF&qWbWfK=7LU_=p~ZDB zw>E-A7F{9aI(rbknoe0uA}bdAJ-0TTM0SZ#S5I$ba&pMF;nRL+csO8bX$cPx54P1n z3X^@`)A{qKen?2j?qbWnd+z;mz^YAyu?G#@o@lAbQBN#n zN+8Fkipb=?$okW}ikc}dteXk5H4)X?n6hul03mfMRboDnq&)+J^LZ`c1(j{0&Q)sZ zykps-$DfDN#QC}xVG;8#+_=0>T6 zTY@Ly16fg9V;G_4C!hgQH~T-4I*=OgbPe-4!@?apyA7TfP6*=nwqzy9FG|AUW-HU~Im$6so6q@f#6# zC1Fow&R2|EGe9sEol$S)vz~sIUT-WAxH**sI9T$Asc&%wYlZwpb5&L{VHor~d3n;& zj?<6ya7=QZca_HqEbR@2NdrArLa%R}oBQ{;#>GmuCW8HnVv-141!x_CBmwi^D-Oa>D zUyMjiK*xH9$5Jxzapg4V;>mD9Xmgb%B=wT)j7ESr5w>nHFC4}&H0`7Fh;|A(Od{dj z#vd?&e`z^f^vWo0JGraZmpIZJ_#N>gsm^S$zpm|L;7fvc{=mY$SZ8vcL9c zwH^bJ3G4vic_C%Cfi!79WWI0MEP&%`x82A|iC@e7rlDX?)*!oWteoY6^uTi_1JLSa z27P>R$%q(qV)S;(y$QEC=iJHOlD(UT>Q@)MBFievCm}^Ve$woSsB6}W%3z?^l~!)t zZNuy9-HT1sEmBz-V4%Q66Fa%kRN}rkcz57No6KZY>$+4=^~0g5>GC%BKpc&^dRL!{ zt=7#x3SrFEQLFnLpT>G3?xm{sTdWKQCeqnjvow6$dBT&2s-*l%|Fc-n8!llU9k zK0EkAkIg8QuH8H&;qU;TLvtk@n%ppE2~R0)Qv9*fn)SGjZ^seJ9tMvjDgA_1TUl9B zXO)~hAmbr}k+sq_MMxcf+xwRK_F|xN4q3xxY*@qXr)jdp?^QGVD1mn;)@4^N_=pd3 zuEzPb@^s-eKBVD9pye+`7oLwa04)@?GC%(BdW)Rxk%eRP~L-=%Bt zqvxtUs?C4#$}Ls};}akY0uBGRE|byK`M7#H>+K|@4;Fx{gs(QC@8yc(iZG3`)_&z( z)ra|)vG;0Ci+%!k*#0VIi>phCzg~gb!3Y?fFR=uM;JHs5os3VJ-I0^X>c6V^0}-p= z*(}JDh=PZRN4L6rAODO!;Ok~So(EO8w`&_4AN6+Gq`xz)+6pWrHadL-vS;_X^I??v zxYFD)mk=LA&`pHvOk+s2<5(pBvs9a)GAns%*RU*pB_p?r#$>lk9cGK%owDP-heUER z=INjc=iPTL^cwUq2@7BbEI*IoR&9PO*TKQ-G)`zgel?J_NXN(Y)OgHcaPWJ*zHu7E zn)5>*#;IoK>K&^XOLpZtEl5BShBe+85EiU$AT1R&sw}qT@nx zY|bRNeDT>JSX<5^6tG}OaSot;Br69CRn~reIWXiMc_2jr0s9Kw;KxelA=ht8^AiTj zNOM!-X}1g(@A)U+BLnu9(~2rq~la|94@UH?`Kx4Ki?u}O1~Qll~x(( zp14wYm)@um(EOVHdzn{Ave7C|pX7>BX?de@nwAYK=LjE^8`rIs^F*fGD|hEd}Yb(Yw_+|I1IU8 zSXv-;0jbcmlV-pbJuW#%xr+!0`hH|zj=V;uHT!f)`m zXZeX$3yuv%l~HziD`QLTU~BJBEhGTZte2<&7mkVT#AH!lw5~|I(M03^*<8^2mID1p zcFU-1Ig3>$I$;;`o5RJAG}P~_imdswK^f}1K0ey$zavLKW50R!Sct!Y0VHw>XuDzu zj)+`tVGW{mjMaOZNgYX^P2_oQdjq$eZV-18{n~79_3IDis5f|V?-X~E#9@?EK-|+~ z(ACq>zdt$W;OE&w*k|aQF@~}qI3KYUrW%QGY!q0ZS(Iiy=k{Ytm|F9WZa*LNKG9T5p9nYX~spC z)0&7K`*J+V`(}Vh{Slo@E!E9Lc+_|$6M5a#{!*+32lFDDXiM9Wa>u9^D*^+t{tCPE zS8M5dRbA25DXN8_DB*2YwMEBenNqEJOD5`)O+fEVrOKwrQjrLUkKuVRLoB$IjNYTf z@>fiSF5+Gj%)=51bBA6Y*v!}4^aTB?t`?#t6m*;@QAy?Kb?2QlZZi~45wvK)q6O_x z{<)0id9fUf9dA+S|0$C-)AIUeb(=Z!fsnGJ(P%F*dagL#%Ity{VdM&Z>t1U+I|1MK zmxR20eNI)xeeot?lm|T-*Y=m8 zBW}UO?J;BxzZhUJ{dy|{JeH#m1qIByy1K@2$a80B=Pil3$w}gXfPhDsn4Uog8klV^ z24P7#=Pb|xXB?v4Xv5;Z#vnchiMBrLA2Z8G*0+nu=J!rqHawBnJyhiSLKw_1UK|j2 zd^;w}ddw2Z1zwm@e^`V6AIUd`$>ObJP4`ngaQBbB|EYccdX2Kt-464SoC^sfqh?^B z*i$WDr0qhH{a=>S~ z8y#(Ed;8f`uE*hQe)lv7a^+?2u+zVH;7_N1jH=y&9pYJfdvO<(h89iZ3)cj!~G1CznIX+aC>|M&e-W zAoGZ%Kzpv5o6EoPZ*uPZ1u&1|*@R%+e#eQ(G``dkpn<;#E>&Wg=PeYE0H3*D)#50T zZan4nS0xG#{_ce?b>-phj&eCr_Bd8^=BSROw%0p~I^vDD^NW#KSS02=pFIY)Q@j*D zXFR;YwW`kRl_skv6CuD!;PUv?=4-cHe`2VjR9|x!yV@Lcaq4V1sBCJZ*R&8<>!WgkP;`-VKb9yEQB-KFiG|)VjPA1{G!=Vi9yYb3v~x z(O+wid@p@R`B$-eyV0(eq=?i&H(k~Or9~}E7RFG(TK`u$x<$=?8E)qmj?|Z`o177_ z>vM~4t4>ui0@!OolK)`~DBUa_!18zJ^lS-cMB`dBc>W6c2aD#VvuIJ1H;Gkp= z)b}|;^LFj>+Zm~8j(3%J-B>@}R98hgfAAbbyCseBxL~^wCkpJuiSRz_UV}Q|BEAKg z>d@Qdnf1KiSl1}M8XG=KXcM?Baka522k9z{cLL?MN2`IN^*A?C2mY*L^YXK4RbO6h zAJwo$`>p4~ORrFdou)HQ5pT=e7)t83aPI;*y<+V7puFfZ-FV%zRX*?4D61 zX=Bf4`kU7=slm!y#TXHR&u_*eh#oT*G#bu?_!66#P zo-`yC5FO%0cud4Np{Vgn=T#BA5I1RC{!3)BMFsg9GnoBt6f5W1c-p?LDN@a=AbRlF z$d~PF|6VH9FyfkYf%(IL8rWf`T}mIJiu$omWI1Q`5>G#LT&5ViT5jjNQ%dO5$p#Ka&s+1BcdSXVu3 zI8l#V9Lh+#_+ls>H&J&~xDLi4tLfOXc+4W-{>fXbNwzi7ZH!9~eSe(okXCf9(Ug%` z9om}JDf}#wD_y{`-0*mm&zFfqpqtC#+`X)Rt5|F->{2EKN-7xq^<@2|=p{}ELKC7F zYsw;jGg902kYm}V^~wI<9Q*uCYAKadDZPqzgxpG3wEX2I0qle1?`KGbF~5)F&gnFGP(Q zXYyLpuR(8|$#k%pw6sDh<$tsuQ*T_A>Y@HT>V^uCOxB($r}@8w#eZ^L=X2hQ8!fV2 z9x?Ow?o3_DOSioF^t=IaG7KJid!cr1y%BLfGXE_)Y_`zut%mEg6v~h3Yv22FYVkMh zHTxM2<&5?N8+!@vSM00f*U{LRzsWskN{U2bMKJhAa4LgbBp07T#kH!%gV50um`%^Z zt=`oSpGp>7MmCNSH?1Si-s@wX}yJMy}L$cHD#9`lfwG<=*y8ebEKGBH8e70 zldE^zB^l_Gj#&YN_RdrHmvA)68Hazr*3Bwq6#?Q-BsZ3)h~{R3Hac_>laE{~A&*)* zQQ>xPd5?~=CB9HCQ0&-NSuxO9g78Pv&T%1D5(zj*rS}#m37oBd?}3~*s$;(jqzaQ-&Ju9AV{`GOR=&+E z&g}5u8=A~v5w`&{CGN_^usm)K3}BRFRb3<&A*D)mxW@ej;|_W_iPMb;m>_yl(0M$$ zIpad4iBo#w=Zv$lpMxx2bJ4F4rRs00#bw}DxCnFByv?R@oflbmyabj>uMfVu36;6X zw2D5^m zKA-W%=mU`bAJEPQVlVOfAKD)9Z!Qo70)oW!1waxYF$s`34?n*IKYwA~a>M@uxO>_; fI|Th-fT)BJ|Nj8c^?src0Dy{urhKie^}GK9oLkxg literal 0 HcmV?d00001 diff --git a/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/Select0.png b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/Select0.png new file mode 100644 index 0000000000000000000000000000000000000000..60b32c761cece041fe5b3de33e1d7f5551eb3073 GIT binary patch literal 32255 zcma%iWmFtp*Ch!7f`#D0li=CI85<8?>9f*nKf(r zPpz)Lee24(`|PvNsSsId5kxp_I0y&`L@`l8c?gJi*ANizn?FJWcf{^i^MT6;dwwy+ zkHE*{qv22BJGFz5s)K-?k)DH@jrCVWGb{2`OWMhrv!>Dw&TsHUvp@0Ik2QQ~xA;ZHYzozOd-JO) z&CJd*#(Vv%M)}DJB!C`>{V98j?dmK4!=MZQ#ttqT>97x5@Bt4Ox|xro`M^-+F(T5d&cY zOQY@GlJ<%BW3(qiVZ!B0-YFTPFxYWn%apMx6T3d$*1u!BvRA}{3C)t(cS6H0cc?%$ z@bhbgG{ph`j<$Kq0@lNAhD*R9&@6ADbu?o(?L9VOW21Eb?UrqLJ-o3;k4MaGpbL~3 zLCfdnqzXk+4C>>!OB(;z`I{F6ot9q1Ow1Ol&-{4?vrQACOhgP$y|R~k^)P>|uenJi z5&OHRV}`c-+hm)kcW8P`Nx&ax+();w23jSLzl`OPuQXZB%2v%4j+!1u^zU3vkTOdY z^U37iZh4bUSv_oH*MW!4gTl23jB=s(e@A=V6b*43y?Tb2A(iEZ54}Y7u($buHqv`q z=L+RHF~7qTVWTu(oD+jG*y3Rggx_C)O%y)DcZzTFL+LbWj%~wRs~JY`&Z#=YW3iON z=YLmbbeLw*r?}l6vF`i$c!=6>)$T918zS;}am^8N+dBH?nM4|!aR8zYYTf8Bl7uRA z69qYLHTj7HwhMJ*kwb98%wu`%~9Whl}6sh#? zc8CHjd}nA>BPIdT>qX#5e3;cYZM_!x^m{vABdVGjSx=)NTD9(p*wjr|V{(E~F|kE6 z=r*j%GUJ0Ct6s$yA6f?bEa{J6OV_JqMtV~;sJ8Yd6pZossvm7!Twi$HdbdgLFtZip zYUw1u2`bAfw95}J=n|D;=aq?jTrS1FW>`L7yUR{n!sxcukPz$L?mkxZO(vaT*89tV zvFihB|3FW z=MgY*%2w>f4w70I-syt6em=upryij1=rB0)vL20#)s3kVX%_<#-#66FK%7Kv39$g70faE z$ll-q_q$9eDsTkt-eH}62X5@VXIM!A&So_HVC`xk&_I(n~o#{c8>qg zE0F_m`#a_@KHE36qsbD8kNXD;&hmz|0FW7ka!{$%96kI3Jmn*pfLu;aZhG&Z27CY0 zfapIx|4&Z=Z$Iz6kD2^;ASf;W3`~^&4KwWCi5>j&oUgF|_Woag9yH`<{b6n{b;-%G zb#U-A*8p_M-YQq*;mHxD(|5Rt>q6DG`61REEpMUUrIvv71WQ<~Pz0Q!w%SrX{!{_< z+-o6l`<+v*jXmPoe*GH~@3iN48Jqo;kRG$k1@4BjBR)N=dFXo`RmJ-xJW?JaF{s(r zva=bV_?J@E^%>TCbKz=|OruXQ@rQ(SJ^ieq6T7du(BtKHfQF?7!^QK>7A%^Ur!LH;` zWLFvIkC<9-tL>3nDz!&GmAy0ut|d}qRL0JkX_H+&=}gX%j6)-KhBnHXsDeDt8y1b= z#;xs6i;JaxR83gU@sufIwo5(uAe(l9`J2UKvh{r0`q!5P8v!Z#3i=qGgwrhEfpJB* zSt^^hv7jl!MJ2AEj@c%6kE@^#mwk?z_0#UgeMDMz>o;>$!yvjA%o(>f)Sm$3(maB+ zC`ecvHB?Od9;w%}eg-p2TMHGhSwIt7XzwhPV~V-8+0b)%PbUuF-}vA!xDkF)z2(qo zNb7+hdTtLebGKk{v_>ky91IHt(FWom7`*(@nfGpv6wST=sT~m03H!X1W4rBZ8DBo*WA#v+Tc!#=u zde18*{#9;YI(|O)&Q((-^Z-Kf?4>$xNTGAPvGaRV<FYlmaEuYDb z^xUNMB3j+G_0NQJb5QJ0K9ka(@3n7H%1J`fVbe7w5^}+=DtKP#sLC~~(1tENrVzYZ ziSzKp$5JYPUZ?w6P(cDC=TW54`K4F{c2T}OlIOM%Z?i2Mw2l>`Vf_USz=A++vg~7v zNF$3Mgk|VZ5g?@T3Yx_fL$;g#2?TQ-$?2-Trw1)!&2mNj^@reifmDWpx-PY;tUR&7 zf^&2<2O*dm+Xd6%Jj~*6={K~z3R!s1>nUSNLcxdhEFnfbq|pKMX7M7%l-N7a2xuS8}xX=QatQVz>lq`gC{>e=-jPsKw0@lJ=y&T zuZoK)k|y(IbQ3;WFoS1QX1j&XPDd>WsU*VjQ{O+&)My}bh}d@@)tZgYBR=2MnGEYz zYOP|+CKO279a(*cF0!6>2|vQ2QR5^kFpNeaJa(HHz34>`&*5q;a}f$}(^wG^Xa(8A zY`EoO{-+MUW*f?@p<-|02r1E)X0bSGLB#^f|3YtPsrA` z6gsezNdBdCbjAMxZijuie_X?V0eCV#8YU*@K)FWaq&s@ zwF+nS3=I6WX;~fL{L&Ji9NN~_7DK&E!Q*6p@;^SoD|xJumW4fxsrJp5miB}$%fjvc zf1Jm!|9GAy4gxn*Q&T4lS^&k{l%JlTYs*h8r4Ar`eSMcae^S{}l0^EObkprQd<6z- zhmLq53~Lj4wh>!CF!VRzrG?GqfgyebW8#qR&5`j3OFyNb!rsJFU*=HEuWNDa;msT{Hk@ZOR06l|7Y&178$FjHRXGM`Pcy$>-Zfre+uT z6)^6b#OM1zzyP5A-}!g_9!q5v6Bl<&npQHd*|SOY>At+}oG#t3q@=-~U?f{RyY98M^zJ}-g)&uo@i;Qy zs3@d`N*$R-t{bpjX8n0$-aYH9o#Qzsf+;@lZxPOB=O0we6xVuMappDDUtTgsIP+I( zcS?}wex&^QU4yU~;{!*8pDGIUNTxdI0M7TZ!3wgJ5LFtl#e|H8>CjVMX^ErV6N$ES zG-cFBhOr^xUfO%%d15GMjVO&T5RHyew4O}|Q_3KhgD84L7aPmTr>y8(F_5y=PD>QY z&Sm^FY8M^36FL_>_=8zXH+8DHls2$_FAU_+7sREz=yTjqdWjB>H@CeyLBvxg6q;}Q zde~Ei7Ih{tlqunrJg8)O+&E+5+XX!qRF^v6TlA4Sm?;LL2!+bGxG8`>uJ_)<$TW!2 zc$1a>rOL9|PEiEY$^m?ug=4!$F69;nLt4KBI{98K}$k`q|D~%it#WaJp2BcC}xu;aP6haz2i#}ENA7a z&0y>Z&Xz(=MB+=6!3oV$?(l*$I3nWnN7E^#yPtTk9)>6mAC95x_3gSp2hC2$R;#xS zpKkEvoK~T>(Qh#-kJIpVJdaV6-*a;fnUeh%)f^_VG#+)#Hke#!wWI)>~|N7s)& z)ZyXL(i-MR+rr%5d zFt|l)xjF68+>i<_RM0G%i)2aG=g_gzN+P$&VnKsv}{RBP0f<;BY zvS=F}`9O1}SkcVg8k6Xed{G3w*rg_;NTG0qq^%H)bhE%^thTZl&RQ4);CoLj?@gH9FY)gQy^Q2xqT=8~ zAl$|_Bu)IG5<;U_a7^f4g%vO?zx3j`#yC?hm_opFZJEt`F;J=pPv-JoHk+-cFf>K+ zNOPb&^c~I?(!+B;i_IXPlIfK~IK`b#rT*^AUGn-K-7@Dew4Z~Pzx^{Zu5JP1)1CJP z$gvY=wEb3iy2*za?vG+QEqBT5Z;J(oZfvcv>N$KoJ-p0PX?@J`;z$wv4TJl;=F zi_cv+sh3Ljg>mO4ba=wfg*ghBSS_>IgD}i03^pqp9;zKX$DTI;k6oe~co7DPFPg== z3CFT?9SXppmqWj_eMx`vjXClzKB$9((z?=hDp8wxDxqMTKj*iXDIan}Jd4=K9Us;8 z0!@V>@74)EH~4L&t6$}I?%FS_g==o$3U;33Vc|2xu%5&r=u~6%AlZJ+K`6&*$`z}R zf=b}vW&YuzL*{CJ^LvBj#+F*5O-f+GhTVlK5+B5peSwjLFeZQ7c+IPgYGk8+ z3dzMNk-g}dfQ+Q%2PL6gvV+X%NklOUaENeBI0bgZrNil(BteUGrI2gM(7K=asruIJ zw}6dQ%-zDP`h%54#If8{$%hGo_`>z|aZ*nVefA3xP)YQHWb#A-__{E3#FE9bP4ck< zY7+E96dmvZ4+BGeSh@W7^U^UpT^k&;Rc4x2ck|d2zIG4`diiMoUx(4X`FySErT(2( z_queez!J39rXa+^jY3tk5z>J+?Ke0f(@a)%P}nC43{Qf*+x*LL@cULG(1Xu91@};ozDa1&jq;Bqnu5!n2Qt?~Bn{+Eqbd4Fm8k`Z3bI{~U zoAHwqDTI~l(d>kyynE~**!W?RF=k8NRMTa@eOdC{**D{Kq|hvZb!|fQy5CH4#o0d? zrbW)RdB`{vJ!1cLC`}jxi(}!*H&)H8^_Lmrz~otNX|Gzd0!A#MCj}GM1vjI5eD@wt{_ber3ez!~#`>4~w0sa_5`8S1>VNCv?3vz#75fyTBau^)r1_woP@$jY&GrXxkV`Hb3$JRQWttPA2 zn^%*~rjXoF{@~_#Y1TuS25^WMZ#;H;fFs1x^|H%xR3? zZkv=)1SR^@U#>q?kG#mlY&WZKV4(gJ8^+HjeazOB~j9F?;)$Rq_ z1tXqKR8diss*~${%4iFhQ*Qut2*Yne%<{Q)1R{TfO^$7~j{`E|(@rlZo79KWJ_!Ia zhs(Fh--A^uBK78TvS_=32>>(ObGUn(c$668S}&jv-)9>P44gZ1;9-iZ*)@w^TBJ({ zE0^{iZA|}Y{-|F57yOWwB|bs6^cxI*QGD2;MSuwP8>gVH@Io)XwU!C`WG%ryK)RqD z)Y&grz3jG(3*whGvuepVmVV!PODb4e<8wb(;f)r=6QtOqFpI6cT7+@GAQ5#fmZ6_;^wLc?}G^y8kcW8GtYFOm3XTT zBlq0_y8hBfUnL0}5zb`a42TN`jq>1;!=* z@wm0Q74F>U46AOR5qyZRy1SRL)V5KCtNls&fcg|%GMPqyOcMj4i?ChFD>D26kC=YW z3u$q^@@s~c*XFvt0YGcPHKP17gjO{TF2anhhnIk_*~l}3g#T;96W$!$FI0)cw~)zw z=P;pUt;0Te89g^8IFRk`5vGNL*?Bl7VzO@d;_DsKgg@Suti;CgN2;YV{P)w$Df*@A zexc;;{gW3%xCJIsbzUnmC1<1YvMr=(+u@xajy}f3=7Q;rF3Z)aIsEeNr(TdiH4w+R zVC4;QBerX2mJD&THzHG$iq(GcMq=yx@JgxU25I zcddO*3}4wBNQ>CV(rRF9xPiIyRe`Wi&?>OqcyB7(+_9&@^5|e-qcnoh517)H(JyQ_ z>syC=x3B%b$BrATo$UJeiYJ&{8W8n=^?8`zDP^g34pDLbV3v~7mN^tg z1WVt{DE_Ee@nP76VMjBoh^#v-g}}yW&>8NRKc=Ogbr2U z2CXg%^tdo)@os?5*L?he9$CCr@3?cga>TjsJtlUA`Z#P-4ZibzbTA~;yenE1Mu)oXzl9`hp7Xj6fL}G?g z^{ApHfNR>&SZF5Szkc-*=i{TTvjOr;nXOV!d+&hM8US4L)1X~3+t@|C>B!6bX$hYO z#WUuBuYLF-($KA)MXtGtQ3Q{KK#ubEK+vAXFBb7x;a?nBA}#gliAlVz+}J*kpe`6 zkt{(WqqE4(e_a;i>?$rcwz#hDA9$GCk|aixPyWz|?{$Y_hye%29!$u9K5~hHKMH^6 z-!AZ6Q#aJ-a{T?ZM0!z2O?<-Gp6srNV6=iTSsj>dZvwT(#qF*4OOQ{O?pF#5I9Aq1 zghblYoQW#$S1%67qh1vq&l?x5A3x~0-T&?!Oy#nFSsMA(+gIQ7k!nl0tFg1ot=A3| zYY1rDl~l#qsmOSEW24E8wvLYZF5oR7msj|}ML`h?$OE4-F-2Zqo`+&ZP|^X%WHNGw z-Ey6sn!Rw$?r`uqkw(j{?QE*tOn5tXYDFj%P4Dhvla`YUu+%N`n8~rK>gvq}9q+M! zw1=Mvv7rCR^Vn`2ib}ha*#fvAkEHE^D0@J20fdtuPEP$JBVh$nsq(qP5w9trCCz3URtbPzV7v{PMa9+m0E4(?~>_J+JlYah`TJzp-vO$PS6hXCU#Mb*CVP)jZ{>MtZ9KZN8OG!9 z%BBal?RA5mon+G>kBK}CBis5Zy;JRE>#MzK5`BD~Gl@!}-=g6vtQ{H4Y2Tf&Wy>zg zxMPSFC@xn3lqc!9C9Vbdiib z^a`MU#JxEfGy8VtVu;+3nwpwL za=FkD>g5UFg+dLtr%qh50pw+FXTk#-0h{R{A74hLjmN@? zjm~vs|{QG54Cw#n~2vDhZBXO3T7_2&Hq_YXC_HEn?~SMOhR&t-YU)&V1gi@BfFc?T$j->9e% z{uH~te2K0#yAnQGoK1Zz?0J(=4e}h7|4FUo1!cV3@P74_4hBR%ey-Tr|4x~) z$^pV0HjCvTaM(T~AP~{f(Fs&GS}yTd>-S}7HDQkw8}*pVucNw4NL;er%O9q9j6R$) zfG5@&(KlvSqwP6zNyRZQi+~$;eW#?6<+|Hk~p1d z5Fw@gSQ1(+Qb{Xkxz6j6XBF-q9zeN<@fP3K%;-*7*7je!)6CDvSSPBTPu~}GEMx>| zxqp%4+Kz2AY$xjWN|m@+%Rw+b8rT-S-aYKJ#Ip^&8mj#h_<0MR6n3pQ9E;IZwU(SL zGRx89vg=B_R4yD}i~iYfj??m9j}iYFiQ#1}W(am>4RWK#(Ttf5I>J+$v>I9hKc5C~;M^WbEAR2B?ktuF1EsjNCcfEdYu0l=- z_0w0%ghHnH@?vPY@?Y>pJ;psZ$fB~x9>#D3WDuQIbSUTo(ygUgIs zccs?$#63FOWG7-K9t&e%DPT0Ok|-@9T!p>~=ehEV4hWFVPf_k*cLl9)NyBUCelD%V0h(yRsibdyGc|VKa^sAT|iOzkCkvulBntmWnsWHWu9yov-{SLQQN%UD2Il6{+mBkcpt;}Gh8T;B z2UEw6WU8{+!bbWmfmPfbH{fmSweRDaq7U-3Mdm}}zjS^|-nhPRv{{n?!E2G5FH{-t zhw3zC6olUe%Rsl1lNBA+j%##vs9O!E>5L6`P9vO#EsacQ5TM9berLc0&}aui>_BbP zRqE_krb^FTWxZ%M#a5ybybxF_7?f%Jm`HG;_mlhFu{Z<@4j&Js_v7WWTV3*R+JQ=B zPg*~NZ-l0b+4QwCsmHDj+v!n$WR320)WPL{L{-slt<&^-OsFp^Z(!XCAQq>|4irjG zaCmEd!_aU6^j=$rKTvd`sQW=ll+gDJkGF@_s3C_@2;ongxu)wA>*6N zmloDF< zpQ>f?Ag5Wf|K^zDii(OP>uE)Vh2N?#q;H?jZYL*Y-$O#`ur(!8)6xB+ws_B14b7AV zhAEEbHecU1R)YsmMRpE+v~h#{@CBjf!>_& zf7gm!XY=&Tm8vYYI@1EacJuG)3IrQFyIhVS?EClcFRrggH$T2PUPFLR(|th*2neWh zzdb9o77F|M^XvETey1yq3aw67%XMZ~s~UGGPS?4z&$LbEUfoPp=3^zTlxAK|xag(j zg=3q9AL6})_CZMS>c@9_ww?(yT3>N{Q384vpu`}U#e2&@*K~{ zzlWIShd!-^0+$wZa3YjYVQm$Fpc7q!Z~d=ybI%SC^TFpl3e&BlxzdyMcAR$YS49Su zX-V|G)6+4ZcaW2Z4kyd?z>@rY_3$uQgEBEhh|vT&o+LvUqn{!ZluL!NyTQ z5#yHQo7-P+cb8L&2jn!65+m!t%1Ww_4@9^yA+RB12}!f=7RgWPkOVfb!KKmrs^GuG z{jBAZ^}h$HKJ|Lpq#8Hu@9ycr&4| zS6npq2m#4cQxtGYGlepcviaii2zz9ot9%j4yev&tM3M9Pfep5JRLMNlokF#>7AC5X((q>Qe02Gj8WLaovyL5$fVX= zI-tD6kY|9_x-f76sdztv5u46Mc}E<@WjH?#01XPjOhs+x>*}5lXpNkhg#?azD12g! z@rsQ-lw>F4zl>KHY?IUS=)DyHe7#{py}#Urq~rW8r8HNFA&M^wGlZ1p%1pMXQY;+; zZ=rf)awIl3=ibaT=m~RcvK^-N?0VoX+JR^i%6XfNEz>Ww4g5u8@7=Kq!D>a+DfjtE> z)*n86XbbqrC^{ta=j62P)TpmyeeS~6F89ejOzZ@udm4ZJQsAFm2?-4yRuuVRXh;+p z89Cv(O3rI)N(Q9jX>m2BRXaS`Ii1fWZ@UoJ6Mrzpk6<|;HuIHa;~X%KS)Sr{uYin@I|1!e&lIqej^vd5-qh-}^f)%8&&sdVN_e&SYaYd>p zfiW#YHzByqD8j0$U-VQWQ8ihSc16y&>{N$auHan;7*eITTpfhIR2}MzTVk@;zKRH| zAet!8w0PWUTw5^Cm293fOL|jeYsg!Sa?D4T_<{=Gqw@bu6ol@}?_o;L>~w-}mzG%i zo}t-^EVYu+6+nd>RA~a8xncc(!c_KHhr-}jZYLUT7uWnJ3YYsoDg_MM^hRb37R&?- z=Rp$7A-dW)*sH^=U$>)-fJIzL1Qc;Psl7z&RldrZtOavEC<}Oak1%wP&Ar?GP;RL~ z5$a;i-|s9a-ML0s^#-?inobf{|k2G{VM}%98JjiZ8&ttZS?+N>}IA`jK5NtSGQ+CO`aAm!R^xyt!hN1g4cdY z*L4%c)BwhGrI)SdrK;Ysyx)T-#*e%4-0puhZpLxszmI4f%9H^cFsV%)d9bdjRJ-%Z zLyGg1WY{>%FSt?n*1>G!6}Wt{HTa8aOMevEd}wBze~j&fg*_kR01(UX#p$jIr;;N# zVP@GuRl5uX+*UD@Gr$6DHlF7!n8#wKCls~XDpDN^g!ox6#m;WaT)4(^AiU;M@g2*c zBL5||7*O8K1lvsOo_OiYvoLC_iwCQ(Ep5$55xjmReY(c*!x^|Rn&G(KaA1T_8QNyI zzqCPSnsXkn1$fq;7^s~7e{0#dK|CjZPyJ5w@ZXpbHlf`zX7 z8FTA0FQomgo+ZpH9~h*ZyX?Sb5CUOhqEpUL-Irx54oN{twEcO6epg3#Y$&|1pS~WV z)w+90s?O}DH9Pt3Vqq;155mqE;$t}?wJWDG=pyK!5BMWrF700`%8-_a1I5{5mfiJ z^Szjln=_{O!}ECdgoWNM**ZE_2y6aouo2ev>6ar?7|9I&h~zp4G#H8qgQ?#w2-F^# zh_NO)ST#{%)E+UFOjZ;#R_mHCWHS-8w}`sdRuGV+4I;IF4&2=CL1HxtZir+YRApsV z;^(WVe;JQ!CE9Lh;5g!?&XgJ{XF`iN(z4Ch*q=CBu&K){P;J-zo;tMI)YY@8ad``6 zw6jB;0VaEAFzr9UWyrT9L(<4ZJD<9H+ef zELXK3*Mj_w=RFlut%{9O&ml_p%1o3OFq}yJew%2Ve^(2gMjGW~?g=@b)~$pBDO;CN zGeThHW5-c6XWnUOXjocVRW;B`hSBPqHlMH>v)b)|zg@>4tTzgaGfW7!kyDkl33(O* zRX)q_Z;Dj@e0UTf;NALH%!)P|+W+IzliSzM9#*-wIo#(?PK^X7E%i7x#d^iOmp1~# z=5qgG#$wl7zQZ4K{M`)uBVBk{w3sgPZy)eG+*7qQeMb)ZhcKzMW=hm?xNq8?z|^aM zIC;B$N=aN@^&*7JEwS4+MgYSO!LAK~kN_VpQaGinSG=t$NR&9PwKGu3Ga9p9S`s>C zTG6HHpCdPEipDFX)K!$SB%RCW4=rU3U2O(8Wv~PdqRJPNb5Lb(+02+YI;7-2?nb+j zP8Vdvuo-TE1#_*zr;GA`Cleob3PqH{)Y4PZcy#cKfO0@1I~ssrL(3w|s_cqGT{$>U zU#~Aq*jh`lFX>}PU*GjRx%dT)Mm}>jaDK+Jt6s|iVlz4{zRtPMCawz;gTY;=aVy& zE8&>^tII`!2w$^r0#gBLDU7E&L#Jn0zCDKdKte9JgqTyn>l=fTE$nKCBkf!hM0;RH zVTD>;Tv)nETFHDN_S|Y@&Cx!5F$@xkkS!&JqosPVe%q1}f{r!ZZXwHp>ctu#BPJ2x z4Ud3uJE*d7W;^di`E+`xy6$UKKGc+)E%4Ssdd_C0#HL!>=sPsc6=~hLeeo71g0ahX zlaMCYcvPH%$%;9yYyZN@F%?K4sxy7Bbc>iJ_8Mr(iPb+gSZkTOkZx>HIc596JKP@U zlo;NhD!FYJmXFs$Z*ujb(h0Er)X9aMq1rv2I(_&rfeM;|o&7YQ+BL z%{DF@x`b~xsPZ>;5D;;J#14#;NN&{ULUj$ye06-ERF51_KsQK$IT|kcb*UwdDyYUA z-1Vn_P~qsgc2XkSQA+zA_4f}>T|Bix=|xdTDfMjnFYb-YzvVUua@yhtWygKiS#YAE2Q-e*9n`bC`YHFsZEFotV+&aHh9MiofqP*_l4!h+CVFrR;R* z2gFlk;LV2`qY(_CqLZ<%{6C4D#&8~N3FtoVp4=2SfOyc9S{8cUE@uC_TWxuyFT9ew*){GAQ}H*Z2$enLUNTIF_W1c z&CDb5$w6?UvRLv#->CjtQ07+cw?Cuux$K`;{bI)F56Za@n_s-7MXoK8UJUPdY}k{` zt3O)RMxxFWd#hvI%D8%uqy z4gMh&#ZW|P+Up;eW$_L#7C~Ov(zS?~uq8#?-zHpBBt9t+JPp+hg_%uOP}*?0aUfz} zvL+9=OgF^EZ&-ipeMP>HO@zI_67cZQ);B<{s;?isi%j^`e2|NR$AIH~SMiBlnh!BbGW#)-{8Tz&67IJ*hUt+597N zt}VGdvPraf`S_iBE#%ot>!dcultCsivwnEgHl zm8!0QU-D~B0DZX88t0{yJR?c42cL-!BH6quCtAVHEaHln44K&m1Pc2&+ zC#gl$(d!GRfV3ul!5wyGCfMy*<(@?k+WV^mN5X@LTA0kU=HXLH7&TB0N6G=41DtBd zBVnWWX<+ciSEoMWn4~Ww!z?VHz5OOqXZ7v~j9}HhQ+`(QsBt#Hy@q?oLL1zo8lbee zJ*q%AX7tXb@KI@98pb3AtaXic+=4pOU`a2xjNM4Q_>Paz51Sf3Fn-eh{{526LS4s1 zer5A11%;A>^27t@5T}dr8@3Ir)*xma+4`yFGl&Tt+|EPGXjTO_;j)&K>f9snDbEBr*I zW_MG36L_=Fwx^CYQuiukC`H=z4;>pbnOOxfm1_rha6sS@ujBo8zY*Ww-U`>)JaR~9 z4xC3~sX1GWjn=`wbqXg~fS{#>s=IeFIQXJ|McIif4e@Vh4G{D>Sr8?(Upcw!6=`0O%gR#Qqv*{*>X zt0UK{)h@Tuf#NAZe8Nje_>790=w|fPN%Vj*pub#5R0P{w3g)5%{pkRMs;$+oF?Do8 z&O9xMNS6lA?A`jv)Rkz18dGu3w4ulqyx+T@Z|q86#|D&KQSu?r$RTq$w_Of=MlXMl z&9wqeKd294exjHx+b~SPYZ|VFSs+De@g#7HSkG^F5nsET1p{CF=g6-*;nEiVLA zUoI167xwf+>l+}FSa^w)Yo}~n?dB@(M<1YbV}wE}V^dl(vFuD4PJL$hhvac9(l{N< zu46d_)S!B8TM7~_bdT3q3G?MAM@f{?m7sFXjd>!V5wRtu-wEZ4dGh6u4V@Eb!hh4Y1y050&WETD zd?md1IxzOTi;zd!Epg=oN)B%Fjkq{XRp$`S<~PQRsi2)Hh*08tuG1+l7hkGe)orzA zD98dDla1`5yE3)kEkCarTJT>v=6)`rb&tCjN1=P$As*8{DpaNn1%_)!fhb7~She>j zJHq15AHGS2?n!l^^4dg+XmcaYq}9a4RL$g53Y}ulpJ;;N7Zj`#dv_g6?{j7G%w30h zAiwn<%e=(o6Ut=lER!qp$sGwuLNXC}2E?bY+24+-tHZ_7hK;TFjjlLHdT%WajI{TM-Uf2_3B24OeY*}M)ItO5m)+(VnlX`Dk8`!} z*4n$hLF9E7%t+6F$Q`c6f^@z~c?~DnZ%-Iq-JjawmS9hmZ+}A|c)?SV6t19jUA3LK zV(lzPB&ND#*r!=zR)}uMmz(@ha)!ej`vSk@#1NhuZL-8t$vM`qox6Qa>VNwtaFW2T z0b+0x_e4rHL0nfLyyPAm0$%8CZwUM6a6f@7wI{COK%JHZ!p?M5uLu&`Vz6lo`tYdM z$-m_^&WTf%+Q@0RaFbu}Kx>Io*;BP{@MXjF9^2A>l<9hItrTdN6w-f0+%FK9hZCxm zY7Vs>CCsJolCgG?7M4ZS7&FGyZ+$G{6|*^P1K=&sI1OgXu%sbKe$%R>;$kh@?Xt=MfiVf{^nBuTc3+uY>8j| z&HM6l!sx+s)Z=>xi6D;K3)KqWwCb?w_HxXQm;ENsO#WM4Gcnl!?eAMuM7FxR%Anc7 z#FCN%N*_cfY`W>gR6Lo1@o_F&-^43*epy&gA6Qc4@xt}aAZ}J2Cko%*=&JWWwE#8fSdVlD%KcQg>sOBk z(2O;sk|Z8(+yqgNcV1)MBm3)z^p)-j?vW^3ArF1$iD6v45D??xS^LZ;k&&aRg>KyL zFT2IlSseCN*o#bGi!lR6@Q$!$RDU7~h{cf?$@J>*k3aat@- zKVf=2#C?6Z{C88JrI`;3>LFe>*?i$3a%kf~_w1@7v%kn%6mv|B&2ft7wxDp9EGsZ$ z!oJh)@ehtU!K!BL>kol@kc9ZfM-#Q{I9X9!F_?O(j1`A|bF|~R~j!~NVLL(^l zHqu-34SiuZt?s!PH0$y1p7t8SJQ{h9j_xHIb%|V$#uj%~1Za%gCVhS9v!QCYMcPg^ zHH%|N5Q)ToUMX>LXi{lx;GOx0AVeHErj7f;t2rge2g;)rwFh05Gv!+M;FsIITXVLo z*QKaL6VJ+GRQfv%L51p6KeGg(U6tlHakH z-a#aO@$3_BN-a$>S-MetuitLRF7O+sa z3Y!jF0g)CIM1&|kL;?W|9YUl=I$H%41*9v|TOgE3NvHw0h&1Vh00AOG1VV|F5J*V) zp8bC3%qjDJzcb&NIWy;v-^?@2@C+pPv!46D*R|HV)^)!_8-hTphYoY|7G78~{+0~< zInz-8$E8J=#xdV#B-vF7_jdb?g&D&^q?xV1zkjX?HnF5?d`V2Z!7^xkrC|Le)oYk+ zI#uKH(praUIhucl9@*if0zXypnf8hqF_TM&YqMbMWo5ojs_n4)bmcJXX2KYYrM>F1BJC zVI@Djqkl&H6{LJ*m9Ym6P|7^$x}!qcBYD%=JS z%D3O5HA@vRO~8=4&CJXc$8L-^HeQQ){ybaraY&VOyAwb#RoeUp0{z(u1n?rKPut{s zB2+VhUQ!V$DW`9=x|siNp9O)=Mdu&-A2#2{%Jx9LC|)>nrkSZ`z}nfdqqaqeoU7U< z{Bsck+N|@kvn%|dAnN4Pb#_F-AA>K3m`1AihxQ`){`~AJ8JO88o7q>gyZfYRWnmO&;0Q{`2t4mK# zF1X^_TNb{ziM6ZB@*1x!2N;kQ)+J^-flHQr8R51ED|TiugLXt%rU9m{zeq%XTfHPa z3|IImbotrn`t2XHdRCYJMru52kaLFxJ{zI8$lIi(5r5nuZ3p!(f8{*xp8IuJGSB7A z&-5RO?!6Z9gCE4^8YfYxyf`*Kp~ZXklVtBT?VPGz=%_|xgpu(PP7kFa?V@-P>1}6A zTF}FkN;QpZg&DUZ>Tf^N)wE21;jd`ZR;>fBz1Ole%Xc*_2^@w^%CZwoX^;A#sI^ul zXTY=Jm)vl6^;*uE^SVqE?(FwbbM8x_k?n9&A6%t#%XdnuMQ zT!BpIX}<=y%I=YxudT`blObM8M!oNKDHnPyaMckOCm;L;*QnXj&hS;@#`)1N%Q@so zM;aA5Xu&L-;+yNNA;i7mNT$@OcN|Z7h&MH>C}K@+$sk>#HwvQB)3WD+9L&yk9|~he zQZqv31G2y1)xIWJPERqvoX{T+sdTG+S4x+ytB<1D9$%&0Lc8LITZl^C7a)AR2iPd` zv4kvpn}Wo{$hQXOMkt2t0o1_5=h?J#gL~eOJC0=s15V{R$DgKi7vq{S9g=jIZ%!Mr zJ+^iAu!`jP4Pj}?(o9%uX~o5o2{nxO?l*CbuQleVKxLcfGox+vpKRZV)6=&biudyf z?SL4KvfAD*d}MB`-&4cj~xg2+6(4N1xXVTXbl?8j({7i(=n|g05iwK& za3$O+B{8x@Yq6QcnRyRox2EfsG6%PZyVr=@b6V&!uY%c#q>+n^v6a+jY`js*zQ{29 zL4Txg6&eCrUz=z;LZmG}RIZ7;xvv)TgVq>z?Mi;eiTk~1ueVZi>b zrknBfa?E-d6mP&b6u32J8H2>Fl%sH?+s+KDis@)lqi5x;Sc@4GGcdXAX}~ zg~{LZFl9_l{+1k7(Eg|@e8}Q3XS?jI#*dNmM@uOxYH`~u)oIysmEi}eNuzz%B!51+ z`KaKG-ax6+Ht1$GWs)=_7wvOR1kOwsfpHnb z&rx|+E8jl(&WBbwam1mQsW(nR3dl40Y;;r^-cL%i!b8E6dq-cJry0TC0!!8rMJ-j$ zT&)pi)w#+^X{Q5mk4cp$vlqF3^2&v+t-!AJkRrId5r&**;+vsQv<||S{CY%(?}bfU zf0p$>^3I(l7||kki`!z`8@1mp2wR+0(e&9DMEc=v2HYj0@aM1GV-7SuT6jwc|5=~= zw$0M};7)SiGH$3>bU`PhQprYdG3z8q75ggm70**|`ym`kZQC_|itAWlwA!X^V9 zez7KmzDtxxeLAS&9IWFdIObrj;VEil2s{~jP$jCfK8X>gI+ome#;F(xF`opt&4tW_ z4h}Yl?D!n7bV{qzbFhDBAI0?x&Zu?mNpX=5b$+H}J~S)tJc7*;2>SWa7s>uEdfdy_ zdavP`WUYkz6D~o;Aw?E4FeU6|Y*?F;x}|5GL|+;=^>R`cFP922r`WO@XWVnQ>n}rg zoPVUJ1^5?t_|XmgO|+r7Gl2sg{3h*Bu1lKimmRT)Dn|-@4}8qHTJ=`nOr@hzeQlL5 z8uG>1Kw}S zo}j~aDVR4WNhDU~#O}P*TNL+{cEX;FDD7ozgs@SR!bttzlK!IxBc2jx6-%hejK);Ej?QRQUU(D|gC98** z${&N+wV|YLr-+`Yyx%3YHj%zqsizBV=WUzt^uK4w_6!^h7yCo-uXnAaBe&goqi0t; z;5t$Grw$0rl-!Py{p{wBHo1i{GQb#@uOXdC@U=1J6Ee-fnVF=e%wN+KcFMVd=d6diL2z5Y^18uRckM?#)5U9VH7zlV*1Z?c4|sDOF#UE%*pSg986a(qG9})JucM7b(K@k2{j_eHpfe>CLlm zt0#r^%9`3&q0_kuY@goycX{B02d8mAe@&lhH-y-&Sx?VaO}+b;-1^>gtayED>!$n6 zWu^`HRM@>ZbR?$1BygB$P(L1!gpfNhe2v=_J#PDu=@7cy@~k(-q)WJxR2kOg_25(s zh0k$H^=1B9=)mPbV41{Q^pE}Z`Pf>b1)2AGJ|5CLG?#Wqw%AQUR^P$13n3@Hp>Ur6 zT5P0Hq99$f{#oLhFgfR0HM`Gu&&Ef#U%aTREq-)|jIs-1=s6>{R7)Jrin#Sn7IahG z=n1ME=J%?*wwl;??15{QLa4|pdtz_jg&wO7)&Bi&=1tCwQn8XlqIMXJQ(v=9(zdcq zqjNnJzE&DhW&CVk19dw9s(89uiA^k7)&1c$5FH;iZy*+joxW_9WCyQq5rbOgsM;_g zu`(5v>{dOCBs)Y&vPuz@7N47yF#$`BCH0~=&bt>q$kG^cU<6kbVH12uvn72^GkSwU z5K3pK6&U=Nf{b$FvD2%;#N;P+KPt0}94;PJheQ5GV7z#jT=B(GMlt*uR)HLM5z4aF z%=u2)IgsO2WpQz_;Tq)it5-I+Z@)v|n;yGyzaZAo+f73BCubtRuds6v?N z)hc_=4?N?~WlYo@BUM>9pEI$$E*naZ`c41n)wNHyGw{|Tg)4b0rQYuJ?N|E8K)bM( z%4bgPRyO@Jr{sIa+w>QS(-Wp8kiF$x-~Lyq`ykMM2k_xZQreD1YCFG!K#hkV-#iTh z9Xhf7%Zr()o3P*~wl$n2$JGK5=<%(?T)l@ZX{)@yY_|7P(dC056^vguL&UqBFQEET zTBF#XXY{dC(?B^v^2|ZZj`xyQ45hS_FYQUjcFN z>|4gQx4)w>nPRp{mdo8gFPhA3DpkGczHNN#7S^A6#A`C5*ohaK^TV;hv?w%z)cdIO zry=hQia(?OJj%sI)|iZ{YCC;qDTmLuKeze%hKM9c_55M(vCS`fJC6%nbA&>|LQDw@ zjQJu(%?e(X3Nt+WB%K{~fB}2fY0!!~GORE)UxBf$x77wq}=R& z=IA++5;|^{?Nb=4k!XE$(h~Z*39449UHDnrc|1Bp)3zr3?I&#g&_{dmbVl9NoHC}m zN!g>0U(+|YV7JrV=$bp1kPx-*Xvk9h+vZx<+W3uz;>tDl&t$Nd6|wS{@NnCUmCbPB z>;k-;+Vv;@C6poBG7>$CrqUJ5d_0Q9SfRI^7h6sxRHfy)d)=eJ6~(_{Qe3?&)@E>C zh>Lk*p#0x|WqWRZ38yBz0FO%3%XTs|Gl$LVq}#T5?eZryi;msW_x(A{a>m(|%1CmZ z9-+kYab5`|OuL-o+DEawDDeupshLvkFmvM}b40N_RcL(P`JjO7M`8Ybw?>TGRGuZw zG1Y1#-Ut(t8vCK;utc_MSX#!*`KD%+k{GS5`+>rZugmB*LETlNbx8v+mch8xYZA#yu7qWs} z58jCuT4OsJP2Vf>6haw4~kCx zHB>6(kyK_{=#_<8b2V2N7l>4OU^$5NvO538l?!r3ZObffR6zf%Anruz>(7^TRFihv z59(*DuHFcc^2KDi?k_0Y+gCB(mz%1PJ*HMwFutd~NTYAu*T+Twc1kIF4cF6vOFG5@ zp`|@DaVJw2)9b`4yXDm2oEO!0*Vi;xQk}Wf=hS>qgw~*cfh)pv95vzFq~gvx5_b^8 z+-=>hlM-hYGe~rpfak{wRVESl{*$t4VlVyA!00J0EY`ok6>FOj?WadHNi!@m1^nf=iofr?IDc$5~X|=--`G1x1&~ZRI{N!v6jvnzeq2 zX|0(Ztg01#dP}8Z)3sN=*z9LHB@xaiC@gFX_s8l1Va7qi)tl(?il9wuH%YMBoH)g) zpf(sNwV+zEDXq;7o@Rab?*`mXF_}E?n~n`gU5{iy5|GjqQ* z2;63lG&q5oSZmqltrYQQ<45g0<}%+kvzJSoSP*pCbk0%cVjprK^dK-(#y)Y>_mH<~ zEicr2BK3eEOUXb|+@}T63y~%3W5R_R--s3(*y>E>K85x-kJHuGGTj@@3F8Jc#tl)k zb|{tUGIPzR3+Xvn{fay**1-Es;lJlBc?EFo1MuY&70-1Br;0)%%yMX=hd=`{i1m;$ z+{uC_b(599Hc*PSJ}<7Kbn|zg7wLp**pL)6p(TPPL3;WS+3<+XPCe|yd&4lgcIBXS z#PtIuzf7qmE4z&Fu`*+uk_a7`GiG7XH`MUy$icYw!wfS`R25tI%u>g3%*=NcB>qQK za)Ea>N|}+G%8{430w-aiHi3bn#tW~SWCkx(aeXtZmki9b$iMbBp_|YO&|f$0Zaw(2 zjDV?BZ<87VGUZjN;r2QyZ+gk|pnMRpC1G!-X`g2bRjnv|B%AQHfz3?KGCOJ)>LsR5 zwBT-EZcsmkkD`JB4zfj9Ft3zxc5tXWxPOc@Dwef5cNj1DMg}74D~U;d5TKdQ8im(x zZnv)IC#rIaWda7#YXtAIfYQb)~#Bo45uO2JaGfMCjku{-W7UWqoj3E@Xu_St+;fQ=$gB? zN5n#F3Ki|J#bu%7GV^ z+#-sHgARUJol?48mB%s5GY}~deWY9QfEMpH@u-&Ita(@IjF62AV@vJ3h%-Jsv@N&& zVa|Fx_UY57O68r0yvG*i=DZxsXtxL89r&N`&j!*6?qemv+Uey}c1cxLIE7bo*ph?2 zMIf=GtE8Y%ZW*RA|NXnjsZ$p*Tl){}+arlUDh;;qH^L`mF!UgTazTX?^y*;)V`TbW z5mdJDYp0YH=-ZWApUEpg@>RqG4x}H7i)CWs;?6$V%N9Wk$q~jl$Fd6nzj`VF$YQ@j ztS|aqq}Nc;o$vr0F?iv=6{h3{e9`*BuM}B=Kqv2{!fGa zr$PSXn!^7DGvuTFw9-9-kG&u67f^H*@!|2%J9qB*sY-!B3lB4O|5bGUH)~z~M}ABF zUVD|Olo%Fh&x?tTQP8^rXF3Fr>ZhJrYH+dGsBSyq*nZc#qI+d~-wr+JR(~45lT!|F zlwJ9xEDVaixNAZfikQ;FNMH3G`*K`-d%jmTbbc;a@E-HI4xtHB*Wk8)+US}ZPLZg& zH)Be-FMor2DQCJen}g-Y@DscH4uSH2jpu&4lH#%#TNWN82>2nWWoKD)GdAKZf^+@s zapKB((k@*=Q*FcI^@7ABWqT;h$$^=I0G@2of8(lj4lQVO^z_);QcI|(>C@F|>9A9g zLrNXG<)+Nr#g1@~3 zfh6t!IU@k#SK&PVVgQD9a|toFMU|>vawcVUXt%T>#Q&gY!CA|FpZl|POB>)CO9e1= z$ik$74FbD8uKQbX+cKCN(3C43Sd?|OtV#@@Ro=&~s|R0ZS>D(QP4JGye>n)W%{yLI z2pBrOJ-C+8$jqdfrX(WCpMK+#cH-rYZOaNnt5Bqg1Eh5?pb9y)1($<11(n(n^$oQ& zk@?M<-dHQngDfV*YdtJ2;9QYmogX|8A<=#g^pUnyxGqdE!;kcnLsz<>21<~W#HvyC zi1pE4dXWZt&3tWkzbO|GnIOa-TdIdZ?^0Udd#v`NG)w)Wr-+RR4vRrvSG!eCAfG>z zfj3s8PT9|2B@G{9MBw`0+b!h?hhMlOB{>PX z?fO?(qrLcM_aA1*yLXatvQ09R3e=Sb?9uJc(SGO^^tgI%Zl((Ui3j$`mjwxBOG}lY zDBmmsVYyu4)%uujgduHvCwa7X;pa{|4#()RUkg79*mhU@Zo*1=Lwn?H*rIB+6=pb8 z_X`v#vrdY&4# z$Om$3>UQ^ONJo8Bd!~@ zx-XahLB>*zY?#AI0zuycH3r)l%o$!Red5B!gQIof3oEIM)PY!f7_2V!vVpkLho&hf z(KiQi;Gi*VNc7c8O660=#=tnPVjS!8-rOs6>U;P~(D+?Zt>qRbMo8&e#h9h-Y!cjw zW?S&ps-*bLlNewtdiSa&CURR>g?klpR~jjUGEFgh&@eD;k?PR1=(CmPTiylc8KZgZ zbg+HxJ#|L&tyBjCT+C>T;xs{a5;$9f@|Xt|m9&cHl5&+@bLJe}CnqOUGJ|+~TOW`; z^EHD%U(5E@E<9ea&+SNYrRCikUv}UEv>E>m!jS%NZ2GdC2DKd*J0qb8nZ;5olM_{) z%b?|Zqe1)KCnX0tm-;Md;z48ia?WIovtD&~32LS8T9QOEY#F=R?lGJ)(@ULGc6H5x zN7HDCe2XhPHBk6=NI36}6ru=7(k{ol1qB#9U-(QW45mAv5W^R5nY25WF-A5mGV#cA zFclpG|KhkXx(~1~@KG{L!EPx+QrGei2?%*Oui8~{d@{alH{UpvVX{(gpG1pv?YDk1 z7^hMH^gy=EUk2C=Q7>)hX4qV2!C*MCNPieoxO0vaRus8s>de z#7eBbX%$~tm(%g01~e?U*;75X+78REvTrc-r|ngaM3yxgI(2>7JU*V7$r!uDs2*ns z2zjz_5KY%_5pYYlvRi0{OOOcn|f_~@7!hXLv(Uz^~k%MNLn4mD*OTB92A1Jxw z`_eqi>Evfqo1GfRR}CPuM!7>({Jgei6M^<8PDy&Km%+|DWEvmH(dFRwP+eQ-O_-)f z{*mM2SkqUD&EDU;%zSk0@|2?>=&=o5&4Q>$`rC7Q3D{lYmmpN3m}a$g`*}_vx4uE6 zGQ-9?T5JYvt72_1VuW~)g^!8SFJD4LIEOhR{S8FYh|ByD`*tYLxo7lH*9gtV2XAK$ zW)bR6OC>))wZW;Sp)Nl>(mCwkg4*eVnvA_-yXVx3CTYF=Sh<0yx~HU#g3Dg5T!kPH zi6Y@?l*7S<-d|N7=M3J+}&w1dD*TyoXx)? zI%o{Q=B9t8QYEtz{%b1rRru5J%K^x@W!@Z#k;a5k(oUtoHXo?*Cs0@aujGV~MpXsC z75^Eg&OtrCDp5qDsP4#vK=S7ZLwuk=K{o_IA3=vD|4BLqfzlQ<; z+pCDa$Uj3^JE|`P0==n_&rt~+n(;*!zB;QI9Glb~i^ zdRp3NK0km37LZN*kAbzk%MfBpue{`wp&<}P7ruEjq9`d=U8Xce-`Uuzr!5)p9?AAj z&Goc`KFe^+MgD@!9kZTe3V8Qi7hZx@>R())x(X+hGZeV27wP>z@GB?06<#B(P8Irl_KAcZh9e z^_R6+54L~>c8;B?$yr=Is{iHaC!DJ^qTx|%tU0CZ^(*~zz+-(l8hmWViclaHD?KtB z;cH4bHQtI%*2h`p^v($?!K{MdOwwrHx}DwncC~Y!-If?@iHj;-u3ixZn5wp6c$6+9-IJ~{X(h#d%LW;iPhb&`NC?2GrjF>@JdrFJamIR^QYon$)Q^bUS!+AgmXcXb@y6oH&qWB zdG~gUeLbxp$#XPOQX_Fax6Le0by!~<6y4Xsf3!KL@veh#Ce-D5rVNBHvH&}Zjz5Fj zyGywmUIJt9c?}QovfB2>z$o1{8{$tw<~r|j4#9_73QZMX>Js31Z(20**C#E#5(uMj zP#ruzjoh88Ll>O^!yOC~>7@egx0M$zqac65^s!`<%yEGZsj)71o!neq#EmbigJ3R- z?oSHyZMy19#gbB2yw{9oNbDc(feYhkeDF#za*u8bWq)@%9>Eo+ZBG>urH>7(jE;`2 zb>i?yRApp1%Qt=RNq*>^-OC38=YdH)_sd~@2UALh*Y}SbaPs{R>mI8rrkkiSn`bSE z61u1%^pDn9xNxYGaKm)TVB18Ajd+n}5T`M0OyjFVN<%N=;LUo=`kM?DifX0|i&4j< zl2kO8JNcTM{ojPQKC@km9nRXgFB-Am`>->os>hvHF~w@dzC3Q{wXL0qIqS1(uG#LM z-3(K@0GSm;aq^EK-c{CrVJ#X2mYhBhf z(I4wnHCFCte?#%Co#9-%QZH+vRzgwS$<7WQZ>?`VF&o78W1K+(g$<{H2J@uanIJsp zjf3EVP%tR^laloi(E(hbR$8Cg?%FdanLp(33LW8$ZSBnMi4D8QPZv=~+)-Lq+6E5i ze~Vh`5YX`sot30z7-6X9`iyoJd;jr93kXaP%XSy{JUIYwFhq^1<7P{Qh_OrMf8el& zxr>5&!Ca=(&x{iFY3bP%AI{j}0VU0KPN$g2-?AVO=&bqhfWMlR9kj4e1d7LEZ~jPX zl5s^j6ftMDydEE%OW&%K(O!U+X8*EUsjkXU_O`m8sss%n%fagv4nmfLr%uYAakFwi zF|>M;$g?a1pWAr>zIzSN;C*_{{n~o*eYt&;Gv32=7QsrH?$Js4YVQY%E>z0szv&)$ zh-7|XR!60l-OOA76JQn25!VNCz4Bu(eVj;~l^Tb-?WyR3P#VQRBrl_oxH3Cj_TIs> zo5O)F87=MYmW>a=wtZ3&@D}yKk z)uixhmujCwAo;?FzcpVf%yY^n!PY0aA~u@Vr0P~9lq-|OMVOuSjj?+%rPpwiF|%G_ z%%YaDtu#sgKf`)?z`<)w!i#o;CpduGHfKB|733Ag;}_?g*S0O_QerQp3z>y@=fg?W z*r_$CvDzz_w$~Tli#Sef@qs|yuClVSHHcq9A6*mG>j3KJzlA#23veQtxw+NPpC1kh z3F+y3)tB}Q=<$W78DHRviH*hHe0hpL7dLbxDJcnd|9<{Hm+NXDMcfAk|=~L zSFVUiOXGUemCinyH58ax4*chTHg|Tw2cJQp{2}E&>(J29f*%Uomji?A4uLH91u2xm zne3Puz(0QmY1pzm5*z5z6{GGwerH2kCHAnPSRPG`v1eJk*VK+csvOYu2 z*{O0xe*DqWs+$1lcN0IYr{4V3^oFJM+W090t1SvSNT28?h1 zAk1M&sk6yZRnj2Rk$~*0RkqK7P8fqg(dr+N4g}=N?#8@-lVeO)!_W=kqepEFfx^n@ zD2+ygPE7KFK594qztbcpM$`)oB;Q{i0<7ow<67UpgVX;Sn+V(68+0EFyeoO&ZI~oV zG))*aDW@se+`4h&Mtpp{&SD^-#boE^R%&fyb5M|sm^DjRlr=CgXd@f}8P`1O60*-I zxs@P>SS@h0i{$OO1HS_AR~;M$=&%NWlhip|g9fyXC$@m>%rAo-s%X%gw2X{fUti_> z&3{>(-W=%e{{4qBAZ}Ii`t@tW{(t>J;6nFFUp?r}MV*_;85v(V@SDIqi^u3SN`+rKqE_&`SddVQ-CL{^#VO`kSxex zeaL;!O7V&@Gl_Jr+Ef3d!o99UjMa$|vl?tUH;xFDn~l$A(HP2@##wS!@TV+p5x(h>@TB2%t0O3q?|OiJ&ae+#E$oSsewxb&*>cRM8F8XpE)XsmiKR z#yi8)0VBk}3*+=Pd+!P&Hb%^dB+U07gH|gm{8&9gn7O}jHipz%|1eTpH*~w~jH;u2 zTt`7$1cyfp;q2bv)?BjZ8$ND(=_^dGA%?pTy;A)8DR2KSC5l=V9cv}1L%C}_<2lu` zhL%l#VMi=Gu_r=)rEqw_Um)61jvzC*-FU#`Xg>V>D^Q)u-naMnuf3HdRb?U-vLLY~ zHA)^W_3G1{*Jy&d4A?o&#yuq!j|O2E>Rl;Pow!IVG&C?p}(3=&R4zy>(}C`rE*IM<0jQS-<>Pm7}!fxl?q z@9T^Eu*I9p+~*oXS&8NBZH#3648d9*#Tqs_#4B3Va$Af90o-fuy@QAjNXJ>^(7?pK zs`pct2Cr8u+@thP=G#WFo(KfxX5{MOTtzb)_YNrnNCiA6;~qmT_%0k4t|~|N^^_H6TK=pXago}d0jzwqb6BmarfR+U?v_9pv+BpJ^Y708BCxBp|=7Ud%_1Q~BQ!QwmjKal> zhNu6yV+lwt4@e0p-77J=Qm>*4m1=oCz+I%;Z4RQmKdIN%uadbsZedFKKG1aY03}%+ zdtXY1E5-VHy_fBW&B{@WInk%-8EMK%NTszn(W!GJt5NT3TShejH{LQxJHZd zvf#Z3dnVt4dj{3)CWDca+LC=UDu`&UpFTLc^soQ)Rn-~GX>YdEBik|@@GvNJ#^<}VWE^y$(D|D9P^x*i$ zbE+o#rU@~BI*5{@9A};zk^|^<3-ANfgfN#dpGks4Ze8p|29S8&;aqROOWgS?7dS~6 zab2;d7y^xo)p}A%fKqtz$B)-dt$lnd?W*9ird~76ctu!scp`JJ!ZzP#oto5ev<e*cMc18t3I5^!Un3(U|G+WVzKk9MQqyzfCLoKZJ9tV$ zQPjyi(vySNy)b_)?z*GdOoNGuge$b59^JNQmQj`e<}}p;eWb!VP}@EZ?PW3I99eOe z{|2!8F6!J^o^;P6OarBJx&`1d+JtwCMkT9h8D&dqT zdfXyuBG8hw#4cY_2Exzm4g_}Vi=X7(MDi?EYbEKXwDB#N<@MRqv)g3W%t^}|&`aUz zA}x?O^?|@!T!S!c3BV?L13O)$M6MKfS0f&uGNqTV~ZA(}y z>>pd0KOSK2W`u;p)X%_B;31&FwFFBTV^B+E3=Fs4)XkS|lOpw6sB`bh= zNT2e?seBHV$$O)SMN|};HJ!$zy6ga5KKphCxbj&0Ce}(0{vdLEl1kMx*iv#ZPB$y{ zX5d z`SjVOjg1W}K)jr`h8&Lxkr0Zz>NAnw3`p`lkur}z6zv%0zOqEc{?35;wc_~r_~=vk z3gy0((PfQwmR%azXoxTW9Dsz+KABorSa>M$GQ=!H*?uVmfPjmJcd3nj^M<(jhZg{k zS#gaZlbVtui0Ae7cTO3qVF9$56IH0EI^H;GC=lH~XDv8L`|f{~O?wIeypuqW+drLQ zwaVtNm41)wxRBIU1gN*ynV$wEJ2~*%aCjx<>gh7 z7^#YLkU){@%)&Oz`+L!-- e<(R)6@a+@??yHioqyfP;$kf>UX0_q{r~eNftjyv7 literal 0 HcmV?d00001 diff --git a/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/Select1.png b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/images/Select1.png new file mode 100644 index 0000000000000000000000000000000000000000..fbee72d1980f552e815424c54f5330717d94861f GIT binary patch literal 38305 zcmb5VWmH^Uw>1bMkl?``5`w$C6EwIx!QI{6Ex5Z>fFQx0;O_43u7%Tw=eh6g9{0OF zdNhBks5)oc*?X?J=3EsfCnJUkhYJS*0f8tX{!IY_0`eLH;$7oM7~m6$yX8XQ<-LQD zgwjXg&-0^UDDXe6qllWLu)UF+(0(M)a-85!B-`G#=0c5`rgDLiR7R^Q|xT$xHp9>vEmfuD$7ic2K*^ZY{o z{LyM~jXh7VKfk^0ot#81Q;D#DxHe;@q6+`{^Aj%X@0g$T|8EqA_yFZJx^b?=W}bKX2Ti7G3j9ZaItoCfaZayFIqT>h$0)V=LI z4BQjwid5=3o06(|J~gQ9>h7LrIbSJQwxb(xCl(VL;gPU(0sA(z_~8*+hU&`ozeFD< z8qjTtCw}}iqzn8c)MC83Nf>L&Aoq6yWvBP%6YJ?j*K)MP+jQvrJ10>y!%=?v*#P}? z9}SwaYcleI}Orf~fdK*I&4l3G2zr*f77fLHDJ5H|t)B1~J+*r^j zq0qT(x_YQjLfiOV3x%E>Zdj7}v7S@4?-!*`L88a{Pk)IxQqNtZf`zQeE{!bcSvb*4 zKW(;8NI+|cwtSbqaw>XhC&xE>0502F4PS`Yl#?^qK8-fJe(>hmvV501J}(&8^r_HUCcF)k7>)eeuf^Ji{VK!D1?I$6_AKQ0h5)32^r(3z(V>a-ApZh7u zWZ=7pmoq50#M;O03J0`9Ri!)Si+mVjgip)v@)SwpL8sg0^1``n*^K$MSh(>gx-!;T zS^+QqI%}`O1J+ZD=HtEVP6&jxu@<6;GLT>I9_->hE?;~|3V8oSSCKt}0v!y$czHL3 zs-}+>IMaP&6K5c?yr5r7#=crILtvUETf<~@<}h_=%O4oCu;l^E4NTAhc2 zGYpC>=;qIqXt`nH}F+{Ywj=FMPQ za02ES9S3FdO0RcIX%K#)3GryYJk?3zGROJrWC1Os;-iLxnz_+Ly)q`>zY;rAnX?5` z2KFPFmsFtR<3{~(%HLLom968wzbd$%S__CP!uMr#^|J3g9jYqtnMgUs`jal(XT9w{ z0KRt@P`>WBf%{UW=>D3o6#07KlQumbbjM#HdTcCY->JipV}6L~8~E86L8DV0ob*20 z+&ADU=@YT0h^Q#@?v5Sk6WtWZ}cHoqHJZ0rQE*ayPNB1x)FZZs$EnMA@S z&bf~B?!nRv5_h>l*UuZoI%R##xw&44-qw?xGA$CFgbNTKNDuzh)Dd_vIE#Jb^142- zOnzHV*ZboL0U@D^t(}7olYG(hg$`!gA^`bbXZ{php}4%6=DA_ z7+t4YbXEBkTTFy|@%H*SXMf30p4j^h1L`GWZdG37J1+?I8T)vA=fA;*76(&DY9rfH zmnC>s!M^bIrXpa^3QMR3+ku(c6aJpT`0mr?UOnV`wX7(E-2=k#h^}XMr2YM-I%~Q< zI&c=h(Z#a&yq$kHUj!Ev;DbwuR4ZxV!1hCJYoESdK=@huzg`120XPWd5qKDXJFx%f zD{2z}QL!KTb2#4c1bIAHQW6VjLC0ls`|YT2LpB|CsM>SG0N)BdiAjF@7Fg5x4^nWN z*}q+Q2_donZ;!Cr|BQen_w8#pUlPZE8vGgfZ!>ZK)&GC>Coc5A-dvS3j+l|D67lZ# zc7AEez~;<1Af7sinx)_>a3&*SAZV@=PlmbC_>21sYVzss-E$Yk&K<|9Bj%j7rIe2< z(BWonu19R;3fl_3EjiVMq2sgSBr|t7Eth!us^IMF>pr&+TzmUi-LvmkBPd65^)BIre+& zLNK)#ASFRnxCU4G5@&KU>sC=ud$%rKv|^p#^!z7T(qMNCO6BEb{ls)e&lwTIG(wIq z32W{9GS5t_4NaH@me1Bw3(kqhR;28dvW#Ed} z`=T8`=EEs%+fO+gLp3n*g%+o6i*RAipd$ZUa@+L%BX=7-lSE^$EgS8cbcal4@l%8P zs%tWBKA*8o7^5Wu*Vr1?>w0Ou&80{wou|vddE6Ezuy%2V!a}m2H#_O24jKKv?(h|S zFD%$~9tyX*tK7jucXH{RsKs`2AN}#IjQXi*3oeZE5fgL;@+wvkK;E}2eq|(@X&$&e z!D566^P%5}fT~Sl14Egk567hP@r&Rh8obyNvC+?qH!wbj>I5p}P(Ckql>})vCTG~8 zRs7bw52JGQst=X8@M{}MlIq5K?RnjF&eBPx;rt%Mph!Y&+xJhW&3o17ltAS(X*JW ze_8}aPikn~A%E~Dp`x1TLw49*kq;T5=_Z8MK|2%t+UZZl>!FbM!v1t^ z!~Aexl5u};B7_%{n;J17fo^liMk8}5|87>P;;1ixKH7d@{8PnnH!U&(9DoI)^aCHQ`-^5HlVh3umS)Oux1fbu`Vhx)?BV^K%S4As6?6L3RgycBVz9XW+f;6n z#Bk~i1KqKQZ!@_ypCVnpAQ)k`9YVST>Dt4AEgy?$Bfu_P%Jn4zS1Oh^~!0vV0l{2qgMrjS$Q<(slT?$;q4YoJgC;L5D<ncM|e zQmq8LA$?Oj)wTGI_%e5eUw`AQ1)=yP7~K8kQrlHn2KMPo`;NHKoNG(pa!;nX)+M2L z5D%q78T?wGi@vQx$nQ+KKcJ3jX__<3(cq3KO3en2T0SkA&gQl1bFY{TSRK3FvN|V* zYU^+HyX8DHA{BqW{y406WG*-S5g(pVIumwaGQ?=Nh3t4Wv!nA*cNLTvPu=T~=`-EWHJ|8U5{bfAVtg*mj1KStfW0{U`8$DT;|Y$>o&9IN zJX?aB)Th}`AmQ-`zzV9xuYA$!)aJq*|B6Ir6;-vO!p9<-shoco$`L}8{qa9gbF7ieurHI zo3?v0(R`HriO`Y~h~;*lY^S5yi59o3gsPH~yb06u>+5g%10BJzUeFKpYvPtDA0*zm zv`*R_S1uj`3<3-kury?hjEtnk{4(?D>^3qImk{#u@(J|1SuU$?))ZD7fZzS zfLwpzHo3>-h(NhDw|uC>OqzdGDm+PH)nZ7+VK}(cR=-@rssUg1OpU-M=iMBqw$FqpSo8(=OZf( zkELKDa`Ke^bt+W_QRm9Ztk@wfigt?JbDDBMd@=aSc<6HGXAGbONSon;B%%+8! zqUMKrF+#aVlBJKBp1yJRTJnjh_3K(jxJ7hUBB>Mn@J z1Xh@8=A&k^B^dVRmIemt>U%AvOIh=0=;ll1g)aV0AUeiwJ|Zd)(cRvwFK5bC$0z}F zi*6Cgpn7h>n6#G;=n8W&T-bVE>P+BcuY{6Kb(t}Ek-r9NZ=7HHp>vIAFOC>Hu&r+2 zP2i}<6w;KQg6!aeIRy6;jF;39CsEan+B=(>De{wF3AuCId`gv55Yf|5 zuGluCUfKPtil%!OVedHR@OpCGb5WEg7qC-8Hrdpo=il3rpt;kdKK;M!l~!Mo71m3wkhgIt+565(lvVr3C{(8Dd1TI1UqPIL`i zy|(;^5}JYf+6kyxWGE@zTf6(AF)=IgkiL?9TH02jZA3vRp-&F%YL(xh55{a=B0rx3d$^e*7|pmm7T@WqN}5gaiid}gn~eWC zvrD5>7mCSykkbA7b9pdFpM|e9G<+gOXK^ZrME5aXSuza|m-Ik((Md8521(>f2`6ij z-pxrtDW~LDNt(6LECpQn0on&yf^4Z}S0Ebss^%a++o6t`GldlJT?Yofms4g5_t#0k z$b-0m6$LgiZd6>c*x zF3a%4mSviM?XMlX1Z9gCQpTAi*Ue2Off(JD!*4d)16jYOi!@|77DuJ;1>!$6vQ7& z9Y24?rDz$jmQcY47qmkX1d$w zyy)NF()ukhhZ~FQCUz)lZmyLFV?&(zwoIxnzb#`I_p}k&9t-OkByDM8!rr^ z^~-iDw6?=LCDiF{5WE^keh9MW!(GQwe!|bAU5uw}^(hcZzfJiNT_hYOv@hgxHPZj( zHziLNZyElMn-@SwVH$OWU+Lo>#?j=_8wfDO=3B+InhAz(Jdj~yT)WHqIZnUzpy8wo zTnh^i+H+q{_*e|iG)&cj(|H2Jb4HnnS+*ZSIq;%rvCw4u}zOz!ACKK}O1Iv^-fn6G{hnSI=6 zGK^FgQz~gaJr*xCCYxEzy>R>IgGV1rzNaAlV13qT54&--ix2m5~twl9Qe_RnFwLLS_X=4DW1{azfkJ)?0D;(;I zdt1#CczA)uCrkAv?scpI9RlCJy)Q2>Pvv`|p4fiLW5GofHBh*6)AC25zS`4`&ZFq= z#k0S?sYu0W4vt>cUbx=JF&c(ab2UReTln5p1F)CK)>&9>W##f^);tQ^!^<$1jMS|-n~#u?30zKRsiFnubD1UrmpXLW0XF}wbu4y)*(m) zn|(5w3T<--j#_k9qqTVjJpAP|=6~+$5wxhoRZ6AR`HiJ^Oz;=}7Q=cgyrJZOsv#YgkkCh1q}|DZ)+d%+%Gu_S4c$gs-E6lM z1sTmdFHFk}F)^b1i#J&UA86vD0rRC{w~U=xxI$K27~pun+@Is?+l)3zxgo-Xpa`?F zNTfq|B|7qUe$D)*jdGvaYOOP%z+nkkychUGDKsJ~Vt>g5q#E0d3eZwrHDp;jCr=km zecx5g_YWrB#y5xP&4^l4{<7A~K^pY)94@fwO_XheS4nkDmKux`z%^Zqs}Ym6i;VgM zc5$m0SY6>sb<-btM8{pAOtpGH{KJT9^@kt68$ONVCN4diT%)uM zvVDyAvLrri`~$$3t2#+8D3(nFy09uMwxq5i%nZ})c$D3?BWX=-9qRas zfleG=uy5?k zuN|e5B8M@(ow-;@$_flRfq)ly?DnZ-&UP(*rAAaWcKmNPvOc>s?Y-Py@OgqeyANmc zyDL#pGsDa{>A=xR7Bt^C!U=iyA`ZEg4y5H3QT(%LI$0kJt8EumLI(ZI9F!^n&nxPcH?($tiqBYEt6ulF7S z?w4e9Sglw|hWgjH*ZjR-Bb(n-l1EPT6DERIuGk_VcJ3R4wz0$e~} zSlW5~R=;0P6^gMASEK*?RA72i&%t2OWeOvGjZG$(Q@xKxU|W?bKmp*c_!6WN_%nD+Wwf?K|au0 zz7{28{^wBRB!q_k=4HeuB#drt^(snB5AgQ~Y&F-7bsY?c-C@1;zkU!j>Q#Y&k+o<4 ztw>*OVlvb1g`9(7nq4zpE7GO>yy7s_>RiE{C0jU`NS2|w+|V4r3Y4XKo4&EJvwLXB z|3^e>tBK(2%Jz8~csy$#o745ltfFIJ_({m?ZhJicM=SE!NPK%RSnoZ$Q{lMgn*RL- z9AEOA-&8>Z!0T5grnppQlg-Udp)gd^%Gz4#T3%ve|Es+*G(5cTuP@I7$+D=Kz!5YV zI>2qZ1|Yp+&f)G{uUw}!t?Kk5-%NBXequ=^0@LX3e1o2w2LO>xN?@x3azRf;`%BuA z9suN@QpvpjOK)bqM)*}SxX~5DX}|puB$K%bWc1y=y_?(Hfglk1NE&Ot@krY1Gp!vE z%)YVxv`m1^pXl$8{i%9G}&h(`5e${w2W zz%puW1=$9SybwFOq{)ohT!mQY9nYDaa_Q3z zK;e#iDPuE%Q-O(F0TY){R>q{$>TmOURG3vRQ3|6{E-`$-wo7l`G}QAGN$X)-wqM=rG^=wGm+KPghV7FeXpl-OlMDa*1J+W7Zas@Cz{9Gd@)jkiC#P5tM4b4i9(aA z5w_Ml_Jv|2h#ruFx-9_Pg4t{!j`X)yBh!utJ3D)C6kc+nnbOFiwBFis{U6C{zK!#5 z??m}tcJV*NEE~QC+jB(9XwxwY7QQ4>OmoQ`;A_jKl0{ueIz<$%D^;KvJ^tRbZHO(= zv3~{95w}E=YpMBq8zTOvbKya-wYBwdCN~y0cQXxv*dOP7wJ=mQkUEi17gDCaLXgUD z(>jinnG>r4p2WKbNAok-3zD21LrMi;S61K^R~dBz8&J`UU$66hM#f|*sR@*qnYjwH z$=INDAP5%Cg!uh zVSQCf3r#2TI9=KBR$mMecAh^>xTi#`2fU-OChTpq;WPdlzDdJ-OIk}awImx6p~uY2 zwU5L6pk30)x7}G$jm>q+bmm!|F?bn|3AjGe-XkWRfBm3z5APjGAF93U3AV&!irfZ9 zmsJQT)!X6y@cK-C4nwlIwzY@e%d9c|HZbDSit5W%5^nOUkN88oQa~vR@Gy>4WL`8f z*{tD_bauajVrAyn!MSA8U<}%o)IA@6C}A&BH~25z)Z)9sKF}HbK3RaT?F-712593K z9q736tM?XM=($bf=^F2nw`ag{$X>|G`%CDgR z)B@;a0GpuN18n{7-8%pX`={psCx3Y;C3zSbeU>&KxsNSTyj3h-Ji4#Kb+v& zjjb{#&L>(`-lPxTcfUFon_51f5bY))zbG<#wcL&1kj4r2I zxR2S8RtPt2HR2k@ZmV;ma$}oYTUU`^OPAFaGDW*iC%sm<2fE+@xV7+w4Leof;luWTcy-O$+OBb9lwRB)k}0{u+&tSkHv#uu(`AsI zpf|jlaV(Pcf5DXRUWj(D)*IE)GnB_a!qoY&23hVyMf!;4!nTsF%cl{ZLe52`8C22H zBZ6rV6g$qbwgx%J%>pDqzW5Ywl(LBpDB)99R@Fk!2FJ3YG zl>x(Mu8DS#XVon8DW|z;qoV~z%|`Rrnmq?gjLUqD2{IQ~X0w~$M{(i?Np!S@LKb=N zMp}u!BWv&U7OtgS_pV7DUUGiWA91@%w>TzLdOv5K9_o4bGbFbCGS|aBTae|0D0|+( zwJomH+5o?vDo2aw=OCnOkaP7y25V}oa@1;nLPagYqPyQX9{Zhzw+Pa$P2Zl_Wa_3e z098I@uq)lu#flx+Qb`v3xU!;=*cXxS;AEuRcgM8ji}4=ex0X~2bMmQ;)?Pw`d{!k1 zLyfl|WYO;b^zYFSpa|HB!8^`E7hg>f7tL_>ACvC6K45+hr&To0!)b{epdH%KFYKBu zgIn1hDb$|l!F)nN=2@?oFyPRzfy66n5Ak8d!e1Gjc$zBH`j{q3OFh0n!Z<~l!`jse z6rDJDHN7%KCSx)lQqu;^(HMwtp*C&? zLF_z{La9sL`7EZ;xfB9lQMrjVMbq%4^*Yw)bhp5UStEhzd#%oZZcLpt4QIn12W-ro zI#yvI=zyP|dYSh)G`xZS>u%5|;x_{uO+xyV(a4{mQ1#_LU4hf?gDC^q9I@ ziIUS%xa9uwTmor~bNrx0RHH9a-P7^g+9v%4DR}5tN%+K_?$j^1lJJs}12V&?yc|<0 z)P_7ki7UpUXTV1Ib{mV^6ozkMubTf+qn&f+?;jFlHT8puBPWU!`9H=OdG+Ons)mPG zeXEVamhN8;zAILzaeAm&6Z6d6x}L6vNjAZ0n;lNq7>B=j+r?xdI4jD@&6sG{ z`&->`CA8K=E0a$loJ8>bT_lJ(uh4}}jga~H#Xf}O`uMzs4EzDKz*I(UqhvO8SIEuj zcF(nuyEk8(!!E3{c&U@Dk&?TG`Mo0d6_aV(XDF~GnFm6R!Lnd;*Fmr*s#B|Du*u9cN`jh z6Me=sI0vr|fnD>RBsbl4LjE*dS+~w+Ez1t_D9y78OwV?GwSDcs%2K``;Ue$jP7{^? z9Il(HK&`95Sz6-RWW}BDb$e+itecS`InHyA3mGxT@Z0gB^=lLAvwFJ+*$kajk(&e- zK0NDoe3udIGDnz3l7vxB5dV*vwx0LPS^|5AZ4FrEBfcZ|IM-7MtHTu#xSmZ?`U&7O z$BKR7;@xVF*xP$92vUBhqEo}AKEh*ysmM#{R*E%uF08ebk=2`LiZ3$`fNa1D6g+%O zT1@Wh>iSb(F9!1P27AcKeS(C9q{m+#!u<5<@9hm_j@moi@rD3K8Z!eJU22t9#akce zcp#vMzMA|?vgs9#5MiJI@2;V#$@t+;L73g{=1|!gpF%i33D0cOp4S6ualByX!NmK` zJ#B$AOlS^^z@mRQ-e9+t-~?DoUZ-Gcj9kCH$RLZpm0OpqEj!sKM6Iofw;C!+u0;D^p zbLA@zL>m!nD>0pj?VIioXhnV^nks9$A`$Rg#Y$exC(-yuQmLwr(QgsDf<$893~0@G zENi4E0&C*H5fF(Y%x6jpr+bBkh2Kc|Blyf@EQ>cVB;;yBjEI-HIDICidtzN4D7(Pz z7^IuIzlbWcJl5nW9uxl4Ie}jjv}V%L3$g53K>iJw?X0+vtijG;qE?G53O6@53<9=q zaaIULy>qid)P0@~Aj z(%^!UFolrjONuVPg)GL|lbXh&e5E9JugyzxgX0(tkk2@g15v^c>VuqeqDHMbuQIc2 zOmZ^T%gYOPlqm4@etu;vmd8uE3?MLYdG5M7k9c~TRVHI86}s{6Gkxlk@V8lBKXzfg zw-En8Mi?!-dVth^?Ge9$b;w|F#!8%Dez_FLgnv90>fOGac;64eB63`y^(L@P5K3hl ztW%Flr7DQNKti@BE=6Iq&)SHLaa@yQSFqdHa|aHy3+jNXJOw2VY1hg znx?bj?+As?sqMC*WgK=fv16~}tYKKtcGt{I@cyGbwtN`h139StIIr+Arg$%k8JEFT ziI@Y0XIljTy-Re7{eynf*_xW?eR?BjRuSRDDJtJMV}fF1Pi49BMEud!Ewo>s`Srd8 z-nDX-WZFm_!d&g?ZgBx%6^xfx5`yamx z{iFkSeZL0)Xn;l_1|)1guiipJLRp%892_Z7ACPhYyB7@hfkiQn+Z6bFtZlh()^Vsa zbK&e**y*trKW;?&o&P+J2spsog8!fjm;b-0;&XZ=1L^;tq~5+O9D{nk+C(;(KFN&+ zXu8p14;2STqSgH->scQM82&35fYRvfY~7+kTm%?mVq#k-r;+Omqkbjalf~MvJUkij zSab|VgXmAs&x$(FB@}SExw-g!o^ONv!GKL6pZDHsscz(?@~vtjJ3cTgSO&C}AH%1A zb2xLn(wxleaa#!-ThO2x3+~}ug={*T71N9c(6P`q$-uXR@dL+}$J1tj>W~{fOmn-O z=1{=Bfen>%IFP??o}Okc<-T!KUy^GRdlwgwcC&LMK`_AdFSMA})!(#OD3V;0&Y2^Z z;@e${a-Ff%x#qX)Ux8d~ufhG9?!@CglYytpBKV_cZUJF?Gf|cXw8+4ZKbC!Imf3SG zS!<83o7{I0us9fDn!?=Q<2hI~hAo#Vr+$6VJ%t-`ZC91sT*JH5e;H*#8{;ul)};Qu zrcFN83-{%cM`C~MN7^ub;A(+k;U;~;^oY6Crm5}6FMy@_KAX5whmR_9aj5p^wo@|Z zWt|(6cK6kOIMa`##O?WV+n2FyY-QR6^^rry?fU*X;}YerwWHJ*B_Vdu?S7OcwmO=Z zH8hY@(uX005BZugwL5Mhxo0NXi|{tMQODi#zEf{B#pWYS_4H|OB(NrQme4K5oY$mC z*>UOUnnJT0)fOT<_+xk5J;i*V?GIvaGb&xj(T*;vo@K1lW6zk9d4IJyzOIprlIlYX zDD^FE1;JTJQ-PPX(;XaEp3odJ$qlMF=l1 z@4-__iCg8CJ6B-y%_GyGpj!As+*|!qzjPAg@1InZ&Z(nt-J|fre*6P=EB8C6lu1bD zLS_}B!%c?6hApDyqvcUn)o1q}YnDxOlz#P^kZ|ZFGN9sihm{}hI*I*T5&LtM??>-x zDxK*hy7=HZ?awYc-sGqxTxL4d%SR8gNIcDq2&E#482WiJcQjkCjC?7 z7n-xxFdMXVW}_Wd$J+@*E**$2UEOh7hO}t@to6mHbgdOm+_8~NQWLd<}<55HHDQ|`(!d}dN z2#+UrM-1)MQ5S=~)xjgnGjW=8M9e2lf{vb>09y?(opdig3FhYunre?o(t-uJ(Y3~& zd#mb$ZJh4~jNl~&0EyKL237*in2=*ag@8pt#tumNVE5zwhb2#r1x+*zj1N7zUNHig zBd4+p`h>3+$5izyF$VT(VzY#JvIIv3waOY%Mo}*KHZ0f!o8=zZ+mAm9;zb>P-FnK% z*hIy@TmP#WkffkwCZ4!ay+7fKny7nDZV`#NF;0K51B~y!=WP0o)6zf}It&Pxjzc2h=PV(Li~cfcZWdA^8=z zJo5NaocWG>SyBTBl*?(4Tw4Lw>M0UFKS3l+kUup31*J|XA=I8x*8QMtW=IBg>>fJ&5mj!!oWo1U(DGP?V98+`_TxdCY zWrmW2gelYU9KrZRLCdsG&q_~tVMz;lbOOxV@&-;d9xsrIdZ4~ealGm7rZgQMQQuVS zIBYk$Zyrgq;(t^$=8tSJyMJ46c= zq#mD6rC{rqMA?#EkJxHBz_a|q>WF3(;Z|us!4NESha_v_F{<-%>oyZxUw@NAVI0TC z+bJE!9s%lesO`daemg)hco-r?^P&>a3Bur(e3fMEjD8pdwNa@73-R zr5@DAIy(Y#xVgeQF--5@;W)QhZRnH=?{#&FcqYH^`sPjLe|O6NIp7*kimx%UNL?Iq z+>;697GHLL$uFQ@7Z$6JWbjh6qhuZ0UM#nwC7Nsbu1bw5f@vf#M@E_Hl#jGC56k=1 zT5s(SI|9N`mczse(r3##5St>6J7z!6)--o?5+M~j2m|s+1rorm?_4>GNN(7V624?N z;@l69ghqynx1=o1fjI+ub1NL1@Zi(}# zA2L?y5_?G1p+|gvr){`@gX{TmgzvoqOnHw@qJzJEayp{XvJaRaF(4pe5e#q0>zG&>wht*&oz4{ zw7!e>el2EeVnh+22T!8>H`-Pkr@xn932avGlisNL zR6X1CT>6y5mbEdfvuD$7nj#Ypy>I#S4;9aYzKgLm#aR$Vt^0Fi-I0cO`UFJtwy)Eh zLJF2D(N2-NilgJeH18)58A5HaL#?IBCI~Or=P$Y$zcLt7KrgxD`%Yg7hRB8)b4ji; zkzhWhKNc5p`M_g-ZSdVMMxDQc^A^q&uI|VABOQL)bg(3$Ge`2PFRxL%q5N9jTS0sU z3n{?gzRPk3g@hQ`*kl)T{{3%v$3Few7r32%+3-;pphXvwvpQ5)K4bke3r>{v)gL<2 zxeSt*Hh?sVZlTSK+uPeamCAwvJ2W)(?+oizMQ@y--Pn0U(Q2F6XTBbI38pveelU&< zyyu!RT>-3R-oi6!s!1wLw%=oD++riZ?I-{r!apYDYlu%~+`m=}PTc=Xx(Uk*uTth; zBu#JZ)_%A0d_GMzfYw@2tyX6st%dYHL)o0<1C*x1-~eiC;Rjwe{{EBDtdkAh-zk>_ zAqpe379@_|UcceIyH^7d!03QFEe6wLBp8J|-dL@e1ZFN}49oAx7gvI0^-t6;x!S_h zT$r!7og_%q588rn&EWAM)p-cc%?_IM9Kz^Tn!E_zYZ)O;E=GRUzfU+bo6e=S;qm51 z#D!zY?CoWmO^Ekd0TS`Am(=v|aOl1b4Nu+O-3C@xN%sUJC$?AO-lpGc|E>yk(6qw? z{(r^vQXgu?^Y>5-f;43p(riMVxnl9**3$8Q?)v;U^Z0w(a`oS3{4|ycCeOPIe9pFi zOBeT&n?Y(^zhDbnaT$-|P^L|zeb|5QDtp>ivUDvkCQd>^sXO1=#W%#3R$CY>ITAKw zdJBx?=`>(b_{!eU4fEsP8+OKZA6eqfMP6n(t1WrRH>q%o(s0TI!r56Y8O*tU$$cHp z2~PFTQ=2q4vYhm0+*7-kuqZ*V>6+}sjDeHJd3uJ;s&ORGZeLL7d{rMyNy4DqXAk}w zynS;vtk;(@sziSn77>qUlrH;2Obva{8(%zMVYPvqdqeqNyNw6?f@JnC;y3O>R+>oW zfQfOivR~fx0b_R806m*j3%WQW@cW7=zQ60863jhr$n(PQKK+*&W^;Kv*Fdd#|J0gx z$EBgCcOq0A+?wLCUNk^L`>#V4)_%VA7bfA_xo=@0Ueb!Z`lv`Mn<~)tMnY&Tuh9Vm zldguCFOz?v6T9>BH1m$_52vDvw}=T5B1MwgB1Y~>4egT?ZKQ=ynL)#t4ouBmVCx@Q z=cqNJ{_An1-#i3TYIh>u*0`M@tKdJhRAwIAy)g$(vzcSJx_j2=UsNK0`H?YUX1?1k z^WHqI;I#u2^smmpM@7|Fn;C`Ml({mRYC_Ed+4QLi?LU+62JI3(T3+zyqjP1>f&dX)y*leSh zsY*Tt5*GvksV3rj>x0p`vvX&yIAYUin&eVQd*#Jle5@{RJ(3jm+DBP<=o+LJMn@K_ z`$TE6O~|hk8|w)|oo_=c@`-U>8|Jhx*Iee(oM zZ(P%o9s1e?^h#=QhtgQRBvP2;dXlrJb+(X+{#riKd$Jd>I!SVahSkgeQ<>?fub9R6 zbUos5%jm_;y*&To~&Y(4);BkEV zK%p@_d}E4^=`cRme^|0_7})JCeJ2rOw~_Rk@YG_OkqqxmMY=!1E(!_t05HUs*vDaD5825+=kZ`m~iM-F|VCc(7V;tPm%C;p@O3Qy?9+>Dt(|3DCMKL~{G}4zE)Y zK8askYjNnT1Q@vvUDX0CD6v#I9r@4LFli&8A{&u3aC+xuz?|Fd`onvF=Vw3Zc$Mi& znbw{>A-ps!o{lVG*>X+IJMD+It*2>A8?&v+rUv=H!|9#S(xRXCwQQXtH@uZDZ@P8$ zhPuJOG@CvH7N+Z6LZ{C@=4r3!CzSM{!>a%0sCJSVDM)K7R===YVxDtj_=RbqzoYkb z79`Bhps8+o5$hL((*?TL0$a&95u>{sTWaFVQkI3aTn0(=y-3NH1f zS(VwxR3nsdw?aZHtZD-a8)P2I#;|s~FEkl=U$Ewz4L{bxQT!@$6V1;lkko*qC}5$a zj=s6~Jj0-~CKMAsni{sy47S%+MR|y%)BlHFemBNNkMbA2+79Ge+q^4cA7;vIK%Z0x z{q*F8eJ^b(vnM@@pyLw`ST7APV_#If9x!zlf0L-b3CyJDZ6^6&d0t$VoESXO#Lq86rkmYa#l}kauM4a>*=+A)0+vfxBJ>bj20)PL z4){El6Fi=NH2G?q@`a>OMP=(TU5e*A?LVXRaEu&zy`4(YTAfHe@)WYE|5LW<6px3~ zO6cV*)oa}{u)$w0mwWUn4Ra{_n#6Y%6a3^(SlDPt%Bg1}uA0WhO1p4%MP^+@mE2z& zb;KdxKv&DV-R}2k^M<^Afaxc_uEGg=Ngf5_mnM`nS-y_W-rdGWV|rR>>V&Stzu@7= zEtm^zH*DvW9;n_*K4R+p3WIs}5=I+j-OjcMcDGMNBRl-jsQQ{Iowqp8%>N(cFdP4l zyns@m@v{7>)|0PYJ3>TxtHHsXv@7IQpmLz!i8LF}`u=6N9#JqbP>Y6+N{3dUb!SeEgPZ>S3NVnXRds2s_Hqa3W z!siMk8b3w)Ye%U6CO8-_D&L{}u@!0)KcMAhg1!Q0vP0?oZ#B*1(1B_@MYJ=t8Ty^? z=@4jgTfG$;a|h>Ti0~bCwuyU43HmLK;9v5`3!LhJldY27@#@3f>9mF<9E@m&J4Bbu zB{xNfeL3euj^TA zvASRbBY-*d?1+=0-YP;S0g-rmvT#|uHI2z?k*9V*a8Cd#9j5V9!kdcb88nss?bqF&sBb~_06_|Sc=c6<0z-eAU5W(YX)wUq5QXR_TqltUtJUT zVj*4Zo=V5mlN}F;;?=mV$mGjDOwvB5Zt{_m-fZ3drxxJQPWNi?{UM4mF>#zQ+%>|g z_oJ1*zCM$e^X@PXV8IFk;-%?A)sB%O@CKVv|Gmj*#z2u_!1^eZS@ILXR8o)eLj+EB zV6lUxBf>ZXvKO(3al610?w7mA-CVgwvTMReW|RXTmuEiz62FsF zlpC<{>+;fCfy!!cs>E2 zS#11Wn(b1=ds16{>tY9M!)I{t?i@^8@{4Umvh~I3oH#@yt8QJeX^#wLqSl{LD(8-+ zK$T9zy3TaZJ0#Y(G-`i!PpyVEZ7H7bcga9L8DqO8+WTs=@M9MTJdBQCoycDVw^N~h zr*Z|Fk76s#jL;L?YbxaE60@--0fkYzmSr|8O{`)=+FpD_xID8VOr@a9liX{SY7c&0 z*~i4Rn488+SGU88NS{ZB7^%mfVn;z6XXjsjxnuQuvY|gFAm1}0RnFx&^fAni>Iz1} zHh`;s$iHjVITY=F3c|mIFh(ERwaGKzi%$6Cx3?@oJR%^OfY3R{?i+X0bUwM?_iH0Q ze*^<1Rx|S5GaOybZ02Z&ws}_keG3)XSRla4lh1&g?r*IVjP8>YG87S=QxDVzUzJ~! zSRHenx*kv>LMJ0A-CIR|j~zn1;+tun$&FHH%tvj|(Q5Mr-hgO37DTlBf_9~DJ0IX? z&3VPHl-&D1)&4BN>&tIuhHP` znuv`}E~Eml4a;(GW&~T7-PV)6(6F!ph8{aUZ{9IwagU&qRt*!bpmO6E*@jn>5z^$o_z^t#>`I9M7%J|@h99pt&%JSdgo`J z?0XQYr}{2pXc(CrXcbhBhv=MGz`&1R&sIEpDPRE%Ov)WpQ~n9vWTaOf0&Ls7nBbJ~*t9_aLMb!M@l9Y?;W zw29Y=&%3;=89hc1lNGnhGVfdPE{8SCI5vg z4TK*3(lb(@_?VkoI*t@E_|h{5!7Gr;9fjwn@|G|4B(`1iKaH)6m9%Kpm=TMTig@t> zS<)WcvHQQ=%_~YPO)hUlyxei;jEkhQ5z|WN#5qaY*WPfcASd zOdGBQ$`_FKmgpt(CXJO6V_Jbkr!TeM<_G$G%4b$`&{;%Eoxl{!QRfEF^B?D^0VT&K z#-~yV*mN>IECy=!-5L>piiVaYC2XaooSmJ^(G{tvs4%gyTa4RH2`MO)hLV^oz>a{6 z|E&rD{~gShrRRb4ScoSkCQvajpp9O2DWpV>#2ZBx5x!MFOwbcaF=*P{*4;XbaJCRX3ZB!yk~m+?B;mIc9Uz8s z^4HitL(!S}$ka|8tnAbI!^N=sr+B`83bhMAia6u>@D1$Eogt1~AW?xz)!$l>C9*U} z8}ckDfpYCgsr41w84T<9_g34Mw!L@!W#>Dpn#;T?y_82(j&h7%*eG2$`ZSqb?8?eH zUlGlBw<)w;a0*;y3n_#vXGq6K4-cIewV9u%Puz;3Y;4w`JrSsw&9X%Kn=wD4MEbO` zWTDSHmWzjaN#wGR&5hGL*w|&m;iOaxd=5x%U!UhKX-p)Ovkto>QmzS)4-<2LXY-2O z{VZO*pl@3SA<`OjCAOs+%XIcE-=COmrm2q>eaBv?9aW3}-cRCIh;wE-S(y5Z=-M2y z=em$!8`tPSm}$;ud9!IQG}rPTEsUthF0@eL0fD-L9$1i#Q&7DRdqZY-#eJ?L_~ z#)?>_QOsNg+suRFb}IdA%xcLhmr*+On}e{mrpSoWSf57WzEpM(ic@8SA^*3?e0ZZ~ zGKZ@|s?MAx+2wx8Z+bR!%0TQ!blIhMlsKL1XJL3C<8^QBI-A`Zp1|@P&&A-`_~2DT=(a61PId_z*P>I&c*f9i@tm%&L-t_Z z{KCSx7-J5zd2f<^`uO5UYkkC@d-dc2podM``_@nNNwN@D<4?s{d97dfI4dch9=&LM zuY6aV-DNs!LtMVWjh^0gN zFK>9hTwUQ|p59Vik;fF-;sxn>soNWA3!T$fR4@z$hu^>)Bjqf&W($cUvk`u6+|SsM zDme7qVFR-22p@jh?7yG-vj$qg_qHO-9KX!=k-u&D$9jo4lF#({_K}uh5TvF5Evn)7 zI;$sL--)cKU|rqMhVGd@ACNf5xl>@FUo!!7skGI z#s@V`Zx>83?s0*sK}gHNTA)VC^luQcD=esLxxB{rBF7>l^|rHY$)9_i2w@-kCsZuN zt>3PqG?Le8v690^sZ|qPFGUTbvg}=p`l>~ zT*xZdIOHFzi8`jz6C0;Oo@yol8duoVcRcDbD}R8!YdZAIl304t+Shl$Mv~s3{8N1w z8s<=T!H62<%U0RzBmOtC-BrS+sR(REEK)6(>yVIT4%>T42Vyay1|wWclRc#(0tJF} zqxG|1HnnHk|C%8P zIvX7u;3q9=YxE9qFHwF$DRN1-rE#+3tcxw}lR3EFY<0eOX`<`dS3@i*9{v*IfG>X| zW$$?E^C9z7mYH*-Xzc!&$XKapG(O0gRMdwprV3(4!E^osx1c|in@QI#q~D~O|K$#{ zw0G8Ss_oE1NR^Zoud zO(8DnK#PS-LwJALankckt3;lllU}xU1>G04W7JOD3Lj`ksqx=r4)4zs=5DHnDmuT) z-frT{3{@QMAo1X_e(y}aoCc%)xi9#;!*u1smopS$i&{|{_Wg9bp3v!gqsvHaHieVZ zlw&>q^&X*!mG94JkLeue)ceZ}_q5q5ALAc$#`8!z=ROK|^{giY+qih-t|&%^sJ~5Ce53zc zOF5Q3;P>U%Nw!ztP{AB~i=~#_%0wV0)Puv!qCf#JyK3(3UXWvp0Yd3qFvKh=};e#`d!L@nCKWNMcP@n+{o(FV9>a%!C8gH|*TY(e*d8 zo9fnsUv+Zzc>><~+WEjiq=&R3&MODkV{+?wQE%w`N{m9wsjCsKZ^umG>S`I!-ig*@IBe{`=^$8QwlN>{n`fb2sM|{E4^1!g7~J zMvgqN+uHAw2v*zum&%WKvJ4H`y~WlZ1>{$&yA5Bv=-n9Y{&C@s>T#W?xcHrC1B}}1 zQSkZoPvCdo|0XfGlUpT;gPP7<)RQwt1X-gf<{EhBh96Gw_+Q>^jFbn3^g|W_(|E>e z#$=Yow;iBJC=sze%Kdrg{bsUim(^~$SVhbjuyGt9cuiI~ z6sWNZCuvI-y`CYb40ju^6FS$GkSL|OvPQM{UPH_IG={tuuk+{2@JNRRDSMFuoj%&l z0;jvKQik-63G3URRQc+Krr2Fc8*AoRgGg;a7d`U@!3D=*p(C;Vv?X;p z!!YjD?tH7t&G)+EC+O}fhPZy7WEpC5UZPLwH*JDZtsOQzrp)U=Av(BaWg>%)-JJQs zAF&L8sPG0c*i0ARCvBg^BF&{@eyp+I7ikkszW(Lb+`yYSgg#Yd3JPOc8_6fg(iQeU z$u6EMc=!r9efE#O4TO7I?85G#lJL#wMr!7Oo!!*}VhWolRf^0ez`qux=xv z^D31VYoeW$R0L$-`Bh?!+$*Hwj40XfeH%{jh1zFh4bM0BTDFcFCq`Bo*%jG@KT;Pu z(rk3P=D&1c@#nl|i1DQBGLig&9e)EYGFzV{#CfAQujJI)R!mH2uu9^~Z)%Imv zkDQF2@vM0{H*zLm$lv3CcXATiBwMoyTZg997B#q|1+rBo27s+p{}`}_$boE9Fdc>; zc1RdUeqLIs{1UipJ-g1Y+=$LoSWNF;8>=|a_3AMe(&mo&i>#j_D+>po5^~me+YcwY zWODj=ykmG11|qQdRJ$QxBha&_(woh3*TSZ%c6WGYS!gTLl|_g|>b9nlS^p(i>qzHU zu-wDuDcTp>F}9s#8IHCmYCDzp_sd!dg_14j4h7ZFam%(_=CD?JjfG$!B+y8Do?h?? zk}xzvj;8db&>DHPS5lQ)`5C@afGAI23@aq_J`wgsz(v$N;O8H8ni!MATzx&k zUNyt}GNCSgzmpy1i_u(iGMTzBb+-JgjgVJ(-F>hfWx>>!7-(W*?uQ6fAun6r>}(!n z(wT##tvU{RuZKee_)SE33o@d%R3oG6M$rAdZ;I?(S9MLng@=w}JrX36=0rhYA5TI# zG{+d_^sXbI!B=FFhpD3kM-2prl5Dbd{EABqSKUbN!hYZmBn+l3OHba~p`jOQ+a!Y` zd49szZ>9BXO~<{sJ^%iS+=r_|BW~`r?tF4njf}fy4H&K`SC5y_0&5;zL0AG~eqaxcBJRSw>JFJPKzri3zT=pCHR}=I~QP~20wL8JLJrKIqL3bnFoG6~= z%pZy2Fz45rtyF263hx5XR=)hoR(vneGf@1;LS)T82xfFwd~kJBJ<#{z7H-cmkdiVg zk@V;gRP+9>_(X;@8&dNPfA}~!#fLA}A~`rAAI9{wLw9(AK2d0Ka$P{9n8vl@F?Cf$ zbWaV41K9A)6yfGWO(aJJB^~~Hjk#l+ z{qd|$M!VEcqUl@O?Q=>$;?fDHemlkr5i;q=S+>fVm8Xxqo7sQ3NWp?(2EW@+c*C(l&) z5%kq#R4|l=64Z)RM49;WNS#qDbs@Q>q1`N??9Q5`@ImTn=_Nk6jBdQfaLB+xj}3*Pk_I*4U5iOpK_Qn5XUR0mJeJ#MMPE_| z%Fj?U_F>&ef--AY=X@0^(yR(>io-**8y#FVIt`&lDf?w-@;|K8QrtO)(}%0GaoKnU zY=lP%X`!ma*r(#WbOz1XW3Qv3qKvN9^s@ndm0v#crD*8fnQB9KTrTowRvOR1>5*3T zocD&Vr{o&B;r+)4_fNL;;}!3ExX#B8d+tzq=_&X?mqPyjt9&Re^a*o8QyYQ%4k+t% zuN*9(VV9`?Ed=-G;yXCJE%6M`S)iQk>I^XIaTevet}dnZEuc+D4?^Ut@V!>ui`g&Bh~ zHI+qhA8yy_l7b18=*W)(Dj)&Jvgk7m4>kO~0kII3`W{`LpT-SpbQJ-=TX0`MZ}J=m zIV?&efS&GeGVc zWZC@txYgACk2=NA$0I`A7r$>F3oOWpJ0iqS6l^Y!Xo)e#n&{NZ+3GId`1$*GAW<}P zhWyr@8R{w&rQ%aziipJl_=D!KL=8j_<`}wuxxQCFzlTcKa9K{~?@KB1{?y*nVzWjs zRQ4Hc%#(?bDbS2ICHiQq zug)CwHD8bTM<|CmWkO4+A41BBJ56lDREL*7-s_Ud&r%pFML^>&I4iaevYQv$?pURI zgC|S$wVLjh>}jd1OxM2XFTd(yhy5@$UF{{`z_=~_OoFncQ54hl@&1y(ZNVe0`et_| zH-d2nbGfPrbcjJ54XBX0=EQs?+o-IF&6*wjBl~nM7OD@94~+RSU-HQwEaW|Z1D9R%J!%& ze-hfU%|ELoU1n697SE*4!{(21H-!@y&JXe99vRn7hdvA=M_z@6^h=t#Hf$p}0Rsn^ z*@QnY;KDRU3FWTmr`Nx8`2xZm3+OP;1}Xg*ubD`AHw!=?J~$3>D7L_{KHrys%aac& z_IyQ_&O9o_BqX+z8mt$p548c|LV%B7g@o1w0K?Ge{#()J-=B#8=aK&zvHw{x|Fd8I zJISg455z^K!Rc!zo%*AH6J-XcP3Ru~2y*jtAQ={?q<8X9PVC>C#SBZg{SPd_e<9@N z_{a5*ydeA?pFg9bq2a4HvUM1l7O&P)iT4hhN=HEN%SDKF1$)Ptj%<66U7@z0VPxrT zWMeIQ#ZL-=eEl%D9#lKts?*ZfYqK<8@4^Tv)9W{9t^au1G-olDOF896yB5Nro2XH2 z8}ax9TTgD=G1)zL0Y2lttN&_mPB#mP2XHr@;3Xlmc|D^idL^chBu1xS$bh3=2Q4>W z;%ruO4WT$XHv=N~3>gmJEW1AAamay5L zqNT`Jx?>ZQ|5^Zwo=d5L!q(}Qe>{RcW5 z5~_RzU1#RpRy#0Q$9sj>7^HXU6W1&lkg|sWbw5}-sOTZSl=%s}hKGE;f3%=w2~KkA z>Ybt0Hzme(()UHEiY_JDXTAebHgvlde^uE-ZOn_Lkeei|-0ZVvba;V`)#X-w)puk0 z<_S%?r7B_%tHUyDy_psRR?y5{q4Y-nW>f1FopYa9N|ZnRS%BHaQ2ol$B3Hm_FSdsW zR}?e7Umh;iT)COVaZ4@Sf|XV&W4-^v{LfLMq)~D6ZN9Xilubov4X3Xu^qSl2&dUZj z;#dZH!xJClFdIp5cl%wsuyk#3RFCwobO&?w^g*Cx6WN-uC6BySV5Y$S+aVAk@+}~p z+{s!w2uH<;ZGn-=y7Te6k*y_y0%w$0#eXBKWJsa(!93hi5D&-tO+p&6zov?0hBdM_ z17Yi#w0JWolnQlNJ>Ytd{YXkW;S2NLs~7U3I^gj4YO@z9Q>2tAx_)mS7zO3VOz(7X z29nz>l9HkPIp_byjaT^sf~F<=iDrZ?}7aP5wQ{6{tdqNB%pBu5m` zQYDz(qt9dYZa0gFEfVx~%P_LH!YkEJPH$-pgj-@d3MNGwULW^|kF7}p+_5oD;@LSX zmpM$2REeJHo@z%3bI>W`X)Oz|Dy+Z*8rI-Y0ViC@&%pkGaPsu0_35~cX?mR?4%5k^ z>NhE(2^>8SuR!+1X^eU(ej_3yH=a7&|K8H$9N5@1}Da)i?TjlO4LY)yWH084(&Rv&AHpyzLczDbmUa!@@^ zXZz=?`#Kp-{%9A6)I7%hBds_NpYOM-rQb-=TSQW+hYYB#&xzqA`yE8He&{`j?}$#S z@1q;)s%lRx?PreLdkVcmkf=NPvG2H(zi{Anm)087LJ|EM$R0>v~z zeJVTSj8$>~iIndL?AFSL53!mj#D8V(N)i3xU|h~xG}gf#!+m2P+M=xfnR&I_(!yo`_M7jbmU=cZW<^?o_g zZ9N&04hJ%TY$U>7A+t&9B7u=_OEz^k&kaC&!gx47NneX_Bf6gZqhI{HTVmy(3U z5mzC)s~A zef#3b(G!N}2!83BQ;pSoK-Y5q$oXHuDF21NUvFBiC!(P65e^6TIJj)OOy{O4(R<}o z+zvqAUFin`?J)y?n$FdExq$zd7uv&6R_Zc&tsYd?J1ix(4_fUSUf~7Pa#8s_wP@vz{X&Y5`8-ho4{3MO? zxb`57e|OUaep(z+8&2g5?i7dYLddC7cr2MidF#X)M7khkk*8J?sb0M!<%5ws{6jfi z(Bg$A^4Bl6b3UmcwedD9HB|Z@-$-m592KHBd7ct`UC4W*-?YZ_M2r3$D-9hMjQ55# zgHAjtShU05Gsbf~y$3OO4ZSXSII77{jOou>U>&cQdX8uV(W#eXw)PBTJPD_Y(x!DZ3ui#m|cto_DwIU|wEP z|8^GlXlsZgcq2d|B<;IhrhlVSpy}h)@<^xIgp3Di4(rG6p|O69=u1l~s`T{%Sn9<~ z5T`YlGTMh@PDdsuqibRGZw`_j&oEYxCSo|y9?wQ~5`L6reIGoX(6v-<@}c}(m;0Ck zIh9`Z*;5)M#-sUTfp$W{78_|U4E|$vFXCmzZXi7KbC6n$?iHcbarx=l6uoi~cUm`s zJuv6yTds`0!Nu$1;nrwnV;Gn$s;aR8W|movtwTN*=ks|U8%6qRZhrHbJptHE2t`}H z&_cxE0yVM7vcgTv^`p2I|Gz*vu+3f>9woANz1N+4*I%8JN(Kkc2fD$r#0(l6J&NZ{ z?jJ>ijMnuI73-VdoBAlfm~B)UlfPbQL~)lfa#%Bb>suM!PhWP%j*Y$Mnd;2p4M~AM z&%PkE`4JSiHW%HldbKZb;d%X?@37ULi8y|c=;&x4o&ARUangY;|;9o#-}q+xjd)S zX{}~wUH_Z%(N8CB^Am5got~z*po>?tXY_5F4ao$w*H!m<_1#KGa;IasTgdjO-^HFZ z_-9Y7T%|M3ZYD7=vE@I`#$S1?1Q)?nY7nK*-wZ}X28Yf=eoo*ZjGa##w6Yc5f>RsQ z@S{iG8QzMyQiOkWJQYG;q?tPLZ@^R@HPS=2uiA=tTbMrb{Y5DP5J8}$ee$CY2J>7tez%BXtf2tS7Z!_mL zcG)`K2lrX7f&_%PQVsC3zpte|O)!q>dhi?%Xh?Hpss9V6gU<9K_a@j01kv+n(nzea z8Eto_G<B}!&0cjm)avKqR>T#8f9HoilpQc;aGz z)bTOPx=1NZtsW#(ZE0LExt8TDpGOFJ&i<`C9m0m3O}6kS2J)btkc`kG|h zhABPfeoNMP!4Zc%8T`eJNcst->LOF_^&0jh9a$u~1Pb;i#$CH=rJhyjXq;r>e#Ydt zK=M=?ugBE0v<5iuA!tVWa1!htI;^KC#dh4pP3`lThAoWbQ%k}X^Fw4IIkm>74Pos2 zm|AAKG?5eLRyY><%x$VJk&^V=lRvC8I7;A>bdu!h=!JrCH=dnvr`}h2)lyA%z~9ap zs1dd2VNctW;GU2yUEf9Z7^I<5T>NxY7(309vLP*!k2R&7W!BNh$se~8UBsMV8=&K0 ze~(=cUOvh=NAs;CQ@9zw9AW=2Fyf6bn_T6-(G8hG&ZE+>J^ms?e7F+zMlF&QbY$$a z5zC-Nw*EAKBR?aO_0_TNU;&PWD>}~3=$H5oKgE5SwnbMM40%T`4Pk|=gsPr(v1w~Ip9-QjM9Od3s>iYn7$>#twcl{`=BL03jB^xZ_-rZ z1LQDI`eDh^O&ZiD+2Od*;mb?&(d%O%Vog0&3nV$Y01RsUQ~wFky8yr0fc+#mclOgI zXZD!F?}v4a=Q2-q*9;ReK^+j-N{0N&vCBW;cK#l+)hH&PZJaO{&!phIqO%EJ0}dNS zX7tOy{WC$5nWPYN#KiE9pc|{%e(YPWzgrl^zLh7@o6e*NHtrV%b-!CLh^WWsTo&*e zG(JgcUs7}w$#>qh>7d59&G(yncIzkZMm}mj9*ZgIseY1kyuOi0#}s9^nkXJVj5O%` z`IUa!Mjb_(@Z{jLKotkB_FLk9D_@>UmIL&pCH&=p++O6zf&B^W=lWiW8p z@!x3Q@J>_NeN^uwbWEX9bvV@i*AL-ty$hMW}`MPXxAt(%7tJNNR#342Qf?_Fp+(x#pLtpsG=x zjL|Z>+QX;WT}v}$Ai=#3ZKtG{j8-V84AXzzQ^47yCUzMZ8SL=7Tjngd1s1VKkZ^F} z-e*}N$1Tu%FV1G9H$$^+RQRpv6zi$)l!iovdYnb{9X zYf+K}ZXUFvEi182BT`i&`v=szv3Vk65&PW}bBhz6@K*>Sue2!)pN;UMMNVrIr&Z4# zTezdzYMpHjb4ZLKsZR2+>C%7|RG5*tq z%GZTbBZl?E8U0~Yp($oBzATxY!(j&Y>UgpEz#LNSjf#qzOwO8NAA1%M*&%BSBc3B* zB4)GaNB1l$@; zFL^w?dc{+vk4Y-}b6LO7rBGz+0jJmFXJ#G<;@wyIguHVTPJ7V{a>m{|nM2{Tzr8hU z3VB!O4VGW3k?zEQOxfvw$?`5oBbJi0p%y&5%#&Q;Yr?7%N1;=Nv47Ke!cz-M7<2Rm zC4wRrtcoTtri(6rXePyQjF8m-LF$6Mkv@F3VExBVd^P2Yp(jbCuQgFlbq4{}dUNqi zl;w>q`C7&dchON|mf`By)6S^y>3Eytmlug`$r?Ogp#f-lmT4v3tqGqeuH&@?8(5>j z|5RBy$jzSim_rviOpdWBUJUKbJ!m&9JkQ@c%qxb#sNW{CNQZy13OPr*(>`0xaNt_L zpQvXx8QU7(Bfs@dq`@Xa3GwPEMJ;$PzJEuh-Qh#Bj+KFtm*Vj5{qeZR+Dqf z6BU_3tB!2g{JCL4s`L-?A6YiUry6$IPNGJHR^I)3hD>b%KSDofxkasW`Wh9oJQ%UJ zx4aVa_W#aluC=@cT;zvVkr|<}^MHwM#_jKqf0TskJzu8#k}1ey3EK}{Jv={gfA{ky zT5-#Nxv(ZAL^s}aC~4=`dygeKd~eUi4`JYGr|CU8Pn)5^h3X+;vOJ3sR-_13b`|CH@t{iH$0I9xwwdCgie#XyU(cd<0 zS5yxVC|HtpW9Cmk{N&cW0@e=&Ua_rY3*(sskOg4fkJQvgX*5Abh9pw9;Xs?QOeuw- zmTADhHypu^b=Ku5t@az85|Wa!DJdZUwWBRD5I>5wZd|clw&e}PA|9P_1dsu>=-ohc z%GRlA@IRGA{qI*77~7dxu#c<2-tZm3=Z=a_ly9iQW_r??tZ(PlSN<#A9wWm_@RW;X z#IJ{5Bh5e4B<+>1_d6_Q5X(~yl#M{=H8jW0c>K{5$gVdx6%sYMh2Jc+IMD(;cZPl0 zhqpco8W$BFS@o@jRZm3T9HkGpWLY3%0Su>`b#mb2mpZx8nl?y*bJ=7T)mwz>bZ|Gj z>SMiX7^yydxWIep>m9d|{GrNuOV}6Hj2!<5 zC!S=r0Q0LHx>}=!!(Xn$0Ui0Mm^2ZH)sPNXDcdhQpR7-iW~(m+###*1mVL0Ao4AB3 zL#V^IwzX)_zlrbo8b8jQ?hiG~<2e=JUNg>C*fXv^*5U!>%9|rDRSV7)2CXOgi0-pN zpg`IU+0NNg;wo&1&P|#z3-N>4p=gdBQAITUS2wo$^}(c3_cPoAGbYhcZEsVwpR<%O#^p(vt@Ws9v8%qcwqS@tT#1-!n~PvGpI4N+f1cRvLEUUR&$+6h+^% z`Px&8EZ@0hH@t!Tdh*%m*{b2Ku{x!gjV$Z18@n+&I^D;#$TGcy>A7E3^tQCR3ra`Z zn5+&Z-W{h#2|?hxEPX9FaMG6HZRm@O<8i1~!i>Aey%&G6VAhtGun+ajs?I=tYqOSU zy+FGDo&>D^)V{t?!+NnbS+7LDsQbbQJF6wSw&mLXXz8=irI8T1=zXYgA1-W3BU;Vk zi?0CWQD>Ln4KRPYw;0b>WG?}b^~n=@x)pZ5n+*n%PhAsRr3uPlFzOe&#%CiK5nDZl z!M6@~?-8~U-}2}Fyq{(~LLwtqS0k-PJxgdl z<);xb2$Rfad3Pa~>Ln?nPQej6!99DS%d@r5U(%czBrY{ktV@AShPw73gmMz`zU?}` zWjdE+)ld1HM`)?xg`h_1Rs?3g?d}v_)a3CNyK@D(m`E^Q;NM#F>EOpIU;fb7=in6z zpc`CZpQX2-4ytMYyu2qwDinNO)Jk&I+}52j_n@+hYxoKV#a<gJn#uibE z%|ZUM$qq&IbZPY3^DjH6K_;%_QQd-5H*T9pKxRk?UxlXs$-)I%Tk13gWmo&AR#1$i zQNooFWKHNE6Qv0_*U%Z)V8lj--!5K_-nZIb216fW|9iR8{`_#772e?QFC7WhZ2E!9 zYw)+AN3+iMSFLI1QP%QG0WT|ehGHPr^=t4k{7UaE=ri(ZFmF5880Gpz0=pGty*SJR z)h{F@A!D=5k(FF3@ef_@-){wS5(qYo{)MWj$SfPs{kc>Ej0Xv8wPT0QB#ZvcEBO!F zT96``-T^cFDa}`}DK&AB-CXIbABSQPY`5~I$PsS_tJ-MvO0vQdmRY2QSiB?T>~0e) z_ypNgpm<;VHSLEFJdXarqI&yV46NIK0Y)eg2_><2xXB&~6;Ptd^h%>Y693V_ zr2ne_ZAAW;b@pFg6j3s5l>%q7#w8|7dU!OIlmJJQflq*wP1jFPmDSY~35B>o9UTzf{8hW%?_m3HwJhL(RX>4#1DDa<6{0g+Gdjrs0XtsHQ-*kUa*%Gjj zJHKk~_^@{ghJ@kcC!oFi*?-_-xsZe9c4ey=&5~CPKIhg>1TU5`M9{Vw;RCu!|8K~k z#M*L7NNLlu=#|>0arQff)4za-v^u(P#9PVxfTxtD&`{ctTDxbVUoq!!iBTxD8n?GT zd3*cy_v)kg-Fm|osK+{8>PykG$?)9|q0F}uU)Y&`$wg9_4K}GqJqpF^Gh3+?d(q{5 zO@nPO>F_%kW$v=`v~l}+9)9f}TMBMxP~7A2z!wa=ykD4Hp8UhJix4KOMlts>-#D}7 zs-Td1!^$cb{0(|dYhEdGyiChKib4L^Xmg~xN;w{smdN;$=+)-{76MI&?apHK_=pj^ z309tYFl+u5Hhw`VXP_#@yVXJ`?t?o>$NOt}jL#k&m zq2U?D>g_j6`Q^^5Baz1J;~|>y?|mc!*G~!4Ell-QHoFqD4fn*P@wkp39p1Da*X+%j ziv&AH58TEGH2OF zP|P_y)H(9HqdlNbMF3wfRfn(VIavgPc7c1kRT|rCvGv`zW zS2^R71;6G+pkc2GTzXW|zW(OZaj=Dy%9P57HuM{$u&0^qSRi~xzm`I~nxZrpV8?dY zH{>$}cxX>18s4~%lhz+8WqWA(eobyyx*ntBdY@B$@mGcl4%Y6hAIJZS6wpM@vvx85 zz;dgv$`EnU(SiC6^PSy~B|35UMpmu;R6f5gD~)RECX^a0(2iik##$Q7vG?BjqnTq< zLl;(iTYxMxN{Sh>eT>s!ltG#2p5T*?R0E!nPG71-Qp>Bpd_3Rv8x!-&gctd$`546u ziLygH9i;7Y-xaQEo>GV2QhaXQlAer8UvJHHA&olgg1TV7O?(=hcTzY}818Nn-hNS0 z6%x`|a!5N~^X+`0p$Keay;bu$EYMNetM??;=B!BqpVZH&qrZV}1SuliC+Wci3Bax^ zOfgjw+YYoAoWSvN_qcsA1FUq|vGH0^y67ply*tLGa7p__+Vh5tQ(+6=PD(bSxoP8D zt!U0vf(>B29mel{)go)2MCM-RagndC4)v|TSyIn%&6Kg;7)eU`A zDG4=zKRq|EM1|cT1tp5A^oc!Ihk|nWksDt1%>DjL$6CDFXzf%D&q#XG=0h}*6Q2Q? zGr#cr!8ISSHK)G9ZccX(Q+7R9f&7H4}XAhLwtD*-kM^{Lm_R(F*mCVL^10xP@>B4jM zw+n)Q(qCj+B&i(CVnLJdIB#8*c?v;k31yV$(Z0i`6>50C=R2#hdBqJL?=pjY`o|t7 z`-SdF<$GQ7zm%|-f^qF8i1A|&`@Z5`P7P&I7phV-d@WZ{&m?kwbA?$vLR0Cn^}%E9 z$O+LtsYp_DWF_@gtEY0_LQKrq-Efj(v9&cMr>?@ju>A~roeVKqs0=H8yW;N=oA_sL z|Emwg<+hOFbO$r~`jjK-TiD@i1o6~LxEK_Y5vxr(Hm@F+zT0Gv1lMKaz@BBRD6*a>RP z3xFTG^_aA4LuSi#i1#%Catdwjw*Zxnq{!11doZAZK4?h%L$k4o{x41q+x7x~ikC0f z2d99r$ugU6W+)4eGjLV{kImxtAj3Zj)033fwtH=Dt-z)6Qq}=Dllvd-xigd;pOtko z`1hYXAU{@21G7s%I-)nI2nz z0bR_O!^eN<{CnxxwTKZg4Dg|R=?zMv^rL1q4gerWVXB)A8@tQ?nh@xaD$*1eyJCDi zt+Fw2LJb4(RB%ubkfaoIb>;b1GPAJx&ppro&4%IPnl5$(h9r&VU(U3>_RfDAi+_c3 z{$pVN{UW2yMiCg%<7IGsX(^Mcnp%a6n(gzBj*frp@z*^EJEo^d@?g$e&|GZEbTz5Y z)}G^Z`AeBKK`Vi;N)2V9A@)2#QTcD5$NRY^dfo)!$S4yMbf9Py?IasadDc#@eK|D5JA$?(s}_i2Ka@MQ&Urum!BRsuzQ`GUI$zLa54@* zU5@w_u&?yU!nMuv;Tb@PaL}XHqdrgAGu9lvKJLPtla0F;u=|KHOZmF`CSP9R1)@uBn>nT0)tPcFRyR#gXJ5%Q8 z@nj!iV3(18aC$(5O*qLKjO9QBlX{#rCM4Z954Nraw_jI4nAl*XtgwX4&&5~jIcH@E zQ^F)h?6o7bd)Pe(>L;{-h+3>}IaVK89Fd4@`0N-=T*X`;;f@1=H~CX@-m92DF$wU3 zlZzo);9X?IT$#n(j$`?i*QEh3sciQ3?)9v=rdBvMjs`odf!$1|7-ZxLGLPRBjvhhU-Q^@03>g7qpPl2g6=ty}Y zzuQj9x3bRxJU0#xG1o#Dnq)4%UXkBS$LgNoP&Q;vE0hXn&xnd2iYEJ3$C#X>zQ_!i zJs@_l2S8o}esLIx`<5#N83jEiHa7OA=JL`x2$y{DY@-W{-t*_{slw{k9uocISN>O< zkEr8kZL{jvZ0w2{16GAoH*HetIIz43yXRliop%F!LNi8%Ma-wLrla?IT6W_1R+)nS zCJqsNDPcwtnI8?s8atHPfi|Gq8$1r8KHTGf%cG7~x(yR98l^N5Z3?n%)h19AL3)aj zdF$epg$6Ozn-+(7DI*-qcU3%q9kbQf8=sI6vSQ1+oKn*Xv}S(LhXD(kA6b49CBr3hNT6t z6D^f=)JH0+0HD)SQDm}WV$T5hXruE&hK*MPLnh5l1MOw?#&eO?_tQSs33+m-+CgrPp=pu!*Q~A#JXDHU&1i$5 zK_UaRt8bnBUl4nf=kC{iE3fbqdXv76nSCFvyF3%`I;2bUIeIDwjoF*9KYAw2;%~x3 z2^O@EmCgHY9-7l{0uPw`FcTFcvupQcMITod)QhOAv*7Hu_q>5f?hgceft3_^AgyBB zcyvnlng~|by4{b$&v@FncZCtX>HhV-*w11IKKus)u25uYVCj36{Od(GvDj<|VCgxG zmfP7_{_kHv22q^sjkAV^jg~@hMQ{E-0S=U7esvW@KlJWX3gJ1nS`pGqLv=r&=uN)v zYI}nIF4DMmNGmmBVDlsOh@cl-iG?R@m(r1f5vO2jCGtqtQ=F^a^UDU@01 z%HrYn$;<2lR0Dcn;-?pZsQlW!|0`_R$j~s_5!vE2Jrn0)Nv16^sP?K7f~Tb|Y$_H7 z1|A<16(=MC%XJx=yXnfBe{BPcxDEbNBVQXairbv7xxRUACwfdyh9r53*!34vx$C!k zbO8l3pki8+$ZT^xxdhTq*C@o%bG0`YT9UTI9Sd!k^4VO8luVkR?TLc%x*N7u%!WP@-k`bS`6Y_NCX_}ce%)YG1+ z$|JJ}bCzfK>P?#(Uo9!1YNwQ}o@=*4aA!x2(t46^NXAh;3eNe{1D-wEJQku1or;z8 zrea@`YI$*PsF&K=9q+}Z)a_{SX8fA{b&Ew8%rcLLXnvc|{FWf_a z(Xv_zrCq|eR@Qgwk~{~i)V2E)+^55xGHM8om!f{K5ZsqtEZC0A&#iOYc|z;NvsAC@ znWe^vVea>011TK*TR~~U?6V-1!Ee9nPSl=nrjD;7adU<0H$w+P1+zG;HZf`G4j?~_ zJKL>ZfpXvGt%9pKj4Bjq67B4=nGPNy8^R&~S$FJCuQY};Db65GB8)jrO*hv|>dcCdC2*P$uxl(~ zEGQB$ZQht@0^_waRQJ|Jq*H~qR&)M<5ge2sf~Ke0DQHfPPWiM%>=`+|jKuEWt&@_a zB^BD99%Ou8=*_PwF@fmeiPdIvw7z);JK5p&8p%OkN+*J9c$ucZApC60Tb?DKK%EO! z(cqSdYHOnd$IN^rS8LC>BLcikzHF-zJm+B>{c^2I+6r77HC$W_ zoMKQVw1MAes--j+elHMO%~)uf5Q?Bp3*en^tG{Q3SF$X5{1(y%Rthqu*P}BFO530y ztc$>PgP(>5{kODSzUF6Z{>_y^jHAiz?Si{rLk2^gl(uq>e%_az%iXc69f_w-o^a)# z;sm|R3S5$^SR6r?j)iE%I+9af2tE3USvdAU4&BLbbFaxAJP(6muYM{Lc5A|~^30Hh zBoFTWnmPSf$~||PZrF0QxCPC4^j)Xnn}Cno#5fGV*xrT^qTJcG3UB(E7PqoPHLaVw z`>By}t$ob~g*}l#Vu$lU-y4jxyuM)ecdGPOvn64N|7L!xRJ-U$^Ldtm$6oCDSVzPm z=lVI73>S@<|M7v0>Xd)vdNks;6m;7J=ohKuaOBdQ#v#=fKJ4&lQS#*R<5#$43k%Hp zgKfm*`{91zUM>@DW6Oxvu{E7~C!U|64sNM&{zXmm@A9csUE72BJTrJe^h?yOsuHKd zQK6(vz5NFj!&-+N-;#F`Kc`zxcZ#_K2T059vCjo^2(=!5C6p+3Cj`(dRqTL?_V2~ fe}nRW8JP%Gx_ud%)zQH|0$k=McZ@&WatZ%GoY)P? literal 0 HcmV?d00001 diff --git a/source/Tutorials/Intermediate/RViz/RViz-Main.rst b/source/Tutorials/Intermediate/RViz/RViz-Main.rst index 59559f5a4e7..4d2e687eab4 100644 --- a/source/Tutorials/Intermediate/RViz/RViz-Main.rst +++ b/source/Tutorials/Intermediate/RViz/RViz-Main.rst @@ -12,4 +12,5 @@ RViz is a 3D visualizer for the Robot Operating System (ROS) framework. RViz-User-Guide/RViz-User-Guide RViz-Custom-Display/RViz-Custom-Display + RViz-Custom-Panel/RViz-Custom-Panel Marker-Display-types/Marker-Display-types From f39b5dfc54524eff2e48c53d435b0082d331fb8f Mon Sep 17 00:00:00 2001 From: Mattia Massarenti <121773111+M61ss@users.noreply.github.com> Date: Mon, 13 Jan 2025 20:04:34 +0100 Subject: [PATCH 03/29] Update Colcon-Tutorial.rst (#4867) Signed-off-by: Mattia Massarenti <121773111+M61ss@users.noreply.github.com> --- source/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.rst b/source/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.rst index 92d9b8fa98c..1e94a073900 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.rst @@ -340,7 +340,7 @@ The ``colcon-argcomplete`` package must be installed, and `some setup may be req Tips ---- -* If you do not want to build a specific package place an empty file named ``COLCON_IGNORE`` in the directory and it will not be indexed. +* If you do not want to build a specific package, then place an empty file named ``COLCON_IGNORE`` in the directory and it will not be indexed. * If you want to avoid configuring and building tests in CMake packages you can pass: ``--cmake-args -DBUILD_TESTING=0``. From cfa3b895f6ae2b7d2fda09c73cf27c67dc6cd32e Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Mon, 13 Jan 2025 20:16:44 -0800 Subject: [PATCH 04/29] =?UTF-8?q?move=20RTI=20Connext=20DDS=20installation?= =?UTF-8?q?=20doc=20under=20Install-Connext-Universit=E2=80=A6=20(#4774)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * move RTI Connext DDS installation doc under Install-Connext-University-Eval. Signed-off-by: Tomoya Fujita * remove unnecessary hyperlinks to avoid self-reference. Signed-off-by: Tomoya Fujita --------- Signed-off-by: Tomoya Fujita --- source/Installation/DDS-Implementations.rst | 176 +----------------- .../Install-Connext-University-Eval.rst | 166 ++++++++++++++++- 2 files changed, 165 insertions(+), 177 deletions(-) diff --git a/source/Installation/DDS-Implementations.rst b/source/Installation/DDS-Implementations.rst index 7e26a11ecf6..d412ab7c161 100644 --- a/source/Installation/DDS-Implementations.rst +++ b/source/Installation/DDS-Implementations.rst @@ -10,6 +10,7 @@ The default DDS vendor is eProsima's Fast DDS. * :doc:`Working with Eclipse Cyclone DDS ` explains how to utilize Cyclone DDS. * :doc:`Working with eProsima Fast DDS ` explains how to utilize Fast DDS. +* :doc:`Working with RTI Connext DDS ` explains how to utilize and evaluate RTI Connext DDS. * :doc:`Working with GurumNetworks GurumDDS ` explains how to utilize GurumDDS. .. toctree:: @@ -22,178 +23,3 @@ If you would like to use one of the other vendors you will need to install their The ROS 2 build will automatically build support for vendors that have been installed and sourced correctly. Once you've installed a new DDS vendor, you can change the vendor used at runtime: :doc:`Working with Multiple RMW Implementations <../How-To-Guides/Working-with-multiple-RMW-implementations>`. - -Detailed instructions for installing other DDS vendors are provided below. - -.. contents:: Platforms / Installation types - :depth: 1 - :local: - -Ubuntu Linux source install ---------------------------- - -RTI Connext (version 6.0.1, amd64 only) -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -Deb packages provided in the ROS 2 apt repositories -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -You can install a deb package of RTI Connext available on the ROS 2 apt repositories. -You will need to accept a license from RTI. - -.. code-block:: bash - - sudo apt update && sudo apt install -q -y rti-connext-dds-6.0.1 - -Source the setup file to set the ``NDDSHOME`` environment variable. - -.. code-block:: bash - - cd /opt/rti.com/rti_connext_dds-6.0.1/resource/scripts && source ./rtisetenv_x64Linux4gcc7.3.0.bash; cd - - -Note: when using ``zsh`` you need to be in the directory of the script when sourcing it to have it work properly - -Now you can build as normal and support for RTI will be built as well. - -Official binary packages from RTI -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -You can install the Connext 6.0.1 package for Linux provided by RTI, via options available for :doc:`university, purchase or evaluation ` - -After downloading, use ``chmod +x`` on the ``.run`` executable and then execute it. -Note that if you're installing to a system directory use ``sudo`` as well. - -The default location is ``~/rti_connext_dds-6.0.1`` - -After installation, run RTI launcher and point it to your license file (obtained from RTI). - -Add the following line to your ``.bashrc`` file pointing to your copy of the license. - -.. code-block:: bash - - export RTI_LICENSE_FILE=path/to/rti_license.dat - -Source the setup file to set the ``NDDSHOME`` environment variable. - -.. code-block:: bash - - cd ~/rti_connext_dds-6.0.1/resource/scripts && source ./rtisetenv_x64Linux4gcc7.3.0.bash; cd - - -Now you can build as normal and support for RTI will be built as well. - -Ubuntu Linux binary install ---------------------------- - -RTI Connext (version 6.0.1, amd64 only) -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -To use RTI Connext DDS there are full-suite install options available for :doc:`university, purchase or evaluation ` -or you can install a libraries-only deb package of RTI Connext 6.0.1, available from the OSRF Apt repository -under a `non-commercial license `__. - -To install the libs-only deb package: - -.. code-block:: bash - - sudo apt update && sudo apt install -q -y rti-connext-dds-6.0.1 - -You will need to accept a license agreement from RTI, and will find an 'rti_license.dat file in the installation. - -Add the following line to your ``.bashrc`` file pointing to your copy of the license (and source it). - -.. code-block:: bash - - export RTI_LICENSE_FILE=path/to/rti_license.dat - -All options need you to source the setup file to set the ``NDDSHOME`` environment variable: - -.. code-block:: bash - - cd /opt/rti.com/rti_connext_dds-6.0.1/resource/scripts && source ./rtisetenv_x64Linux4gcc7.3.0.bash; cd - - -Note: the above may need modification to match your RTI installation location - -If you want to install the Connext DDS-Security plugins please refer to :doc:`this page `. - -OSX source install ------------------- - -RTI Connext (6.0.1) -^^^^^^^^^^^^^^^^^^^ - -If you would like to also build against RTI Connext DDS there are options available for :doc:`university, purchase or evaluation ` - -You also need a Java runtime installed to run the RTI code generator, which you can get `here `__. - -After installing, run RTI launcher and point it to your license file. - -Source the setup file to set the ``NDDSHOME`` environment variable before building your workspace. - -.. code-block:: bash - - source /Applications/rti_connext_dds-6.0.1/resource/scripts/rtisetenv_x64Darwin17clang9.0.bash - -You may need to increase shared memory resources following https://community.rti.com/kb/osx510 - -If you want to install the Connext DDS-Security plugins please refer to :doc:`this page `. - -OSX binary install ------------------- - - -Enable Connext support -^^^^^^^^^^^^^^^^^^^^^^ - -To use RTI Connext DDS there are options available for :doc:`university, purchase or evaluation ` - -After installing, run RTI launcher and point it to your license file. - -Source the setup file to set the ``NDDSHOME`` environment variable before building your workspace. - -.. code-block:: bash - - source /Applications/rti_connext_dds-6.0.1/resource/scripts/rtisetenv_x64Darwin17clang9.0.bash - -You may need to increase shared memory resources following https://community.rti.com/kb/osx510. - -If you want to install the Connext DDS-Security plugins please refer to :doc:`this page `. - -Windows source install ----------------------- - -RTI Connext 6.0.1 -^^^^^^^^^^^^^^^^^ - -If you would like to also build against RTI Connext DDS there are options available for :doc:`university, purchase or evaluation ` - -After installing, use the RTI Launcher to load your license file. - -Then before building ROS 2, set up the Connext environment: - -.. code-block:: bash - - call "C:\Program Files\rti_connext_dds-6.0.1\resource\scripts\rtisetenv_x64Win64VS2017.bat" - -Note that this path might need to be slightly altered depending on where you selected to install RTI Connext DDS, and which version of Visual Studio was selected. -The path above is the current default path as of version 6.0.1, but will change as the version numbers increment in the future. - -If you want to install the Connext DDS-Security plugins please refer to :doc:`this page `. - -Windows binary install ----------------------- - - -RTI Connext -^^^^^^^^^^^ - -To use RTI Connext DDS there are options available for :doc:`university, purchase or evaluation ` - -After installing, run RTI launcher and point it to your license file. - -Then before using ROS 2, set up the Connext environment: - -.. code-block:: bash - - call "C:\Program Files\rti_connext_dds-6.0.1\resource\scripts\rtisetenv_x64Win64VS2017.bat" - -If you want to install the Connext DDS-Security plugins please refer to :doc:`this page `. diff --git a/source/Installation/DDS-Implementations/Install-Connext-University-Eval.rst b/source/Installation/DDS-Implementations/Install-Connext-University-Eval.rst index 0f312b092c6..4ffe5012c0c 100644 --- a/source/Installation/DDS-Implementations/Install-Connext-University-Eval.rst +++ b/source/Installation/DDS-Implementations/Install-Connext-University-Eval.rst @@ -1,8 +1,9 @@ RTI Connext DDS =============== -A libraries-only version of RTI Connext DDS 6.0.1 may be installed per the :doc:`installation instructions <../../Installation>` for -Debian/Ubuntu Linux (amd64) platforms only, under a `non-commercial license `__. +.. contents:: Table of Contents + :depth: 1 + :local: A full-suite installation of RTI Connext DDS is available for many additional platforms, for universities, evaluation, or purchase. This installation includes diagnostic tools, layered services, and security. See below for installation details. @@ -24,3 +25,164 @@ To install RTI Connext DDS **version 6.0.1** Evalution: * Contact license@rti.com for an evaluation license. * Install RTI Connext 6.0.1 by running the installation program. When finished, it will run the RTI Launcher. * Use the RTI Launcher to install the license file (rti_license.dat) if needed. The launcher may also be used to launch the diagnostic tools and services. + +Detailed instructions for each platform are provided below. + +Ubuntu Linux source install +--------------------------- + +RTI Connext (version 6.0.1, amd64 only) +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Deb packages provided in the ROS 2 apt repositories +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +You can install a deb package of RTI Connext available on the ROS 2 apt repositories. +You will need to accept a license from RTI. + +.. code-block:: bash + + sudo apt update && sudo apt install -q -y ros-{DISTRO}-rmw-connextdds rti-connext-dds-6.0.1 + +Source the setup file to set the ``NDDSHOME`` environment variable. + +.. code-block:: bash + + cd /opt/rti.com/rti_connext_dds-6.0.1/resource/scripts && source ./rtisetenv_x64Linux4gcc7.3.0.bash; cd - + +Note: when using ``zsh`` you need to be in the directory of the script when sourcing it to have it work properly + +Now you can build as normal and support for RTI will be built as well. + +Official binary packages from RTI +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +You can install the Connext 6.0.1 package for Linux provided by RTI. + +After downloading, use ``chmod +x`` on the ``.run`` executable and then execute it. +Note that if you're installing to a system directory use ``sudo`` as well. + +The default location is ``~/rti_connext_dds-6.0.1`` + +After installation, run RTI launcher and point it to your license file (obtained from RTI). + +Add the following line to your ``.bashrc`` file pointing to your copy of the license. + +.. code-block:: bash + + export RTI_LICENSE_FILE=path/to/rti_license.dat + +Source the setup file to set the ``NDDSHOME`` environment variable. + +.. code-block:: bash + + cd ~/rti_connext_dds-6.0.1/resource/scripts && source ./rtisetenv_x64Linux4gcc7.3.0.bash; cd - + +Now you can build as normal and support for RTI will be built as well. + +Ubuntu Linux binary install +--------------------------- + +RTI Connext (version 6.0.1, amd64 only) +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +You can install a libraries-only deb package of RTI Connext 6.0.1, available from the OSRF Apt repository under a `non-commercial license `__. + +To install the libs-only deb package: + +.. code-block:: bash + + sudo apt update && sudo apt install -q -y ros-{DISTRO}-rmw-connextdds rti-connext-dds-6.0.1 + +You will need to accept a license agreement from RTI, and will find an 'rti_license.dat file in the installation. + +Add the following line to your ``.bashrc`` file pointing to your copy of the license (and source it). + +.. code-block:: bash + + export RTI_LICENSE_FILE=path/to/rti_license.dat + +All options need you to source the setup file to set the ``NDDSHOME`` environment variable: + +.. code-block:: bash + + cd /opt/rti.com/rti_connext_dds-6.0.1/resource/scripts && source ./rtisetenv_x64Linux4gcc7.3.0.bash; cd - + +Note: the above may need modification to match your RTI installation location + +If you want to install the Connext DDS-Security plugins please refer to :doc:`this page <./Install-Connext-Security-Plugins>`. + +OSX source install +------------------ + +RTI Connext (6.0.1) +^^^^^^^^^^^^^^^^^^^ + +You also need a Java runtime installed to run the RTI code generator, which you can get `here `__. + +After installing, run RTI launcher and point it to your license file. + +Source the setup file to set the ``NDDSHOME`` environment variable before building your workspace. + +.. code-block:: bash + + source /Applications/rti_connext_dds-6.0.1/resource/scripts/rtisetenv_x64Darwin17clang9.0.bash + +You may need to increase shared memory resources following https://community.rti.com/kb/osx510 + +If you want to install the Connext DDS-Security plugins please refer to :doc:`this page <./Install-Connext-Security-Plugins>`. + +OSX binary install +------------------ + + +Enable Connext support +^^^^^^^^^^^^^^^^^^^^^^ + +After installing, run RTI launcher and point it to your license file. + +Source the setup file to set the ``NDDSHOME`` environment variable before building your workspace. + +.. code-block:: bash + + source /Applications/rti_connext_dds-6.0.1/resource/scripts/rtisetenv_x64Darwin17clang9.0.bash + +You may need to increase shared memory resources following https://community.rti.com/kb/osx510. + +If you want to install the Connext DDS-Security plugins please refer to :doc:`this page <./Install-Connext-Security-Plugins>`. + +Windows source install +---------------------- + +RTI Connext 6.0.1 +^^^^^^^^^^^^^^^^^ + +After installing, use the RTI Launcher to load your license file. + +Then before building ROS 2, set up the Connext environment: + +.. code-block:: bash + + call "C:\Program Files\rti_connext_dds-6.0.1\resource\scripts\rtisetenv_x64Win64VS2017.bat" + +Note that this path might need to be slightly altered depending on where you selected to install RTI Connext DDS, and which version of Visual Studio was selected. +The path above is the current default path as of version 6.0.1, but will change as the version numbers increment in the future. + +If you want to install the Connext DDS-Security plugins please refer to :doc:`this page <./Install-Connext-Security-Plugins>`. + +Windows binary install +---------------------- + + +RTI Connext +^^^^^^^^^^^ + +After installing, run RTI launcher and point it to your license file. + +Then before using ROS 2, set up the Connext environment: + +.. code-block:: bash + + call "C:\Program Files\rti_connext_dds-6.0.1\resource\scripts\rtisetenv_x64Win64VS2017.bat" + +If you want to install the Connext DDS-Security plugins please refer to :doc:`this page <./Install-Connext-Security-Plugins>`. From 3959d21c85453d4133089dcf793f903987339006 Mon Sep 17 00:00:00 2001 From: Jihye Sofia Seo <9078892+jihyeseo@users.noreply.github.com> Date: Tue, 14 Jan 2025 10:05:33 +0100 Subject: [PATCH 05/29] Fix a typo in Writing-A-Simple-Cpp-Service-And-Client.rst (#4934) Signed-off-by: Jihye Sofia Seo <9078892+jihyeseo@users.noreply.github.com> --- .../Writing-A-Simple-Cpp-Service-And-Client.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client.rst b/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client.rst index 0a71492ba88..a1a743ad30f 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client.rst @@ -215,7 +215,7 @@ Inside the ``ros2_ws/src/cpp_srvcli/src`` directory, create a new file called `` request->a = 41; request->b = 1; auto result_future = client->async_send_request(request); - if (rclcpp::spin_until_future_complete(node, result_future) == + if (rclcpp::spin_until_future_complete(node, result_future) != rclcpp::FutureReturnCode::SUCCESS) { RCLCPP_ERROR(node->get_logger(), "service call failed :("); From ebb2768fe71c569d4afe6b93fa81a88c743776cd Mon Sep 17 00:00:00 2001 From: Jan Kaniuka <80155305+jkaniuka@users.noreply.github.com> Date: Tue, 14 Jan 2025 19:45:20 +0000 Subject: [PATCH 06/29] Accessing parameters loaded from YAML file (#4929) * docs(migrating_parameters): added hint regarding usage of dots instead of slashes while accessing params in ROS 2 * docs(python_params_in_class) : accessing params from YAML file * docs(cpp_params_in_class) : accessing params from YAML file * replaced :doc: with :ref: in reference * shorter description of setting params via YAML file - added references instead * added directions towards intermediate tutorials * docs(Understanding parameters): added comment regarding dots usage while separating params namespaces and name --- .../Migrating-Parameters.rst | 9 ++++++- .../Understanding-ROS2-Parameters.rst | 4 +++ .../Using-Parameters-In-A-Class-CPP.rst | 26 +++++++++++++++++-- .../Using-Parameters-In-A-Class-Python.rst | 26 +++++++++++++++++-- .../Using-ROS2-Launch-For-Large-Projects.rst | 4 +++ 5 files changed, 64 insertions(+), 5 deletions(-) diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-Parameters.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-Parameters.rst index ac07b2faf0e..5168f906df4 100644 --- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-Parameters.rst +++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-Parameters.rst @@ -21,7 +21,7 @@ In ROS 2, parameters are associated per node and are configurable at runtime wit Migrating YAML Parameter Files ------------------------------ -This guide describes how to adapt ROS 1 parameters files for ROS 2. +This guide describes how to adapt ROS 1 parameters files for ROS 2 and illustrates the difference in the way parameters can be accessed from the node level. YAML file example ^^^^^^^^^^^^^^^^^ @@ -60,6 +60,13 @@ We would construct our ROS 2 parameters file as follows: Note the use of wildcards (``/**``) to indicate that the parameter ``debug`` should be set on any node in any namespace. +Accessing parameters inside node +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Let's say we want to use ``lidar_name`` parameter inside C++/Python node. +In ROS 1, we used slashes to separate node name and namespaces - ``"lidar_ns/lidar_node_name/lidar_name"``. +In ROS 2, we use dots instead of slashes - ``"lidar_ns.lidar_node_name.lidar_name"``. + Feature parity ^^^^^^^^^^^^^^ diff --git a/source/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters.rst b/source/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters.rst index 5d28b52f8ec..8ad0b507316 100644 --- a/source/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters.rst +++ b/source/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters.rst @@ -85,6 +85,8 @@ You will see the node namespaces, ``/teleop_turtle`` and ``/turtlesim``, followe qos_overrides./parameter_events.publisher.reliability use_sim_time +The namespaces of the parameter and its name are separated using dots as you can see, for example, in ``parameter_events.publisher.depth``. + Every node has the parameter ``use_sim_time``; it's not unique to turtlesim. Based on their names, it looks like ``/turtlesim``'s parameters determine the background color of the turtlesim window using RGB color values. @@ -214,6 +216,8 @@ Your terminal will return the message: Read-only parameters can only be modified at startup and not afterwards, that is why there are some warnings for the "qos_overrides" parameters. +.. _LoadParameterFileOnNodeStartup: + 7 Load parameter file on node startup ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-CPP.rst b/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-CPP.rst index 20102288586..24320fc3b34 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-CPP.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-CPP.rst @@ -22,7 +22,7 @@ Background When making your own :doc:`nodes <../Beginner-CLI-Tools/Understanding-ROS2-Nodes/Understanding-ROS2-Nodes>` you will sometimes need to add parameters that can be set from the launch file. -This tutorial will show you how to create those parameters in a C++ class, and how to set them in a launch file. +This tutorial will show you how to create those parameters in a C++ class, and how to set them using launch file. Prerequisites ------------- @@ -297,7 +297,7 @@ The terminal should return the following message every second: [INFO] [minimal_param_node]: Hello world! Now you can see the default value of your parameter, but you want to be able to set it yourself. -There are two ways to accomplish this. +There are four ways to accomplish this. 3.1 Change via the console ~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -428,6 +428,22 @@ The terminal should return the following message the first time: Further outputs should show ``[INFO] [minimal_param_node]: Hello world!`` every second. +3.3 Change via launch file loading parameters from YAML file +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Instead of listing parameters and their values in launch file, you can create a separate YAML file that will be loaded in launch file. +Placing parameters in a YAML file makes it easier to organize them, for example, by assigning them to different namespaces. +You can read more about it :ref:`here `. + +.. note:: + + While declaring, getting and setting parameter value inside your C++ node, you should use dot as a separator between parameter's namespace and name. + +3.4 Change via passing YAML file as an argument at node startup +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Return to :ref:`tutorial about parameters ` to remind yourself, how to load parameters file at node startup using CLI. + Summary ------- @@ -438,3 +454,9 @@ Next steps ---------- Now that you have some packages and ROS 2 systems of your own, the :doc:`next tutorial <./Getting-Started-With-Ros2doctor>` will show you how to examine issues in your environment and systems in case you have problems. + +Related content +--------------- + +* For more detailed information about using YAML files to load parameters, please refer to :ref:`this section ` of Managing large projects tutorial. +* If you want to learn, how to monitor and respond to parameter changes, check out :doc:`Monitoring for parameter changes (C++) <../Intermediate/Monitoring-For-Parameter-Changes-CPP>` tutorial. diff --git a/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-Python.rst b/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-Python.rst index 7e87b472a52..539aaa68f3b 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-Python.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-Python.rst @@ -22,7 +22,7 @@ Background When making your own :doc:`nodes <../Beginner-CLI-Tools/Understanding-ROS2-Nodes/Understanding-ROS2-Nodes>` you will sometimes need to add parameters that can be set from the launch file. -This tutorial will show you how to create those parameters in a Python class, and how to set them in a launch file. +This tutorial will show you how to create those parameters in a Python class, and how to set them using launch file. Prerequisites ------------- @@ -294,7 +294,7 @@ The terminal should return the following message every second: [INFO] [parameter_node]: Hello world! Now you can see the default value of your parameter, but you want to be able to set it yourself. -There are two ways to accomplish this. +There are four ways to accomplish this. 3.1 Change via the console ~~~~~~~~~~~~~~~~~~~~~~~~~~ @@ -434,6 +434,22 @@ The terminal should return the following message the first time: Further outputs should show ``[INFO] [minimal_param_node]: Hello world!`` every second. +3.3 Change via launch file loading parameters from YAML file +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Instead of listing parameters and their values in launch file, you can create a separate YAML file that will be loaded in launch file. +Placing parameters in a YAML file makes it easier to organize them, for example, by assigning them to different namespaces. +You can read more about it :ref:`here `. + +.. note:: + + While declaring, getting and setting parameter value inside your Python node, you should use dot as a separator between parameter's namespace and name. + +3.4 Change via passing YAML file as an argument at node startup +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Return to :ref:`tutorial about parameters ` to remind yourself, how to load parameters file at node startup using CLI. + Summary ------- @@ -444,3 +460,9 @@ Next steps ---------- Now that you have some packages and ROS 2 systems of your own, the :doc:`next tutorial <./Getting-Started-With-Ros2doctor>` will show you how to examine issues in your environment and systems in case you have problems. + +Related content +--------------- + +* For more detailed information about using YAML files to load parameters, please refer to :ref:`this section ` of Managing large projects tutorial. +* If you want to learn, how to monitor and respond to parameter changes, check out :doc:`Monitoring for parameter changes (Python) <../Intermediate/Monitoring-For-Parameter-Changes-Python>` tutorial. diff --git a/source/Tutorials/Intermediate/Launch/Using-ROS2-Launch-For-Large-Projects.rst b/source/Tutorials/Intermediate/Launch/Using-ROS2-Launch-For-Large-Projects.rst index 8217cb76d74..7442b58daf4 100644 --- a/source/Tutorials/Intermediate/Launch/Using-ROS2-Launch-For-Large-Projects.rst +++ b/source/Tutorials/Intermediate/Launch/Using-ROS2-Launch-For-Large-Projects.rst @@ -123,6 +123,8 @@ However, there are cases when some nodes or launch files have to be launched sep .. note:: Design tip: Be aware of the tradeoffs when deciding how many top-level launch files your application requires. +.. _Parameters: + 2 Parameters ^^^^^^^^^^^^ @@ -170,6 +172,8 @@ First, create a new file called ``turtlesim_world_1_launch.py``. This launch file starts the ``turtlesim_node`` node, which starts the turtlesim simulation, with simulation configuration parameters that are defined and passed to the nodes. +.. _LoadingParametersFromYAMLFile: + 2.2 Loading parameters from YAML file ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ From 3a56fc9d5dca4afa39b6b63f3c161767119330f5 Mon Sep 17 00:00:00 2001 From: yadunund Date: Wed, 15 Jan 2025 12:17:21 -0800 Subject: [PATCH 07/29] Add note on how to block the release of select packages in a given repository (#4941) Signed-off-by: Yadunund --- source/How-To-Guides/Releasing/First-Time-Release.rst | 7 +++++++ source/How-To-Guides/Releasing/Subsequent-Releases.rst | 7 +++++++ 2 files changed, 14 insertions(+) diff --git a/source/How-To-Guides/Releasing/First-Time-Release.rst b/source/How-To-Guides/Releasing/First-Time-Release.rst index b5c146625ca..351a3c9712a 100644 --- a/source/How-To-Guides/Releasing/First-Time-Release.rst +++ b/source/How-To-Guides/Releasing/First-Time-Release.rst @@ -114,6 +114,13 @@ You should respond to the prompts as following: Bloom will automatically create a pull request for you against `rosdistro `_. +.. note:: + + By default, bloom will release all packages in the source repository. + To selectively block the release of some packages for a particular ``{DISTRO}``, add ``{DISTRO}.ignored`` files to the ``master``` branch of the release repository. + In each file, list the name of the package, one per line, to block the release of the package. + The `rosidl-release `_ repository may serve as a useful reference for this configuration. + Next Steps ---------- diff --git a/source/How-To-Guides/Releasing/Subsequent-Releases.rst b/source/How-To-Guides/Releasing/Subsequent-Releases.rst index 34d99ea1e9a..767ffc264b6 100644 --- a/source/How-To-Guides/Releasing/Subsequent-Releases.rst +++ b/source/How-To-Guides/Releasing/Subsequent-Releases.rst @@ -54,6 +54,13 @@ Run the following command, replacing ``my_repo`` with the name of your repositor Bloom will automatically create a pull request for you against `rosdistro `_. +.. note:: + + By default, bloom will release all packages in the source repository. + To selectively block the release of some packages for a particular ``{DISTRO}``, add ``{DISTRO}.ignored`` files to the ``master``` branch of the release repository. + In each file, list the name of the package, one per line, to block the release of the package. + The `rosidl-release `_ repository may serve as a useful reference for this configuration. + Next Steps ---------- From 1c8de6b87bd01079ae4bbbcd056df7dd166bc1b5 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Wed, 15 Jan 2025 12:18:26 -0800 Subject: [PATCH 08/29] add Extra Arguments for Component Manager. (#4904) * add Extra Arguments for Component Manager. Signed-off-by: Tomoya Fujita * move the command line example before the table. Signed-off-by: Tomoya Fujita * address review comments. Signed-off-by: Tomoya Fujita --------- Signed-off-by: Tomoya Fujita --- source/Tutorials/Intermediate/Composition.rst | 50 +++++++++++++++++-- 1 file changed, 47 insertions(+), 3 deletions(-) diff --git a/source/Tutorials/Intermediate/Composition.rst b/source/Tutorials/Intermediate/Composition.rst index f03d441ef1d..e5833e1ef00 100644 --- a/source/Tutorials/Intermediate/Composition.rst +++ b/source/Tutorials/Intermediate/Composition.rst @@ -367,12 +367,56 @@ Passing additional arguments into components ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ The ``ros2 component load`` command-line supports passing particular options to the component manager for use when constructing the node. -As of now, the only command-line option that is supported is to instantiate a node using intra-process communication. -This functionality can be used as follows: + +The following example shows the use of the extra arguments ``use_intra_process_comms`` and ``forward_global_arguments``: .. code-block:: bash - ros2 component load /ComponentManager composition composition::Talker -e use_intra_process_comms:=true + ros2 component load /ComponentManager composition composition::Talker -e use_intra_process_comms:=true -e forward_global_arguments:=false + +The following extra arguments are supported. + +.. list-table:: Extra Arguments for Component Manager + :widths: 15 15 15 15 + :header-rows: 1 + + * - Argument + - Type + - Default + - Description + * - ``forward_global_arguments`` + - Boolean + - True + - Apply global arguments to the component node when loading. + * - ``enable_rosout`` + - Boolean + - True + - Enable the ``rosout`` topic publisher in the component node. + * - ``use_intra_process_comms`` + - Boolean + - False + - Enable intra-process communication in the component node. + * - ``enable_topic_statistics`` + - Boolean + - False + - Enable a topic statistics publisher in the component node. + * - ``start_parameter_services`` + - Boolean + - True + - Enable services to manage parameters in the component node. + * - ``start_parameter_event_publisher`` + - Boolean + - True + - Enable the parameter event publisher in the component node. + * - ``use_clock_thread`` + - Boolean + - True + - Enable a dedicated clock thread in the component node. + * - ``enable_logger_service`` + - Boolean + - False + - Enable logger level management service in the component node. + Composable nodes as shared libraries ------------------------------------ From ae8f007571520735fafe5d42dccfdc643307c027 Mon Sep 17 00:00:00 2001 From: Victor Coutinho Vieira Santos <69547580+ViktorCVS@users.noreply.github.com> Date: Thu, 16 Jan 2025 10:57:13 -0300 Subject: [PATCH 09/29] Correcting the name of the programming language (#4946) --- source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst b/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst index 68bf7b8bb6b..53bc4f377aa 100644 --- a/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst +++ b/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst @@ -68,7 +68,7 @@ Also be sure to add this information to the ``setup.py`` file as well. description='Python bag reading tutorial', license='Apache-2.0', -2 Write the C++ Reader +2 Write the Python Reader ^^^^^^^^^^^^^^^^^^^^^^ Inside the ``ros2_ws/src/bag_reader_node_py/bag_reader_node_py`` directory, create a new file called ``simple_bag_reader.py`` and paste the following code into it. From 73a7aec86ed1c0034e22aaa970be718ae190ea89 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alejandro=20Hern=C3=A1ndez=20Cordero?= Date: Thu, 16 Jan 2025 18:54:19 +0100 Subject: [PATCH 10/29] Update Reading-From-A-Bag-File-Python.rst MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Alejandro Hernández Cordero --- source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst b/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst index 53bc4f377aa..d4e8b746b2c 100644 --- a/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst +++ b/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst @@ -69,7 +69,7 @@ Also be sure to add this information to the ``setup.py`` file as well. license='Apache-2.0', 2 Write the Python Reader -^^^^^^^^^^^^^^^^^^^^^^ +^^^^^^^^^^^^^^^^^^^^^^^^^ Inside the ``ros2_ws/src/bag_reader_node_py/bag_reader_node_py`` directory, create a new file called ``simple_bag_reader.py`` and paste the following code into it. From f7ce0afee7ed9725f42abd7301ca2fe81219badc Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Thu, 16 Jan 2025 09:58:48 -0800 Subject: [PATCH 11/29] Fix title underline (#4949) Signed-off-by: Christophe Bedard From 32d390dd4135dd0917d61448e97e98bf9ea19c82 Mon Sep 17 00:00:00 2001 From: Scott K Logan Date: Tue, 21 Jan 2025 10:43:20 -0600 Subject: [PATCH 12/29] Add initial timeline for Kilted Kaiju (#4905) * Add initial timeline for Kilted Kaiju * Also populate the platform targets based on current REP-2000 proposal. * Fix Kilted branch date Signed-off-by: Scott K Logan Co-authored-by: Tomoya Fujita --- source/Releases/Release-Kilted-Kaiju.rst | 49 ++++++++++++++++++++++-- 1 file changed, 46 insertions(+), 3 deletions(-) diff --git a/source/Releases/Release-Kilted-Kaiju.rst b/source/Releases/Release-Kilted-Kaiju.rst index f5d3f93bb4a..78c38266af8 100644 --- a/source/Releases/Release-Kilted-Kaiju.rst +++ b/source/Releases/Release-Kilted-Kaiju.rst @@ -19,15 +19,17 @@ Kilted Kaiju is primarily supported on the following platforms: Tier 1 platforms: -* TODO +* Ubuntu 24.04 (Noble): ``amd64`` and ``arm64`` +* Windows 10 (Visual Studio 2019): ``amd64`` Tier 2 platforms: -* TODO +* RHEL 9: ``amd64`` Tier 3 platforms: -* TODO +* macOS: ``amd64`` +* Debian Bookworm: ``amd64`` For more information about RMW implementations, compiler / interpreter versions, and system dependency versions see `REP 2000 `__. @@ -45,3 +47,44 @@ Development progress For progress on the development of Kiltled Kaiju, see `this project board `__. For the broad process followed by Kilted Kaiju, see the :doc:`process description page `. + +Release Timeline +---------------- + + December, 2024 - Platform decisions + REP 2000 is updated with the target platforms and major dependency versions. + + Mon. April 7, 2025 - Alpha + RMW freeze + Preliminary testing and stabilization of ROS Base [1]_ packages, and API and feature freeze for RMW provider packages. + + Mon. April 14, 2024 - Freeze + API and feature freeze for ROS Base [1]_ packages in Rolling Ridley. + Only bug fix releases should be made after this point. + New packages can be released independently. + + Mon. April 21, 2024 - Branch + Branch from Rolling Ridley. + ``rosdistro`` is reopened for Rolling PRs for ROS Base [1]_ packages. + Kilted development shifts from ``ros-rolling-*`` packages to ``ros-kilted-*`` packages. + + Mon. April 28, 2024 - Beta + Updated releases of ROS Desktop [2]_ packages available. + Call for general testing. + + Thu, May 1, 2024 - Kick off of Tutorial Party + Tutorials hosted at https://github.com/osrf/ros2_test_cases are open for community testing. + + Mon. May 12, 2024 - Release Candidate + Release Candidate packages are built. + Updated releases of ROS Desktop [2]_ packages available. + + Mon. May 19, 2024 - Distro Freeze + Freeze all Kilted branches on all `ROS 2 desktop packages `__ and ``rosdistro``. + No pull requests for any ``kilted`` branch or targeting ``kilted/distribution.yaml`` in ``rosdistro`` repo will be merged. + + Fri. May 23, 2024 - General Availability + Release announcement. + `ROS 2 desktop packages `__ source freeze is lifted and ``rosdistro`` is reopened for Kilted pull requests. + +.. [1] The ``ros_base`` variant is described in `REP 2001 (ros-base) `_. +.. [2] The ``desktop`` variant is described in `REP 2001 (desktop-variants) `_. From c717d69e49b554b1626204adedf600d102d30c2f Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Tue, 21 Jan 2025 15:51:27 -0800 Subject: [PATCH 13/29] add example how to use wildcards in parameter yaml file. (#4950) * add example how to use wildcards in parameter yaml file. Signed-off-by: Tomoya.Fujita * adjust explanation a bit and typo fixes. Signed-off-by: Tomoya.Fujita --------- Signed-off-by: Tomoya.Fujita Signed-off-by: Tomoya.Fujita --- source/How-To-Guides/Node-arguments.rst | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/source/How-To-Guides/Node-arguments.rst b/source/How-To-Guides/Node-arguments.rst index d7c73f5c5fc..e0d4751c43c 100644 --- a/source/How-To-Guides/Node-arguments.rst +++ b/source/How-To-Guides/Node-arguments.rst @@ -125,6 +125,27 @@ As an example, save the following as ``demo_params.yaml``: some_integers: [1, 2, 3, 4] some_doubles : [3.14, 2.718] + /**: + ros__parameters: + wildcard_full: "Full wildcard for any namespaces and any node names" + + /**/parameter_blackboard: + ros__parameters: + wildcard_namespace: "Wildcard for a specific node name under any namespace" + + /*: + ros__parameters: + wildcard_nodename_root_namespace: "Wildcard for any node names, but only in root namespace" + + +.. note:: + + Wildcards can be used for node names and namespaces. + ``*`` matches a single token delimited by slashes (``/``). + ``**`` matches zero or more tokens delimited by slashes. + Partial matches are not allowed (e.g. ``foo*``). + + Then either declare the parameters within your node with `declare_parameter `__ or `declare_parameters `__, or `set the node to automatically declare parameters `__ if they were passed in via a command line override. Then run the following: @@ -148,3 +169,6 @@ Other nodes will be able to retrieve the parameter values, e.g.: some_lists.some_doubles some_lists.some_integers use_sim_time + wildcard_full + wildcard_namespace + wildcard_nodename_root_namespace From bcf2e4cfb6be774b9a9c2f8b0f161d083d40149b Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Wed, 22 Jan 2025 09:46:53 -0800 Subject: [PATCH 14/29] build only selected packages to enable security. (#4890) Signed-off-by: Tomoya Fujita --- .../Tutorials/Advanced/Security/Introducing-ros2-security.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/Tutorials/Advanced/Security/Introducing-ros2-security.rst b/source/Tutorials/Advanced/Security/Introducing-ros2-security.rst index 2c5fdd49b8d..b0eef6e17ef 100644 --- a/source/Tutorials/Advanced/Security/Introducing-ros2-security.rst +++ b/source/Tutorials/Advanced/Security/Introducing-ros2-security.rst @@ -71,7 +71,7 @@ Fast DDS requires an additional CMake flag to build the security plugins, so the .. code-block:: bash - colcon build --symlink-install --cmake-args -DSECURITY=ON + colcon build --symlink-install --cmake-args -DSECURITY=ON --packages-select fastrtps rmw_fastrtps_cpp rmw_fastrtps_dynamic_cpp rmw_fastrtps_shared_cpp Selecting an alternate middleware From cee9b1192093998022ab72ff4fb036bb7ae9ab5f Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Thu, 23 Jan 2025 22:53:02 -0800 Subject: [PATCH 15/29] Update Launching-Multiple-Nodes.rst (#4961) (#4962) * Add the same message found in the prerequisites of the previous tutorials. Signed-off-by: Yamil Aucca <162926034+studiareCS@users.noreply.github.com> (cherry picked from commit 2460a9c2fc89d886851ba7308a49c1204591a2dc) Co-authored-by: Yamil Aucca <162926034+studiareCS@users.noreply.github.com> --- .../Launching-Multiple-Nodes/Launching-Multiple-Nodes.rst | 2 ++ 1 file changed, 2 insertions(+) diff --git a/source/Tutorials/Beginner-CLI-Tools/Launching-Multiple-Nodes/Launching-Multiple-Nodes.rst b/source/Tutorials/Beginner-CLI-Tools/Launching-Multiple-Nodes/Launching-Multiple-Nodes.rst index ba7ed9da43c..c37bc7109cd 100644 --- a/source/Tutorials/Beginner-CLI-Tools/Launching-Multiple-Nodes/Launching-Multiple-Nodes.rst +++ b/source/Tutorials/Beginner-CLI-Tools/Launching-Multiple-Nodes/Launching-Multiple-Nodes.rst @@ -38,6 +38,8 @@ You also won't be able to use the ``sudo apt install ros--`` co If you are using Linux and are not already familiar with the shell, `this tutorial `__ will help. +As always, don't forget to source ROS 2 in :doc:`every new terminal you open <../Configuring-ROS2-Environment>`. + Tasks ----- From f9b32d55caaddb9a5431da4ccbca34ed4e77e67e Mon Sep 17 00:00:00 2001 From: Alexis Guijarro Date: Fri, 24 Jan 2025 10:43:40 -0600 Subject: [PATCH 16/29] Improved-Dynamic-Discovery.rst: Fixing Bash Syntax (#4960) * Improved-Dynamic-Discovery.rst: Fixing Bash Syntax * Improved-Dynamic-Discovery.rst: Adding missing fixes to bash code lines --- source/Tutorials/Advanced/Improved-Dynamic-Discovery.rst | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/source/Tutorials/Advanced/Improved-Dynamic-Discovery.rst b/source/Tutorials/Advanced/Improved-Dynamic-Discovery.rst index c9a8cba6694..fcd0e4086ab 100755 --- a/source/Tutorials/Advanced/Improved-Dynamic-Discovery.rst +++ b/source/Tutorials/Advanced/Improved-Dynamic-Discovery.rst @@ -227,28 +227,28 @@ For example, the following commands will limit the ROS 2 communication only with .. code-block:: console export ROS_AUTOMATIC_DISCOVERY_RANGE=LOCALHOST - export ROS_STATIC_PEERS=192.168.0.1;remote.com + export ROS_STATIC_PEERS='192.168.0.1;remote.com' To maintain this setting between shell sessions, you can add the command to your shell startup script: .. code-block:: console echo "export ROS_AUTOMATIC_DISCOVERY_RANGE=LOCALHOST" >> ~/.bashrc - echo "export ROS_STATIC_PEERS=192.168.0.1;remote.com" >> ~/.bashrc + echo "export ROS_STATIC_PEERS='192.168.0.1;remote.com'" >> ~/.bashrc .. group-tab:: macOS .. code-block:: console export ROS_AUTOMATIC_DISCOVERY_RANGE=LOCALHOST - export ROS_STATIC_PEERS=192.168.0.1;remote.com + export ROS_STATIC_PEERS='192.168.0.1;remote.com' To maintain this setting between shell sessions, you can add the command to your shell startup script: .. code-block:: console echo "export ROS_AUTOMATIC_DISCOVERY_RANGE=LOCALHOST" >> ~/.bash_profile - echo "export ROS_STATIC_PEERS=192.168.0.1;remote.com" >> ~/.bash_profile + echo "export ROS_STATIC_PEERS='192.168.0.1;remote.com'" >> ~/.bash_profile .. group-tab:: Windows From 482b754eba5d8bc071b62f45029cf46d2e6fa404 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Mon, 27 Jan 2025 00:45:43 -0800 Subject: [PATCH 17/29] suggest spin_all to migrate spinOnce to execute all available works in the queue. (#4966) Signed-off-by: Tomoya.Fujita --- .../Migrating-CPP-Package-Example.rst | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst index 5cdb8ff0ccf..f380f55e3b8 100644 --- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst +++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Package-Example.rst @@ -204,13 +204,13 @@ Change the publish call to use the ``->`` operator instead of ``.``. chatter_pub->publish(msg); Spinning (i.e., letting the communications system process any pending -incoming/outgoing messages) is different in that the call now takes the node as -an argument: +incoming/outgoing messages until no more work is available) is different +in that the call now takes the node and timeout as arguments: .. code-block:: cpp // ros::spinOnce(); - rclcpp::spin_some(node); + rclcpp::spin_all(node, 0s); Sleeping using the rate object is unchanged. @@ -218,11 +218,15 @@ Putting it all together, the new ``talker.cpp`` looks like this: .. code-block:: cpp + #include #include // #include "ros/ros.h" #include "rclcpp/rclcpp.hpp" // #include "std_msgs/String.h" #include "std_msgs/msg/string.hpp" + + using namespace std::chrono_literals; + int main(int argc, char **argv) { // ros::init(argc, argv, "talker"); @@ -247,7 +251,7 @@ Putting it all together, the new ``talker.cpp`` looks like this: // chatter_pub.publish(msg); chatter_pub->publish(msg); // ros::spinOnce(); - rclcpp::spin_some(node); + rclcpp::spin_all(node, 0s); loop_rate.sleep(); } return 0; From fc1311bedb1786813cd0a27b4b3bba844dbb718e Mon Sep 17 00:00:00 2001 From: Osman Karaketir Date: Mon, 27 Jan 2025 19:52:23 +0300 Subject: [PATCH 18/29] Remove confusing services definition (#4970) Service is not always blocking-call. --- source/How-To-Guides/Topics-Services-Actions.rst | 1 - 1 file changed, 1 deletion(-) diff --git a/source/How-To-Guides/Topics-Services-Actions.rst b/source/How-To-Guides/Topics-Services-Actions.rst index 1c1bbdfb421..5a57e0d1185 100644 --- a/source/How-To-Guides/Topics-Services-Actions.rst +++ b/source/How-To-Guides/Topics-Services-Actions.rst @@ -21,7 +21,6 @@ Services -------- * Should be used for remote procedure calls that terminate quickly, e.g. for querying the state of a node or doing a quick calculation such as IK. They should never be used for longer running processes, in particular processes that might be required to preempt if exceptional situations occur and they should never change or depend on state to avoid unwanted side effects for other nodes. -* Simple blocking call. Mostly used for comparably fast tasks as requesting specific data. Semantically for processing requests. Actions ------- From 147e7364970e1638fb8dec021d4b5ece36e5e834 Mon Sep 17 00:00:00 2001 From: Geoffrey Biggs Date: Tue, 28 Jan 2025 07:33:32 +0900 Subject: [PATCH 19/29] Correct Kat Scott's role listing (#4967) Signed-off-by: Geoffrey Biggs --- source/The-ROS2-Project/Governance.rst | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/source/The-ROS2-Project/Governance.rst b/source/The-ROS2-Project/Governance.rst index d63ef8c4fc9..10223d331c1 100644 --- a/source/The-ROS2-Project/Governance.rst +++ b/source/The-ROS2-Project/Governance.rst @@ -105,11 +105,6 @@ The ROS PMC currently consists of the following constituents: - `nuclearsandwich `_ - Member / Infrastructure Project Lead - PST (UTC-8)/PDT (UTC-7) - * - Kat Scott - - `Intrinsic `_ - - `kscottz `_ - - OSRA Developer Advocate - - PST (UTC-8)/PDT (UTC-7) * - Alberto Soragna - `iRobot `_ - `alsora `_ @@ -146,6 +141,10 @@ The ROS committers (who are not also part of the ROS PMC) consists of the follow - `Intrinsic `_ - `quarkytale `_ - PST (UTC-8)/PDT (UTC-7) + * - Kat Scott + - `Intrinsic `_ + - `kscottz `_ + - PST (UTC-8)/PDT (UTC-7) * - Miguel Company - `eProsima `_ - `MiguelCompany `_ From 2e1572292a0d4bdc030ad27a9a2a76d2b08ad0d6 Mon Sep 17 00:00:00 2001 From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com> Date: Thu, 30 Jan 2025 15:15:38 +0100 Subject: [PATCH 20/29] Remove underscored objects from rosbag_py tutorial (backport #4976) (#4978) remove underscore methods that are imported into rosbag2_py in __init__.py Signed-off-by: Joe Rickwalder (cherry picked from commit 9f4a25f1128060e1a3da30cd919006077b60ab30) Signed-off-by: Tomoya Fujita Co-authored-by: Joe Rickwalder Co-authored-by: Tomoya Fujita --- .../Reading-From-A-Bag-File-Python.rst | 8 +++--- .../Recording-A-Bag-From-Your-Own-Node-Py.rst | 28 +++++++++---------- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst b/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst index d4e8b746b2c..c2bcccc7f17 100644 --- a/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst +++ b/source/Tutorials/Advanced/Reading-From-A-Bag-File-Python.rst @@ -87,10 +87,10 @@ Inside the ``ros2_ws/src/bag_reader_node_py/bag_reader_node_py`` directory, crea def __init__(self): super().__init__('simple_bag_reader') self.reader = rosbag2_py.SequentialReader() - storage_options = rosbag2_py._storage.StorageOptions( + storage_options = rosbag2_py.StorageOptions( uri='my_bag', storage_id='mcap') - converter_options = rosbag2_py._storage.ConverterOptions('', '') + converter_options = rosbag2_py.ConverterOptions('', '') self.reader.open(storage_options, converter_options) self.publisher = self.create_publisher(String, 'chatter', 10) @@ -138,10 +138,10 @@ The default conversion options are used, which will perform no conversion and st .. code-block:: Python - storage_options = rosbag2_py._storage.StorageOptions( + storage_options = rosbag2_py.StorageOptions( uri='my_bag', storage_id='mcap') - converter_options = rosbag2_py._storage.ConverterOptions('', '') + converter_options = rosbag2_py.ConverterOptions('', '') self.reader.open(storage_options, converter_options) Next, we create a publisher and a timer to publish the data that reader object reads from the bag file. diff --git a/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-Py.rst b/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-Py.rst index 85fc1513141..4e86d5877d9 100644 --- a/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-Py.rst +++ b/source/Tutorials/Advanced/Recording-A-Bag-From-Your-Own-Node-Py.rst @@ -104,13 +104,13 @@ Inside the ``ros2_ws/src/bag_recorder_nodes_py/bag_recorder_nodes_py`` directory super().__init__('simple_bag_recorder') self.writer = rosbag2_py.SequentialWriter() - storage_options = rosbag2_py._storage.StorageOptions( + storage_options = rosbag2_py.StorageOptions( uri='my_bag', storage_id='mcap') - converter_options = rosbag2_py._storage.ConverterOptions('', '') + converter_options = rosbag2_py.ConverterOptions('', '') self.writer.open(storage_options, converter_options) - topic_info = rosbag2_py._storage.TopicMetadata( + topic_info = rosbag2_py.TopicMetadata( id=0, name='chatter', type='std_msgs/msg/String', @@ -163,10 +163,10 @@ The default conversion options are used, which will perform no conversion and st .. code-block:: Python - storage_options = rosbag2_py._storage.StorageOptions( + storage_options = rosbag2_py.StorageOptions( uri='my_bag', storage_id='mcap') - converter_options = rosbag2_py._storage.ConverterOptions('', '') + converter_options = rosbag2_py.ConverterOptions('', '') self.writer.open(storage_options, converter_options) Next, we need to tell the writer about the topics we wish to store. @@ -175,7 +175,7 @@ This object specifies the topic name, topic data type, and serialization format .. code-block:: Python - topic_info = rosbag2_py._storage.TopicMetadata( + topic_info = rosbag2_py.TopicMetadata( id=0, name='chatter', type='std_msgs/msg/String', @@ -346,13 +346,13 @@ Inside the ``ros2_ws/src/bag_recorder_nodes_py/bag_recorder_nodes_py`` directory self.data.data = 0 self.writer = rosbag2_py.SequentialWriter() - storage_options = rosbag2_py._storage.StorageOptions( + storage_options = rosbag2_py.StorageOptions( uri='timed_synthetic_bag', storage_id='mcap') - converter_options = rosbag2_py._storage.ConverterOptions('', '') + converter_options = rosbag2_py.ConverterOptions('', '') self.writer.open(storage_options, converter_options) - topic_info = rosbag2_py._storage.TopicMetadata( + topic_info = rosbag2_py.TopicMetadata( id=0, name='synthetic', type='example_interfaces/msg/Int32', @@ -391,7 +391,7 @@ First, the name of the bag is changed. .. code-block:: Python - storage_options = rosbag2_py._storage.StorageOptions( + storage_options = rosbag2_py.StorageOptions( uri='timed_synthetic_bag', storage_id='mcap') @@ -399,7 +399,7 @@ The name of the topic is also changed, as is the data type stored. .. code-block:: Python - topic_info = rosbag2_py._storage.TopicMetadata( + topic_info = rosbag2_py.TopicMetadata( id=0, name='synthetic', type='example_interfaces/msg/Int32', @@ -531,13 +531,13 @@ Inside the ``ros2_ws/src/bag_recorder_nodes_py/bag_recorder_nodes_py`` directory def main(args=None): writer = rosbag2_py.SequentialWriter() - storage_options = rosbag2_py._storage.StorageOptions( + storage_options = rosbag2_py.StorageOptions( uri='big_synthetic_bag', storage_id='mcap') - converter_options = rosbag2_py._storage.ConverterOptions('', '') + converter_options = rosbag2_py.ConverterOptions('', '') writer.open(storage_options, converter_options) - topic_info = rosbag2_py._storage.TopicMetadata( + topic_info = rosbag2_py.TopicMetadata( id=0, name='synthetic', type='example_interfaces/msg/Int32', From 49f66fd7247c567eb8a6a52f5d2a1dd88fcd0de5 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Thu, 30 Jan 2025 09:14:31 -0800 Subject: [PATCH 21/29] address mistyping detected by codespell checker. (#4980) Signed-off-by: Tomoya Fujita --- source/Concepts/Basic/About-Interfaces.rst | 2 +- source/Concepts/Basic/About-Topics.rst | 2 +- source/Concepts/Intermediate/About-RQt.rst | 4 ++-- source/How-To-Guides/Ament-CMake-Documentation.rst | 2 +- source/How-To-Guides/Core-maintainer-guide.rst | 2 +- source/How-To-Guides/Getting-Backtraces-in-ROS-2.rst | 2 +- source/How-To-Guides/Installation-Troubleshooting.rst | 4 ++-- .../Migrating-from-ROS1/Migrating-CPP-Packages.rst | 2 +- .../Migrating-from-ROS1/Migrating-Launch-Files.rst | 2 +- .../Migrating-Python-Package-Example.rst | 4 ++-- source/How-To-Guides/Using-Variants.rst | 2 +- source/How-To-Guides/Using-ros2-param.rst | 2 +- .../Install-Connext-University-Eval.rst | 2 +- .../Contributing/Contributing-To-ROS-2-Documentation.rst | 4 ++-- source/The-ROS2-Project/Contributing/Developer-Guide.rst | 4 ++-- source/The-ROS2-Project/ROSCon-Content.rst | 2 +- source/Tutorials/Advanced/FastDDS-Configuration.rst | 2 +- source/Tutorials/Advanced/Reading-From-A-Bag-File-CPP.rst | 2 +- source/Tutorials/Advanced/Security/Access-Controls.rst | 2 +- .../Tutorials/Advanced/Security/Deployment-Guidelines.rst | 4 ++-- .../Advanced/Security/Introducing-ros2-security.rst | 2 +- source/Tutorials/Advanced/Security/The-Keystore.rst | 8 ++++---- .../Beginner-CLI-Tools/Configuring-ROS2-Environment.rst | 2 +- .../Using-Parameters-In-A-Class-Python.rst | 2 +- source/Tutorials/Demos/Real-Time-Programming.rst | 2 +- .../Intermediate/Monitoring-For-Parameter-Changes-CPP.rst | 2 +- .../Monitoring-For-Parameter-Changes-Python.rst | 2 +- .../Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst | 2 +- .../Intermediate/Tf2/Quaternion-Fundamentals.rst | 2 +- .../Intermediate/URDF/Exporting-an-URDF-File.rst | 2 +- 30 files changed, 39 insertions(+), 39 deletions(-) diff --git a/source/Concepts/Basic/About-Interfaces.rst b/source/Concepts/Basic/About-Interfaces.rst index 9c7d5f4677c..228fc1789f6 100644 --- a/source/Concepts/Basic/About-Interfaces.rst +++ b/source/Concepts/Basic/About-Interfaces.rst @@ -207,7 +207,7 @@ For example: Constants ^^^^^^^^^ -Each constant definition is like a field description with a default value, except that this value can never be changed programatically. +Each constant definition is like a field description with a default value, except that this value can never be changed programmatically. This value assignment is indicated by use of an equal '=' sign, e.g. .. code-block:: bash diff --git a/source/Concepts/Basic/About-Topics.rst b/source/Concepts/Basic/About-Topics.rst index 3cd7086a33c..16560d43f40 100644 --- a/source/Concepts/Basic/About-Topics.rst +++ b/source/Concepts/Basic/About-Topics.rst @@ -14,7 +14,7 @@ Publish/Subscribe ----------------- A publish/subscribe system is one in which there are producers of data (publishers) and consumers of data (subscribers). -The publishers and subscribers know how to contact each other through the concept of a "topic", which is a common name so that the entites can find each other. +The publishers and subscribers know how to contact each other through the concept of a "topic", which is a common name so that the entities can find each other. For instance, when you create a publisher, you must also give it a string that is the name of the topic; the same goes for the subscriber. Any publishers and subscribers that are on the same topic name can directly communicate with each other. There may be zero or more publishers and zero or more subscribers on any particular topic. diff --git a/source/Concepts/Intermediate/About-RQt.rst b/source/Concepts/Intermediate/About-RQt.rst index 3268b9a5950..b73ff96179a 100644 --- a/source/Concepts/Intermediate/About-RQt.rst +++ b/source/Concepts/Intermediate/About-RQt.rst @@ -56,7 +56,7 @@ RQt Components Structure RQt consists of two metapackages: -* *rqt* - core infrastucture modules. +* *rqt* - core infrastructure modules. * *rqt_common_plugins* - Commonly useful debugging tools. Advantage of RQt framework @@ -72,7 +72,7 @@ Compared to building your own GUIs from scratch: From system architecture's perspective: * Support multi-platform (basically wherever `QT `__ and ROS run) and multi-language (``Python``, ``C++``). -* Manageable lifecycle: RQt plugins using a common API makes maintainance & reuse easier. +* Manageable lifecycle: RQt plugins using a common API makes maintenance & reuse easier. Further Reading diff --git a/source/How-To-Guides/Ament-CMake-Documentation.rst b/source/How-To-Guides/Ament-CMake-Documentation.rst index bd32615ccc3..32242743e59 100644 --- a/source/How-To-Guides/Ament-CMake-Documentation.rst +++ b/source/How-To-Guides/Ament-CMake-Documentation.rst @@ -341,7 +341,7 @@ The macros have additional parameters: find_package(ament_cmake_gtest REQUIRED) ament_add_gtest(some_test - APPEND_ENV PATH=some/addtional/path/for/testing/resources) + APPEND_ENV PATH=some/additional/path/for/testing/resources) - ``APPEND_LIBRARY_DIRS``: append libraries so that they can be found by the linker at runtime. This can be achieved by setting environment variables like ``PATH`` on Windows and ``LD_LIBRARY_PATH`` on Linux, but this makes the call platform specific. diff --git a/source/How-To-Guides/Core-maintainer-guide.rst b/source/How-To-Guides/Core-maintainer-guide.rst index 504673c3069..6743129ec8c 100644 --- a/source/How-To-Guides/Core-maintainer-guide.rst +++ b/source/How-To-Guides/Core-maintainer-guide.rst @@ -6,7 +6,7 @@ ROS 2 Core Maintainer Guide =========================== -Each package in the ROS 2 core has one or more maintainers that are responsibile for the general health of the package. +Each package in the ROS 2 core has one or more maintainers that are responsible for the general health of the package. This guide gives some information about the responsibilities of a ROS 2 core package maintainer. .. contents:: Table of Contents diff --git a/source/How-To-Guides/Getting-Backtraces-in-ROS-2.rst b/source/How-To-Guides/Getting-Backtraces-in-ROS-2.rst index 401fa7ee9fb..2ec9f357a14 100755 --- a/source/How-To-Guides/Getting-Backtraces-in-ROS-2.rst +++ b/source/How-To-Guides/Getting-Backtraces-in-ROS-2.rst @@ -232,7 +232,7 @@ We will insert the GDB snippet here. prefix=['xterm -e gdb -ex run --args'] -This will provide a more interactive debbuging experience. +This will provide a more interactive debugging experience. Example usecase for debugging building upon ``'start_sync_slam_toolbox_node'`` - .. code-block:: python diff --git a/source/How-To-Guides/Installation-Troubleshooting.rst b/source/How-To-Guides/Installation-Troubleshooting.rst index e346b7bcfc6..e1faee17226 100644 --- a/source/How-To-Guides/Installation-Troubleshooting.rst +++ b/source/How-To-Guides/Installation-Troubleshooting.rst @@ -51,7 +51,7 @@ then you will need to update your firewall configuration to allow multicast usin sudo ufw allow in proto udp from 224.0.0.0/4 -You can check if the multicast flag is enabled for your network interface using the :code:`ifconfig` tool and looking for :code:`MULITCAST` in the flags section: +You can check if the multicast flag is enabled for your network interface using the :code:`ifconfig` tool and looking for :code:`MULTICAST` in the flags section: .. code-block:: bash @@ -242,7 +242,7 @@ To resolve this error, you will need to: rosdep install error ``homebrew: Failed to detect successful installation of [qt5]`` ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -While following the :doc:`Creating a workspace <../Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace>` tutorial, you might encounter the following error stating that ``rosdep`` failes to install Qt5. +While following the :doc:`Creating a workspace <../Tutorials/Beginner-Client-Libraries/Creating-A-Workspace/Creating-A-Workspace>` tutorial, you might encounter the following error stating that ``rosdep`` fails to install Qt5. .. code-block:: bash diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst index 94e099bed5a..ac6b5655a18 100644 --- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst +++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-CPP-Packages.rst @@ -109,7 +109,7 @@ If your ``CMakeLists.txt`` uses ``include_directories()``, then delete those cal # Delete calls to include_directories like this one! include_directories(include ${catkin_INCLUDE_DIRS}) -Add a call ``target_include_directories()`` for every library in your pacakage (`example `__). +Add a call ``target_include_directories()`` for every library in your package (`example `__). .. code-block:: cmake diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-Launch-Files.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-Launch-Files.rst index 24212f46c93..6d00fc71147 100644 --- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-Launch-Files.rst +++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-Launch-Files.rst @@ -314,7 +314,7 @@ New tags in ROS 2 set_env and unset_env ^^^^^^^^^^^^^^^^^^^^^ -See `env`_ tag decription. +See `env`_ tag description. push_ros_namespace ^^^^^^^^^^^^^^^^^^ diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-Python-Package-Example.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-Python-Package-Example.rst index 81f23a2d191..47e006a8919 100644 --- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-Python-Package-Example.rst +++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-Python-Package-Example.rst @@ -485,7 +485,7 @@ Remove the statement that imports ``rospy``. # Remove this import rospy -Rplace it with a statement that imports ``rclpy``. +Replace it with a statement that imports ``rclpy``. .. code-block:: Python @@ -807,7 +807,7 @@ Echo the message published by the node in the third terminal: You should see messages with the current time being published in the second terminal, and those same messages received in the third. -Refactor code to use ROS 2 convensions +Refactor code to use ROS 2 conventions -------------------------------------- You have successfully migrated a ROS 1 Python package to ROS 2! diff --git a/source/How-To-Guides/Using-Variants.rst b/source/How-To-Guides/Using-Variants.rst index 485d957f56e..12a680e4710 100644 --- a/source/How-To-Guides/Using-Variants.rst +++ b/source/How-To-Guides/Using-Variants.rst @@ -1,7 +1,7 @@ Using variants ============== -Metapackages do not provide software directly but depend on a group of other related packages to provide a convienent installation mechanism for the complete group of packages. [#]_ [#]_ +Metapackages do not provide software directly but depend on a group of other related packages to provide a convenient installation mechanism for the complete group of packages. [#]_ [#]_ Variants are a list of official metapackages for commonly useful groups of ROS packages. .. [#] https://wiki.debian.org/metapackage diff --git a/source/How-To-Guides/Using-ros2-param.rst b/source/How-To-Guides/Using-ros2-param.rst index 9351ce614f0..1f496ba10b2 100644 --- a/source/How-To-Guides/Using-ros2-param.rst +++ b/source/How-To-Guides/Using-ros2-param.rst @@ -64,7 +64,7 @@ This can be worked around by using the YAML syntax for explicitly setting string ros param set /my_node my_string '!!str off' Additionally, YAML supports heterogeneous lists, containing (say) a string, a boolean, and an integer. -However, ROS 2 parameters do not support heterogenous lists, so any YAML list that has multiple types will be interpreted as a string. +However, ROS 2 parameters do not support heterogeneous lists, so any YAML list that has multiple types will be interpreted as a string. Assuming that the parameter ``my_int_array`` on node ``my_node`` is of type integer array, the following will not work: .. code-block:: console diff --git a/source/Installation/DDS-Implementations/Install-Connext-University-Eval.rst b/source/Installation/DDS-Implementations/Install-Connext-University-Eval.rst index 4ffe5012c0c..68f6b7d72fb 100644 --- a/source/Installation/DDS-Implementations/Install-Connext-University-Eval.rst +++ b/source/Installation/DDS-Implementations/Install-Connext-University-Eval.rst @@ -19,7 +19,7 @@ The university license application can be found `here `__. * Download the version(s) to match your environment. * Contact license@rti.com for an evaluation license. diff --git a/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst b/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst index d551e85ac29..c2be93c7b61 100644 --- a/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst +++ b/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst @@ -186,7 +186,7 @@ Migrating a Wiki File In the case where there is a table of contents, the first useful tag may be an ``

`` tag. Similarly, the ROS wiki contains some footer text that starts with ``
`` and ends just above ```` that can also be removed. #. Convert your html file by running a PanDoc conversion between HTML and restructured text. - The following command coverts an HTML file to the equivalent reStructured text files: ``pandoc -f html -t rst urdf.html > URDF.rst``. + The following command converts an HTML file to the equivalent reStructured text files: ``pandoc -f html -t rst urdf.html > URDF.rst``. #. Attempt to build your new documentation using the ``make html`` command. There may be errors and warnings that you will need to address. @@ -202,7 +202,7 @@ Migrating a Wiki File #. For each image files downloaded update the image file links to point to the correct image directory for the ROS Docs. If any of the images require updating, or could be replaced with a `Mermaid `__ chart, please make this change. - Be aware that Mermaid.js is only supported in the core ROS 2 documenation currently. + Be aware that Mermaid.js is only supported in the core ROS 2 documentation currently. #. Once your document is complete add a table of contents to the top of your new rst document using the appropriate Sphinx commands. This block should replace any existing table of contents from the old ROS Wiki. diff --git a/source/The-ROS2-Project/Contributing/Developer-Guide.rst b/source/The-ROS2-Project/Contributing/Developer-Guide.rst index e0fb2b40b67..82527cec000 100644 --- a/source/The-ROS2-Project/Contributing/Developer-Guide.rst +++ b/source/The-ROS2-Project/Contributing/Developer-Guide.rst @@ -206,8 +206,8 @@ Examples: * This is an example of describing an extension point for a package -API Documetation for ROS Packages -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +API Documentation for ROS Packages +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ API documentation for all released ROS packages can be `found here `__. We recommend using `index.ros.org `_ to search through available ROS packages to find their documentation. diff --git a/source/The-ROS2-Project/ROSCon-Content.rst b/source/The-ROS2-Project/ROSCon-Content.rst index bcf5cb00dca..79fc05a65c4 100644 --- a/source/The-ROS2-Project/ROSCon-Content.rst +++ b/source/The-ROS2-Project/ROSCon-Content.rst @@ -116,7 +116,7 @@ The following `ROSCon `__ talks have been given on ROS 2 - `video `__ * - Building Foundation Model-powered Robots with ROS: A Survey - `video `__ - * - Scenic for ROS: A Probabilistic Programming Language for World Modelin... + * - Scenic for ROS: A Probabilistic Programming Language for World Modeling... - `video `__ * - Software Platform Design and SDK Development for ROS 2-based LG AI Com... - `video `__ diff --git a/source/Tutorials/Advanced/FastDDS-Configuration.rst b/source/Tutorials/Advanced/FastDDS-Configuration.rst index 61fdb10bb11..94e69449b17 100644 --- a/source/Tutorials/Advanced/FastDDS-Configuration.rst +++ b/source/Tutorials/Advanced/FastDDS-Configuration.rst @@ -453,7 +453,7 @@ In order to use the values in the XML file, the environment variable ``RMW_FASTR However, this entails **another caveat**: If ``RMW_FASTRTPS_USE_QOS_FROM_XML`` is set, but the XML file does not define ``publishMode`` or ``historyMemoryPolicy``, these attributes take the *Fast DDS* default value instead of the ``rmw_fastrtps`` default value. -This is important, especially for ``historyMemoryPolicy``, because the *Fast DDS* deafult value is ``PREALLOCATED`` which does not work with ROS2 topic data types. +This is important, especially for ``historyMemoryPolicy``, because the *Fast DDS* default value is ``PREALLOCATED`` which does not work with ROS2 topic data types. Therefore, in the example, a valid value for this policy has been explicitly set (``DYNAMIC``). diff --git a/source/Tutorials/Advanced/Reading-From-A-Bag-File-CPP.rst b/source/Tutorials/Advanced/Reading-From-A-Bag-File-CPP.rst index 88118b1dc54..ce984c6dc9e 100644 --- a/source/Tutorials/Advanced/Reading-From-A-Bag-File-CPP.rst +++ b/source/Tutorials/Advanced/Reading-From-A-Bag-File-CPP.rst @@ -204,7 +204,7 @@ Then, we can pass both these objects to the ``rclcpp::Serialization::deserialize serialization_.deserialize_message(&serialized_msg, ros_msg.get()); Finally, we publish the deserialized message and print out the xy coordinate to the terminal. -We also break out of the loop so that we publish the next message during the next timer calback. +We also break out of the loop so that we publish the next message during the next timer callback. .. code-block:: C++ diff --git a/source/Tutorials/Advanced/Security/Access-Controls.rst b/source/Tutorials/Advanced/Security/Access-Controls.rst index 511520dc9b7..ef30adae135 100644 --- a/source/Tutorials/Advanced/Security/Access-Controls.rst +++ b/source/Tutorials/Advanced/Security/Access-Controls.rst @@ -111,7 +111,7 @@ Sign the policy file This next command creates the new S/MIME signed policy file ``permissions.p7s`` from the updated XML file ``permissions.xml``. The file must be signed with the Permissions CA certificate, **which requires access to the Permission CA private key**. -If the private key has been protected, additional steps may be required to unlock and use it accoring to your security plan. +If the private key has been protected, additional steps may be required to unlock and use it according to your security plan. .. code-block:: bash diff --git a/source/Tutorials/Advanced/Security/Deployment-Guidelines.rst b/source/Tutorials/Advanced/Security/Deployment-Guidelines.rst index eab8b362285..430478790db 100644 --- a/source/Tutorials/Advanced/Security/Deployment-Guidelines.rst +++ b/source/Tutorials/Advanced/Security/Deployment-Guidelines.rst @@ -16,7 +16,7 @@ Background ---------- Typical deployment scenarios often involve shipping containerized applications, or packages, into remote systems. -Special attention should be payed when deploying security enabled applications, requiring users to reason about the sensitivity of packaged files. +Special attention should be paid when deploying security enabled applications, requiring users to reason about the sensitivity of packaged files. Complying with the `DDS Security standard `_, the ``sros2`` package provides a collection of utilities for managing security under ROS 2 environments in a highly modular and flexible fashion. @@ -124,7 +124,7 @@ Now, build the docker image with the command: Understanding the compose file ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -A compose configration file takes an image to create containers as services. +A compose configuration file takes an image to create containers as services. In this tutorial, three services are defined within the configuration: * *keystore-creator*: That, similarly to previous tutorials, it internally initializes a new keystore tree directory. diff --git a/source/Tutorials/Advanced/Security/Introducing-ros2-security.rst b/source/Tutorials/Advanced/Security/Introducing-ros2-security.rst index b0eef6e17ef..cce97f136f7 100644 --- a/source/Tutorials/Advanced/Security/Introducing-ros2-security.rst +++ b/source/Tutorials/Advanced/Security/Introducing-ros2-security.rst @@ -80,7 +80,7 @@ Selecting an alternate middleware If you choose not to use the default middleware implementation, be sure to :doc:`change your DDS implementation <../../../Installation/DDS-Implementations/>` before proceeding. ROS 2 allows you to change the DDS implementation at runtime. -See `how to work with mulitple RMW implementations <../../../How-To-Guides/Working-with-multiple-RMW-implementations>` to explore different middleware implementations. +See `how to work with multiple RMW implementations <../../../How-To-Guides/Working-with-multiple-RMW-implementations>` to explore different middleware implementations. Note that secure communication between vendors is not supported. diff --git a/source/Tutorials/Advanced/Security/The-Keystore.rst b/source/Tutorials/Advanced/Security/The-Keystore.rst index 8efba9e16ae..23aeba16aa3 100644 --- a/source/Tutorials/Advanced/Security/The-Keystore.rst +++ b/source/Tutorials/Advanced/Security/The-Keystore.rst @@ -24,8 +24,8 @@ Background Before proceeding ensure you have completed the :doc:`Introducing-ros2-security` tutorial. The ``sros2`` package can be used to create keys, certificates and policies necessary to enable ROS 2 security. -However, the security configuration is extrememly flexible. -A basic understanding of the ROS 2 Security Keystore will allow integration with an existing PKI (Public Key Infrastructure) and managment of sensitive key materials consistent with organizational policies. +However, the security configuration is extremely flexible. +A basic understanding of the ROS 2 Security Keystore will allow integration with an existing PKI (Public Key Infrastructure) and management of sensitive key materials consistent with organizational policies. Security Artifact Locations @@ -177,11 +177,11 @@ Secure processes (typically ROS nodes) run within a security enclave. In the simplest case, all the processes can be consolidated into the same enclave, and all processes will then use the same security policy. However, to apply different policies to different processes, the processes can use different security enclaves when starting. For more details about security enclaves, see the `design document `_. -The security enclave is specifed by using the ROS argument ``--enclave`` when running a node. +The security enclave is specified by using the ROS argument ``--enclave`` when running a node. **Each security enclave requires six files** in order to enable security. Each file **must** be named as defined below, and as outlined in the `DDS Security standard `_. -In order to avoid having mulitple copies of the same files, the ``sros2`` utilities create links for each enclave to the single governance policy, the Identity CA and Permissions CA descibed above. +In order to avoid having multiple copies of the same files, the ``sros2`` utilities create links for each enclave to the single governance policy, the Identity CA and Permissions CA described above. See the following six files within the ``listener`` enclave. Three are specific to this enclave, while three are generic to this ROS system: diff --git a/source/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.rst b/source/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.rst index ade973c487f..e1f4ddc7c8f 100644 --- a/source/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.rst +++ b/source/Tutorials/Beginner-CLI-Tools/Configuring-ROS2-Environment.rst @@ -111,7 +111,7 @@ If you don't want to have to source the setup file every time you open a new she C:\dev\ros2_{DISTRO}\local_setup.ps1 - PowerShell will request permission to run this script everytime a new shell is opened. + PowerShell will request permission to run this script every time a new shell is opened. To avoid that issue you can run: .. code-block:: console diff --git a/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-Python.rst b/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-Python.rst index 539aaa68f3b..6f919ed31da 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-Python.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Using-Parameters-In-A-Class-Python.rst @@ -299,7 +299,7 @@ There are four ways to accomplish this. 3.1 Change via the console ~~~~~~~~~~~~~~~~~~~~~~~~~~ -This part will use the knowledge you have gained from the :doc:`tutoral about parameters <../Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters>` and apply it to the node you have just created. +This part will use the knowledge you have gained from the :doc:`tutorial about parameters <../Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters>` and apply it to the node you have just created. Make sure the node is running: diff --git a/source/Tutorials/Demos/Real-Time-Programming.rst b/source/Tutorials/Demos/Real-Time-Programming.rst index 83739fbe92b..a669272a3a7 100644 --- a/source/Tutorials/Demos/Real-Time-Programming.rst +++ b/source/Tutorials/Demos/Real-Time-Programming.rst @@ -165,7 +165,7 @@ The requirements of a real-time system depend on the application, but let's say So, our average latency was really good in this run, but the maximum latency was unacceptable because it actually exceeded our update loop! What happened? We may be suffering from a non-deterministic scheduler. -If you're running a vanilla Linux system and you don't have the RT_PREEMPT kernel installed, you probably won't be able to meet the real-time goal we set for ourselves, because the Linux scheduler won't allow you to arbitrarily pre-empt threads at the user level. +If you're running a vanilla Linux system and you don't have the RT_PREEMPT kernel installed, you probably won't be able to meet the real-time goal we set for ourselves, because the Linux scheduler won't allow you to arbitrarily preempt threads at the user level. See the `realtime design article `__ for more information. diff --git a/source/Tutorials/Intermediate/Monitoring-For-Parameter-Changes-CPP.rst b/source/Tutorials/Intermediate/Monitoring-For-Parameter-Changes-CPP.rst index a0344295627..654fea47784 100644 --- a/source/Tutorials/Intermediate/Monitoring-For-Parameter-Changes-CPP.rst +++ b/source/Tutorials/Intermediate/Monitoring-For-Parameter-Changes-CPP.rst @@ -320,7 +320,7 @@ Now, to test monitoring of remote parameters, first run the newly-built paramete ros2 run cpp_parameter_event_handler parameter_event_handler -Next, from another teminal (with ROS initialized), run the parameter_blackboard demo application, as follows: +Next, from another terminal (with ROS initialized), run the parameter_blackboard demo application, as follows: .. code-block:: console diff --git a/source/Tutorials/Intermediate/Monitoring-For-Parameter-Changes-Python.rst b/source/Tutorials/Intermediate/Monitoring-For-Parameter-Changes-Python.rst index 87de5f52bec..a2065ac25b9 100644 --- a/source/Tutorials/Intermediate/Monitoring-For-Parameter-Changes-Python.rst +++ b/source/Tutorials/Intermediate/Monitoring-For-Parameter-Changes-Python.rst @@ -316,7 +316,7 @@ Now, to test monitoring of remote parameters, first run the newly-built paramete ros2 run python_parameter_event_handler node_with_parameters -Next, from another teminal (with ROS initialized), run the parameter_blackboard demo application, as follows: +Next, from another terminal (with ROS initialized), run the parameter_blackboard demo application, as follows: .. code-block:: console diff --git a/source/Tutorials/Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst b/source/Tutorials/Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst index d6bb5a901be..2fdbd3ed689 100644 --- a/source/Tutorials/Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst +++ b/source/Tutorials/Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst @@ -169,7 +169,7 @@ A configuration contains: * Displays + their properties * Tool properties -* The viewpoint and settings for the 3D visualzation +* The viewpoint and settings for the 3D visualization Views Panel ----------- diff --git a/source/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.rst b/source/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.rst index 6e62f49e4c8..cf4907b96e7 100644 --- a/source/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.rst +++ b/source/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.rst @@ -32,7 +32,7 @@ In this tutorial, you will learn how quaternions and conversion methods work in Prerequisites ------------- -However, this is not a hard requirement and you can stick to any other geometric transfromation library that suit you best. +However, this is not a hard requirement and you can stick to any other geometric transformation library that suit you best. You can take a look at libraries like `transforms3d `_, `scipy.spatial.transform `_, `pytransform3d `_, `numpy-quaternion `_ or `blender.mathutils `_. Components of a quaternion diff --git a/source/Tutorials/Intermediate/URDF/Exporting-an-URDF-File.rst b/source/Tutorials/Intermediate/URDF/Exporting-an-URDF-File.rst index 2614c4ef286..cc50c2d9fcf 100644 --- a/source/Tutorials/Intermediate/URDF/Exporting-an-URDF-File.rst +++ b/source/Tutorials/Intermediate/URDF/Exporting-an-URDF-File.rst @@ -37,7 +37,7 @@ However, we figured it would be helpful to produce a list of available URDF expo * `Gazebo SDFormat to URDF Parser `_ * `SDF to URDF Converter in Python `_ * `URDF to Webots Simulator Format `_ - * The `Blender Robotics Tools `_ respository includes a number of useful tools, including a tool to export `URDF files from Blender. `_ + * The `Blender Robotics Tools `_ repository includes a number of useful tools, including a tool to export `URDF files from Blender. `_ * `CoppeliaSim URDF Exporter `_ * `Isaac Sim URDF Exporter `_ From b0a330adc4fd6e35a6797f3187ab433d772a1a28 Mon Sep 17 00:00:00 2001 From: Katherine Scott Date: Tue, 4 Feb 2025 09:35:06 -0800 Subject: [PATCH 22/29] Suggested additions from contributor. (#4990) * Suggested additions from contributor. * I think this is the formatting it wants. * Update source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst Co-authored-by: Christophe Bedard Signed-off-by: Katherine Scott --------- Signed-off-by: Katherine Scott Co-authored-by: Christophe Bedard --- .../Contributing-To-ROS-2-Documentation.rst | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst b/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst index c2be93c7b61..feb32d8a288 100644 --- a/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst +++ b/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst @@ -278,6 +278,10 @@ Writing pages The ROS 2 documentation website uses the ``reStructuredText`` format, which is the default plaintext markup language used by Sphinx. This section is a brief introduction to ``reStructuredText`` concepts, syntax, and best practices. +When formatting your ``reStructuredText`` file **please make sure to write only one sentence per line as it makes reviewing and modifying your file much easier.** +Also, be mindful of the use of white space in your file! +The ROS 2 documentation linter will not accept pull requests with trailing white space. +We recommend that you enable automatic white space highlighting and or cleanup if your editor supports it. You can refer to `reStructuredText User Documentation `_ for a detailed technical specification. @@ -383,6 +387,13 @@ Images can be inserted using the ``.. image::`` directive. .. image:: images/turtlesim_follow1.png +Charts, Graphs, and Diagrams +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +The ROS 2 Documentation now supports charts, graphs, and diagrams written using `Mermaid Charts. `__ +We prefer that charts, graphs, and diagrams use Mermaid instead of static image files as it allows us to programmatically update and edit these resources as the project evolves. +Full documentation of the `Mermaid graph language syntax can be found on their website. `__ + References and Links ^^^^^^^^^^^^^^^^^^^^ From b9fb2b4758e8fc9c7c7e901beeb64ae10b68126a Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Thu, 6 Feb 2025 10:05:20 -0800 Subject: [PATCH 23/29] automatic spellcheck by codespell for common misspellings. (#4997) * automatic spellcheck by codespell for common misspellings. Signed-off-by: Tomoya Fujita * remove indention from the whitelist. Signed-off-by: Tomoya Fujita --------- Signed-off-by: Tomoya Fujita --- .github/workflows/test.yml | 17 +++++++++++++++++ Makefile | 3 +++ README.md | 9 +++++++++ codespell_whitelist.txt | 1 + requirements.txt | 1 + .../Code-Style-Language-Versions.rst | 8 ++++---- 6 files changed, 35 insertions(+), 4 deletions(-) create mode 100644 codespell_whitelist.txt diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index f1d478c3f61..c287342bbfc 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -37,6 +37,23 @@ jobs: - name: Lint run: make lint + spellcheck: + runs-on: ubuntu-22.04 + steps: + - name: Checkout + uses: actions/checkout@v4 + + - name: Setup Python + uses: actions/setup-python@v5 + with: + python-version: '3.10' + + - name: Install dependencies with pip + run: pip install --no-warn-script-location --user -r requirements.txt -c constraints.txt + + - name: Spellcheck + run: make spellcheck + build: needs: [test, lint] runs-on: ubuntu-22.04 diff --git a/Makefile b/Makefile index 5014099150f..e8a706bba0f 100644 --- a/Makefile +++ b/Makefile @@ -28,6 +28,9 @@ lint: test: doc8 --ignore D001 --ignore-path build +spellcheck: + git ls-files '*.md' '*.rst' | xargs codespell --ignore-words=codespell_whitelist.txt --skip="source/Releases/*" + linkcheck: $(BUILD) -b linkcheck $(OPTS) $(SOURCE) $(LINKCHECKDIR) @echo diff --git a/README.md b/README.md index 062f63b4759..3de74eb10be 100644 --- a/README.md +++ b/README.md @@ -51,6 +51,15 @@ For local testing of the current tree use: `sensible-browser build/html/index.html` +### Spelling Check + +To check the spelling, use: + +`make spellcheck` + +> [!NOTE] +> If that detects specific words that need to be ignored, add it to [codespell_whitelist](./codespell_whitelist.txt). + ### Deployment test To test building the multisite version deployed to the website use: diff --git a/codespell_whitelist.txt b/codespell_whitelist.txt new file mode 100644 index 00000000000..b7860a05aa8 --- /dev/null +++ b/codespell_whitelist.txt @@ -0,0 +1 @@ +empy diff --git a/requirements.txt b/requirements.txt index 2406de14841..d75e4c9adbf 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,3 +1,4 @@ +codespell doc8 docutils pip diff --git a/source/The-ROS2-Project/Contributing/Code-Style-Language-Versions.rst b/source/The-ROS2-Project/Contributing/Code-Style-Language-Versions.rst index c1284cb634d..5ee4cfafe68 100644 --- a/source/The-ROS2-Project/Contributing/Code-Style-Language-Versions.rst +++ b/source/The-ROS2-Project/Contributing/Code-Style-Language-Versions.rst @@ -166,9 +166,9 @@ Pointer Syntax Alignment Class Privacy Keywords ~~~~~~~~~~~~~~~~~~~~~~ -* Do not put 1 space before ``public:``, ``private:``, or ``protected:``, it is more consistent for all indentions to be a multiple of 2 +* Do not put 1 space before ``public:``, ``private:``, or ``protected:``, it is more consistent for all indentations to be a multiple of 2 - * rationale: most editors don't like indentions which are not a multiple of the (soft) tab size + * rationale: most editors don't like indentations which are not a multiple of the (soft) tab size * Use zero spaces before ``public:``, ``private:``, or ``protected:``, or 2 spaces * If you use 2 spaces before, indent other class statements by 2 additional spaces * Prefer zero spaces, i.e. ``public:``, ``private:``, or ``protected:`` in the same column as the class @@ -254,7 +254,7 @@ This is **not** OK: } -Use open braces rather than excessive indention, e.g. for distinguishing constructor code from constructor initializer lists +Use open braces rather than excessive indentation, e.g. for distinguishing constructor code from constructor initializer lists This is OK: @@ -364,7 +364,7 @@ Since there is not an existing CMake style guide we will define our own: * Use ``snake_case`` identifiers (variables, functions, macros). * Use empty ``else()`` and ``end...()`` commands. * No whitespace before ``(``\ 's. -* Use two spaces of indention, do not use tabs. +* Use two spaces of indentation, do not use tabs. * Do not use aligned indentation for parameters of multi-line macro invocations. Use two spaces only. * Prefer functions with ``set(PARENT_SCOPE)`` to macros. * When using macros prefix local variables with ``_`` or a reasonable prefix. From 3dbac70c85988929ac742c400df4d8cd45db9710 Mon Sep 17 00:00:00 2001 From: MariuszSzczepanikSpyrosoft <118888269+MariuszSzczepanikSpyrosoft@users.noreply.github.com> Date: Fri, 7 Feb 2025 19:32:53 +0100 Subject: [PATCH 24/29] Add ROS 1 to ROS 2 migration note for group parameter handling (#4983) * Add ROS 1 to ROS 2 migration note for group parameter handling Add information to help developers safely migrate parameter updates by highlighting that ROS 2's default set_parameters service behaves differently than ROS 1's dynamic_reconfigure regarding atomic updates. Points users to set_parameters_atomically service to maintain atomic behavior during migration. * Remove 'default' terminology from parameter services note * Adapt the structure of the migration guide from ROS 1 to ROS 2 * Refactor based on code review * Fix console code-block --- source/Concepts/Basic/About-Parameters.rst | 14 +---------- .../Migrating-Parameters.rst | 25 +++++++++++++++++++ 2 files changed, 26 insertions(+), 13 deletions(-) diff --git a/source/Concepts/Basic/About-Parameters.rst b/source/Concepts/Basic/About-Parameters.rst index c1378eb7154..e0f535e1e2d 100644 --- a/source/Concepts/Basic/About-Parameters.rst +++ b/source/Concepts/Basic/About-Parameters.rst @@ -119,16 +119,4 @@ Migrating from ROS 1 The :doc:`Launch file migration guide <../../How-To-Guides/Migrating-from-ROS1/Migrating-Launch-Files>` explains how to migrate ``param`` and ``rosparam`` launch tags from ROS 1 to ROS 2. -The :doc:`YAML parameter file migration guide <../../How-To-Guides/Migrating-from-ROS1/Migrating-Parameters>` explains how to migrate parameter files from ROS 1 to ROS 2. - -In ROS 1, the ``roscore`` acted like a global parameter blackboard where all nodes could get and set parameters. -Since there is no central ``roscore`` in ROS 2, that functionality no longer exists. -The recommended approach in ROS 2 is to use per-node parameters that are closely tied to the nodes that use them. -If a global blackboard is still needed, it is possible to create a dedicated node for this purpose. -ROS 2 ships with one in the ``ros-{DISTRO}-demo-nodes-cpp`` package called ``parameter_blackboard``; it can be run with: - -.. code-block:: console - - ros2 run demo_nodes_cpp parameter_blackboard - -The code for the ``parameter_blackboard`` is `here `__. +The :doc:`Migration guide <../../How-To-Guides/Migrating-from-ROS1/Migrating-Parameters>` explains how to migrate parameter from ROS 1 to ROS 2. diff --git a/source/How-To-Guides/Migrating-from-ROS1/Migrating-Parameters.rst b/source/How-To-Guides/Migrating-from-ROS1/Migrating-Parameters.rst index 5168f906df4..af99c20e596 100644 --- a/source/How-To-Guides/Migrating-from-ROS1/Migrating-Parameters.rst +++ b/source/How-To-Guides/Migrating-from-ROS1/Migrating-Parameters.rst @@ -18,6 +18,21 @@ In ROS 2, parameters are associated per node and are configurable at runtime wit * See :doc:`ROS 2 CLI usage <../../Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters>` for a better understanding of how the CLI tools work and its differences with ROS 1 tooling. +Global Parameter Server +----------------------- + +In ROS 1, the ``roscore`` acted like a global parameter blackboard where all nodes could get and set parameters. +Since there is no central ``roscore`` in ROS 2, that functionality no longer exists. +The recommended approach in ROS 2 is to use per-node parameters that are closely tied to the nodes that use them. +If a global blackboard is still needed, it is possible to create a dedicated node for this purpose. +ROS 2 ships with one in the ``ros-{DISTRO}-demo-nodes-cpp`` package called ``parameter_blackboard``; it can be run with: + +.. code-block:: console + + ros2 run demo_nodes_cpp parameter_blackboard + +The code for the ``parameter_blackboard`` is `here `__. + Migrating YAML Parameter Files ------------------------------ @@ -74,3 +89,13 @@ Some features of ROS 1 parameters files do not exist in ROS 2: - Mixed types in a list is not supported yet (`related issue `_) - ``deg`` and ``rad`` substitutions are not supported + + +Parameter Atomic Operation +-------------------------- + +When migrating parameter groups from ROS 1 to ROS 2, there are important differences to consider. +In ROS 1, ``dynamic_reconfigure`` handles parameter groups atomically, meaning all parameters in a reconfiguration request are processed together in a single callback. +In ROS 2, the ``set_parameters`` service processes each parameter individually, which may lead to multiple callback invocations. +To maintain atomic behavior when migrating from ``dynamic_reconfigure``, use the ``set_parameters_atomically`` service, which validates and applies all parameters as a single operation. +If any parameter fails validation, no parameters will be updated. From 67f669dc66802fac8f89514f6960555dde5282a3 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Mon, 10 Feb 2025 09:33:18 -0800 Subject: [PATCH 25/29] use ubuntu:jammy for container, otherwise doc8 failes to start. (#5007) Signed-off-by: Tomoya.Fujita --- .devcontainer/devcontainer.json | 2 +- docker/image/Dockerfile | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json index 4c3c2ceac60..619e5e5eb0e 100644 --- a/.devcontainer/devcontainer.json +++ b/.devcontainer/devcontainer.json @@ -5,7 +5,7 @@ }, "workspaceMount": "source=${localWorkspaceFolder},target=/tmp/doc_repository,type=bind", "workspaceFolder": "/tmp/doc_repository", - "postCreateCommand": "pip3 install --no-warn-script-location --user -r requirements.txt -c constraints.txt --break-system-packages", + "postCreateCommand": "pip3 install --no-warn-script-location --user -r requirements.txt -c constraints.txt", "features": { "ghcr.io/devcontainers/features/git:1": {} }, diff --git a/docker/image/Dockerfile b/docker/image/Dockerfile index 28ee3e2bea7..7c0988f9090 100644 --- a/docker/image/Dockerfile +++ b/docker/image/Dockerfile @@ -3,7 +3,7 @@ # # docker build -f docker/image/Dockerfile . -FROM ubuntu:noble +FROM ubuntu:jammy ARG user=rosindex ARG uid=1000 From 4ec9fba7c934053c065632a8d69f9ad0af096bda Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Mon, 10 Feb 2025 09:38:20 -0800 Subject: [PATCH 26/29] add documentation about spell check by codespell. (#5005) Signed-off-by: Tomoya.Fujita --- Makefile | 2 +- codespell.cfg | 15 ++++++++++++ codespell_whitelist.txt | 3 +++ .../Contributing-To-ROS-2-Documentation.rst | 23 ++++++++++++++++++- .../Deploying-ROS-2-on-IBM-Cloud.rst | 2 +- 5 files changed, 42 insertions(+), 3 deletions(-) create mode 100644 codespell.cfg diff --git a/Makefile b/Makefile index e8a706bba0f..b5d0ece7c46 100644 --- a/Makefile +++ b/Makefile @@ -29,7 +29,7 @@ test: doc8 --ignore D001 --ignore-path build spellcheck: - git ls-files '*.md' '*.rst' | xargs codespell --ignore-words=codespell_whitelist.txt --skip="source/Releases/*" + git ls-files '*.md' '*.rst' | xargs codespell --config codespell.cfg linkcheck: $(BUILD) -b linkcheck $(OPTS) $(SOURCE) $(LINKCHECKDIR) diff --git a/codespell.cfg b/codespell.cfg new file mode 100644 index 00000000000..e34631dee88 --- /dev/null +++ b/codespell.cfg @@ -0,0 +1,15 @@ +[codespell] + +# Enable built-in dictionaries/rules. +# See more details for https://github.com/codespell-project/codespell/tree/main/codespell_lib/data. +builtin = clear,rare,informal,code + +# Ignore words listed in this file. +ignore-words = codespell_whitelist.txt + +# Skip checking files in this directory. +# This folder is ignored for a couple of reasons. +# *-Changelog.rst files are generated by commit history that could include some misspellings, +# but we should keep the original commit messages here. +# Besides, it includes names of authors and contributors, which compile up the false alarms. +skip = source/Releases/* diff --git a/codespell_whitelist.txt b/codespell_whitelist.txt index b7860a05aa8..918813b83c1 100644 --- a/codespell_whitelist.txt +++ b/codespell_whitelist.txt @@ -1 +1,4 @@ empy +ws +lets +jupyter diff --git a/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst b/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst index feb32d8a288..5c656f264dc 100644 --- a/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst +++ b/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst @@ -99,12 +99,33 @@ This is the recommended way to test out local changes. The build process can take some time. To see the output, open ``build/html/index.html`` in your browser. -You can also run the documentation tests locally (using `doc8 `_) with the following command: + +Checking / Testing the site +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +You can run the documentation tests locally (using `doc8 `_) with the following command: .. code-block:: console make test +You can run the documentation linter locally (using `sphinx-lint `_) with the following command: + +.. code-block:: console + + make lint + +You can run the documentation spell checker locally (using `codespell `_) with the following command: + +.. code-block:: console + + make spellcheck + +.. note:: + + If that detects specific words that need to be ignored, add it to `codespell_whitelist `_ . + + View Site Through Github CI ^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/source/Tutorials/Miscellaneous/Deploying-ROS-2-on-IBM-Cloud.rst b/source/Tutorials/Miscellaneous/Deploying-ROS-2-on-IBM-Cloud.rst index 708cf5d0661..47010283873 100644 --- a/source/Tutorials/Miscellaneous/Deploying-ROS-2-on-IBM-Cloud.rst +++ b/source/Tutorials/Miscellaneous/Deploying-ROS-2-on-IBM-Cloud.rst @@ -280,7 +280,7 @@ So now we have the full pipeline working, from creating the Dockerfile, all the way to deploying it and seeing it work on IBM Cloud. But, what if we want to use a custom set of packages we (or someone else) created? -Well that all has to do with how you set-up your Dockerfile. Lets use +Well that all has to do with how you set-up your Dockerfile. Let's use the example provided by ROS 2 `here `__. Create a new directory with a new Dockerfile (or overwrite the existing one) and add the following in it (or download the file From 3ac77be098dbd56d6bddcbcf207a304f82cc154d Mon Sep 17 00:00:00 2001 From: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> Date: Tue, 11 Feb 2025 18:53:22 +0100 Subject: [PATCH 27/29] Add tutorial on Node Interfaces Template Class (#4992) MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Created Using-Node-Interfaces-Template-Class.rst and modified Intermediate.rst * fixing lint errors * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: Alejandro Hernández Cordero Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: Katherine Scott Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: Katherine Scott Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Update source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst Co-authored-by: yadunund Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> * Implemented Suggested Changes --------- Signed-off-by: Nikos Tziaros <33639811+NickTziaros@users.noreply.github.com> Co-authored-by: Alejandro Hernández Cordero Co-authored-by: Katherine Scott Co-authored-by: yadunund --- source/Tutorials/Intermediate.rst | 1 + .../Using-Node-Interfaces-Template-Class.rst | 242 ++++++++++++++++++ 2 files changed, 243 insertions(+) create mode 100644 source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst diff --git a/source/Tutorials/Intermediate.rst b/source/Tutorials/Intermediate.rst index 583bac4d6fa..65d453c187a 100644 --- a/source/Tutorials/Intermediate.rst +++ b/source/Tutorials/Intermediate.rst @@ -10,6 +10,7 @@ Intermediate Intermediate/Writing-an-Action-Server-Client/Py Intermediate/Writing-a-Composable-Node Intermediate/Composition + Intermediate/Using-Node-Interfaces-Template-Class Intermediate/Monitoring-For-Parameter-Changes-CPP Intermediate/Monitoring-For-Parameter-Changes-Python Intermediate/Launch/Launch-Main diff --git a/source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst b/source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst new file mode 100644 index 00000000000..74006e81288 --- /dev/null +++ b/source/Tutorials/Intermediate/Using-Node-Interfaces-Template-Class.rst @@ -0,0 +1,242 @@ +Using the Node Interfaces Template Class (C++) +============================================== + +**Goal:** Learn how to access ``Node`` information using ``rclcpp::NodeInterfaces<>`` + +**Tutorial level:** Intermediate + +**Time:** 10 minutes + +.. contents:: Table of Contents + :depth: 2 + :local: + + +Overview +-------- + +Not all ROS Nodes are created equally! +the ``rclcpp::Node`` and ``rclcpp_lifecycle::LifecycleNode`` classes do not share an inheritance tree, which means ROS developers can run into compile time type issues when they want to write a function that takes in a ROS node pointer as an argument. +To address this issue, ``rclcpp`` includes the ``rclcpp::NodeInterfaces<>`` template type that should be used as the preferred convention for passing for both conventional and lifecycle nodes to functions. +This `ROSCon 2023 lightning talk `_ summarizes the issue and remedy succinctly. +The following tutorial will show you how to use ``rclcpp::NodeInterfaces<>`` as reliable and compact interface for all ROS node types. + +The ``rclcpp::NodeInterfaces<>`` template class provides a compact and efficient way to manage Node Interfaces in ROS 2. This is particularly useful when working with different types of ``Nodes``, such as ``rclcpp::Node`` and ``rclcpp_lifecycle::LifecycleNode``, which do not share the same inheritance tree. + +1 Accessing Node Information with a ``SharedPtr`` +------------------------------------------------- + +In the example below, we create a simple ``Node`` called ``Simple_Node`` and define a function ``node_info`` that accepts a ``SharedPtr`` to the ``Node``. The function retrieves and prints the name of the ``Node``. + +.. code-block:: c++ + + #include + #include "rclcpp/rclcpp.hpp" + + void node_info(rclcpp::Node::SharedPtr node) + { + RCLCPP_INFO(node->get_logger(), "Node name: %s", node->get_name()); + } + + class SimpleNode : public rclcpp::Node + { + public: + SimpleNode(const std::string & node_name) + : Node(node_name) + { + } + }; + + int main(int argc, char * argv[]) + { + rclcpp::init(argc, argv); + auto node = std::make_shared("Simple_Node"); + node_info(*node); + } + +Output: + +.. code-block:: console + + [INFO] [Simple_Node]: Node name: Simple_Node + +While this approach works well for arguments of type ``rclcpp::Node``, it does not work for other node types like ``rclcpp_lifecycle::LifecycleNode``. + +2 Explicitly pass ``rclcpp::node_interfaces`` +--------------------------------------------- + +A more robust approach, applicable to all node types, is to explicitly pass ``rclcpp::node_interfaces`` as function arguments, as demonstrated in the example below. +In the example that follows, we create function called ``node_info`` that take as arguments two ``rclcpp::node_interfaces``, ``NodeBaseInterface`` and ``NodeLoggingInterface`` and prints the ``Node`` name. +We then create two nodes of type ``rclcpp_lifecycle::LifecycleNode`` and ``rclcpp::Node`` and pass their interfaces in ``node_info``. + +.. code-block:: c++ + + void node_info(std::shared_ptr base_interface, + std::shared_ptr logging_interface) + { + RCLCPP_INFO(logging_interface->get_logger(), "Node name: %s", base_interface->get_name()); + } + + class SimpleNode : public rclcpp::Node + { + public: + SimpleNode(const std::string & node_name) + : Node(node_name) + { + } + }; + + class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode + { + public: + explicit LifecycleTalker(const std::string & node_name, bool intra_process_comms = false) + : rclcpp_lifecycle::LifecycleNode(node_name, + rclcpp::NodeOptions().use_intra_process_comms(intra_process_comms)) + {} + } + + int main(int argc, char * argv[]) + { + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor exe; + auto node = std::make_shared("Simple_Node"); + auto lc_node = std::make_shared("Simple_LifeCycle_Node"); + node_info(node->get_node_base_interface(),node->get_node_logging_interface()); + node_info(lc_node->get_node_base_interface(),lc_node->get_node_logging_interface()); + } + +.. code-block:: console + + [INFO] [Simple_Node]: Node name: Simple_Node + [INFO] [Simple_LifeCycle_Node]: Node name: Simple_LifeCycle_Node + +As functions grow in complexity, the number of ``rclcpp::node_interfaces`` arguments also increases, leading to readability and compactness issues. +To make the code more flexible and compatible with different node types, we use ``rclcpp::NodeInterfaces<>``. + +3 Using ``rclcpp::NodeInterfaces<>`` +------------------------------------ + +The recommended way of accessing a ``Node`` type's information is through the ``Node Interfaces``. + +Below, similar to the previous example, a ``rclcpp_lifecycle::LifecycleNode`` and a ``rclcpp::Node`` are created. + +.. code-block:: c++ + + #include + #include + #include + #include "lifecycle_msgs/msg/transition.hpp" + #include "rclcpp/rclcpp.hpp" + #include "rclcpp_lifecycle/lifecycle_node.hpp" + #include "rclcpp_lifecycle/lifecycle_publisher.hpp" + #include "rclcpp/node_interfaces/node_interfaces.hpp" + + using MyNodeInterfaces = + rclcpp::node_interfaces::NodeInterfaces; + + void node_info(MyNodeInterfaces interfaces) + { + auto base_interface = interfaces.get_node_base_interface(); + auto logging_interface = interfaces.get_node_logging_interface(); + RCLCPP_INFO(logging_interface->get_logger(), "Node name: %s", base_interface->get_name()); + } + + class SimpleNode : public rclcpp::Node + { + public: + SimpleNode(const std::string & node_name) + : Node(node_name) + { + } + }; + + class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode + { + public: + explicit LifecycleTalker(const std::string & node_name, bool intra_process_comms = false) + : rclcpp_lifecycle::LifecycleNode(node_name, + rclcpp::NodeOptions().use_intra_process_comms(intra_process_comms)) + {} + } + + int main(int argc, char * argv[]) + { + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor exe; + auto node = std::make_shared("Simple_Node"); + auto lc_node = std::make_shared("Simple_LifeCycle_Node"); + node_info(*node); + node_info(*lc_node); + } + +Output: + +.. code-block:: console + + [INFO] [Simple_Node]: Node name: Simple_Node + [INFO] [Simple_LifeCycle_Node]: Node name: Simple_LifeCycle_Node + +3.1 Examine the code +~~~~~~~~~~~~~~~~~~~~ + +.. code-block:: c++ + + using MyNodeInterfaces = + rclcpp::node_interfaces::NodeInterfaces; + + void node_info(MyNodeInterfaces interfaces) + { + auto base_interface = interfaces.get_node_base_interface(); + auto logging_interface = interfaces.get_node_logging_interface(); + RCLCPP_INFO(logging_interface->get_logger(), "Node name: %s", base_interface->get_name()); + } + +Instead of accepting ``SharedPtr`` or a node interface, this function takes a reference to a ``rclcpp::node_interfaces::NodeInterfaces`` object. +Another advantage of using this approach is the support for implicit conversion of node-like objects. +This means that it is possible to directly pass any node-like object to a function expecting a ``rclcpp::node_interfaces::NodeInterfaces`` object. + +It extracts: + +* ``NodeBaseInterface`` Provides basic node functionalities. +* ``NodeLoggingInterface`` Enables logging. + +Then, it retrieves and prints the node name. + +.. code-block:: c++ + + class SimpleNode : public rclcpp::Node + { + public: + SimpleNode(const std::string & node_name) + : Node(node_name) + { + } + }; + + class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode + { + public: + explicit LifecycleTalker(const std::string & node_name, bool intra_process_comms = false) + : rclcpp_lifecycle::LifecycleNode(node_name, + rclcpp::NodeOptions().use_intra_process_comms(intra_process_comms)) + {} + } + +Next, we create a ``rclcpp::Node`` as well as a ``rclcpp_lifecycle::LifecycleNode`` class. The ``rclcpp_lifecycle::LifecycleNode`` class often includes functions for the state transitions ``Unconfigured``, ``Inactive``, ``Active``, and ``Finalized``. However, they are not included for demonstration purposes. + +.. code-block:: c++ + + int main(int argc, char * argv[]) + { + rclcpp::init(argc, argv); + rclcpp::executors::SingleThreadedExecutor exe; + auto node = std::make_shared("Simple_Node"); + auto lc_node = std::make_shared("Simple_LifeCycle_Node"); + node_info(*node); + node_info(*lc_node); + } + +In the main function, a ``SharedPtr`` to both ``rclcpp_lifecycle::LifecycleNode`` and ``rclcpp::Node`` is created. +The function declared above is called once with each node type as an argument. + +.. note:: The ``SharedPtr`` needs to be dereferenced as the template accepts a reference to the ``NodeT`` object. From cc07913d462d4e702b27ab1403f0a97fb9ed2c91 Mon Sep 17 00:00:00 2001 From: "David V. Lu!!" Date: Tue, 11 Feb 2025 20:08:03 -0500 Subject: [PATCH 28/29] Clean up sentences (white space changes only) (#5001) * Clean up sentences (white space changes only) * Roll back Releases changes --- .../Concepts/Basic/About-Client-Libraries.rst | 3 +- source/Concepts/Basic/About-Interfaces.rst | 10 +- source/Concepts/Basic/About-Parameters.rst | 9 +- source/Concepts/Basic/About-Topics.rst | 5 +- .../Intermediate/About-Cross-Compilation.rst | 4 +- .../About-Different-Middleware-Vendors.rst | 13 +- .../Concepts/Intermediate/About-Executors.rst | 13 +- source/Contact.rst | 11 +- source/Glossary.rst | 12 +- .../Ament-CMake-Documentation.rst | 10 +- .../Ament-CMake-Python-Documentation.rst | 4 +- source/How-To-Guides/DDS-tuning.rst | 3 +- .../Installation-Troubleshooting.rst | 9 +- .../Installing-on-Raspberry-Pi.rst | 3 +- source/How-To-Guides/ROS-2-IDEs.rst | 6 +- .../Releasing/Index-Your-Packages.rst | 12 +- ...n-single-or-separate-docker-containers.rst | 6 +- ...ROS-2-with-VSCode-and-Docker-Container.rst | 3 +- .../How-To-Guides/Topics-Services-Actions.rst | 15 +- .../How-To-Guides/Using-Python-Packages.rst | 3 +- ...king-with-multiple-RMW-implementations.rst | 9 +- source/Package-Docs.rst | 6 +- .../Related-Projects/Nvidia-ROS2-Projects.rst | 6 +- .../Visualizing-ROS-2-Data-With-Foxglove.rst | 28 +++- .../Contributing/Build-Farms.rst | 37 +++-- .../Code-Style-Language-Versions.rst | 7 +- .../Contributing-To-ROS-2-Documentation.rst | 16 +- .../Contributing/Developer-Guide.rst | 6 +- .../Contributing/Quality-Guide.rst | 3 +- .../Contributing/Windows-Tips-and-Tricks.rst | 9 +- source/The-ROS2-Project/Feature-Ideas.rst | 4 +- source/The-ROS2-Project/Features.rst | 3 +- source/The-ROS2-Project/Marketing.rst | 5 +- source/The-ROS2-Project/Roadmap.rst | 3 +- .../Advanced/Ament-Lint-For-Clean-Code.rst | 9 +- .../Discovery-Server/Discovery-Server.rst | 13 +- .../Security/Deployment-Guidelines.rst | 3 +- .../Advanced/Security/Examine-Traffic.rst | 3 +- .../Simulators/Webots/Installation-MacOS.rst | 3 +- .../Webots/Installation-Windows.rst | 3 +- .../Webots/Simulation-Supervisor.rst | 3 +- .../Topic-Statistics-Tutorial.rst | 5 +- .../Understanding-ROS2-Nodes.rst | 3 +- .../Beginner-Client-Libraries/Pluginlib.rst | 6 +- .../Demos/Intra-Process-Communication.rst | 31 +++- source/Tutorials/Demos/Quality-of-Service.rst | 3 +- .../Tutorials/Demos/Real-Time-Programming.rst | 15 +- source/Tutorials/Demos/dummy-robot-demo.rst | 21 ++- .../Marker-Display-types.rst | 34 ++-- .../RViz-Custom-Display.rst | 18 +- .../RViz-Custom-Panel/RViz-Custom-Panel.rst | 3 +- .../RViz/RViz-User-Guide/RViz-User-Guide.rst | 18 +- source/Tutorials/Intermediate/Rosdep.rst | 3 +- .../Tutorials/Intermediate/Testing/Python.rst | 3 +- .../Intermediate/Testing/Testing-Main.rst | 54 ++++-- .../Tf2/Quaternion-Fundamentals.rst | 3 +- .../Tf2/Time-Travel-With-Tf2-Cpp.rst | 9 +- .../Writing-A-Tf2-Static-Broadcaster-Cpp.rst | 3 +- .../Writing-A-Tf2-Static-Broadcaster-Py.rst | 3 +- ...d-Collision-Properties-to-a-URDF-Model.rst | 6 +- ...ilding-a-Movable-Robot-Model-with-URDF.rst | 3 +- ...ual-Robot-Model-with-URDF-from-Scratch.rst | 3 +- .../URDF/Exporting-an-URDF-File.rst | 3 +- .../Using-URDF-with-Robot-State-Publisher.rst | 1 + .../Using-Xacro-to-Clean-Up-a-URDF-File.rst | 3 +- .../Writing-an-Action-Server-Client/Cpp.rst | 6 +- .../Writing-an-Action-Server-Client/Py.rst | 3 +- ...ding-ROS2-Package-with-eclipse-2021-06.rst | 3 +- ...g-Realtime-rt_preempt-kernel-for-ROS-2.rst | 16 +- .../Deploying-ROS-2-on-IBM-Cloud.rst | 157 +++++++++--------- source/index.rst | 3 +- 71 files changed, 501 insertions(+), 274 deletions(-) diff --git a/source/Concepts/Basic/About-Client-Libraries.rst b/source/Concepts/Basic/About-Client-Libraries.rst index 1079ece209d..9780e0320c7 100644 --- a/source/Concepts/Basic/About-Client-Libraries.rst +++ b/source/Concepts/Basic/About-Client-Libraries.rst @@ -77,7 +77,8 @@ While the C++ and Python client libraries are maintained by the core ROS 2 team, * `C `__ ``rclc`` does not put a layer on top of rcl but complements rcl to make rcl+rclc a feature-complete client library in C. See `micro.ros.org `__ for tutorials. * `JVM and Android `__ Java and Android bindings for ROS 2. * `.NET Core, UWP and C# `__ This is a collection of projects (bindings, code generator, examples and more) for writing ROS 2 applications for .NET Core and .NET Standard. -* `Node.js `__ rclnodejs is a Node.js client for ROS 2. It provides a simple and easy JavaScript API for ROS 2 programming. +* `Node.js `__ rclnodejs is a Node.js client for ROS 2. + It provides a simple and easy JavaScript API for ROS 2 programming. * `Rust `__ This is a set of projects (the rclrs client library, code generator, examples and more) that enables developers to write ROS 2 applications in Rust. * `Flutter and Dart `__ Flutter and Dart bindings for ROS 2. diff --git a/source/Concepts/Basic/About-Interfaces.rst b/source/Concepts/Basic/About-Interfaces.rst index 228fc1789f6..ed72f28c0c9 100644 --- a/source/Concepts/Basic/About-Interfaces.rst +++ b/source/Concepts/Basic/About-Interfaces.rst @@ -18,9 +18,13 @@ This description makes it easy for ROS tools to automatically generate source co In this document we will describe the supported types: -* msg: ``.msg`` files are simple text files that describe the fields of a ROS message. They are used to generate source code for messages in different languages. -* srv: ``.srv`` files describe a service. They are composed of two parts: a request and a response. The request and response are message declarations. -* action: ``.action`` files describe actions. They are composed of three parts: a goal, a result, and feedback. +* msg: ``.msg`` files are simple text files that describe the fields of a ROS message. + They are used to generate source code for messages in different languages. +* srv: ``.srv`` files describe a service. + They are composed of two parts: a request and a response. + The request and response are message declarations. +* action: ``.action`` files describe actions. + They are composed of three parts: a goal, a result, and feedback. Each part is a message declaration itself. Messages diff --git a/source/Concepts/Basic/About-Parameters.rst b/source/Concepts/Basic/About-Parameters.rst index e0f535e1e2d..d2f5a00ce65 100644 --- a/source/Concepts/Basic/About-Parameters.rst +++ b/source/Concepts/Basic/About-Parameters.rst @@ -89,11 +89,14 @@ The services that are created by default are: * ``/node_name/get_parameters``: Uses a service type of ``rcl_interfaces/srv/GetParameters``. Given a list of parameter names, returns a list of parameter values associated with the parameters. * ``/node_name/list_parameters``: Uses a service type of ``rcl_interfaces/srv/ListParameters``. - Given an optional list of parameter prefixes, returns a list of the available parameters with that prefix. If the prefixes are empty, returns all parameters. + Given an optional list of parameter prefixes, returns a list of the available parameters with that prefix. + If the prefixes are empty, returns all parameters. * ``/node_name/set_parameters``: Uses a service type of ``rcl_interfaces/srv/SetParameters``. - Given a list of parameter names and values, attempts to set the parameters on the node. Returns a list of results from trying to set each parameter; some of them may have succeeded and some may have failed. + Given a list of parameter names and values, attempts to set the parameters on the node. + Returns a list of results from trying to set each parameter; some of them may have succeeded and some may have failed. * ``/node_name/set_parameters_atomically``: Uses a service type of ``rcl_interfaces/srv/SetParametersAtomically``. - Given a list of parameter names and values, attempts to set the parameters on the node. Returns a single result from trying to set all parameters, so if one failed, all of them failed. + Given a list of parameter names and values, attempts to set the parameters on the node. + Returns a single result from trying to set all parameters, so if one failed, all of them failed. Setting initial parameter values when running a node ---------------------------------------------------- diff --git a/source/Concepts/Basic/About-Topics.rst b/source/Concepts/Basic/About-Topics.rst index 16560d43f40..23081a69b03 100644 --- a/source/Concepts/Basic/About-Topics.rst +++ b/source/Concepts/Basic/About-Topics.rst @@ -48,4 +48,7 @@ That has two meanings in this context: Then the code will ensure that ``field1`` is always an unsigned integer and that ``field2`` is always a string. -2. The semantics of each field are well-defined. There is no automated mechanism to ensure this, but all of the core ROS types have strong semantics associated with them. For instance, the IMU message contains a 3-dimensional vector for the measured angular velocity, and each of the dimensions is specified to be in radians/second. Other interpretations should not be placed into the message. +2. The semantics of each field are well-defined. + There is no automated mechanism to ensure this, but all of the core ROS types have strong semantics associated with them. + For instance, the IMU message contains a 3-dimensional vector for the measured angular velocity, and each of the dimensions is specified to be in radians/second. + Other interpretations should not be placed into the message. diff --git a/source/Concepts/Intermediate/About-Cross-Compilation.rst b/source/Concepts/Intermediate/About-Cross-Compilation.rst index 91f1eb743c8..d70eb66e664 100644 --- a/source/Concepts/Intermediate/About-Cross-Compilation.rst +++ b/source/Concepts/Intermediate/About-Cross-Compilation.rst @@ -22,7 +22,9 @@ How does it work ? Cross-compiling simple software (e.g. no dependencies on external libraries) is relatively simple and only requiring a cross-compiler toolchain to be used instead of the native toolchain. There are a number of factors which make this process more complex: - - The software being built must support the target architecture. Architecture specific code must be properly isolated and enabled during the build according to the target architecture. Examples include assembly code. + - The software being built must support the target architecture. + Architecture specific code must be properly isolated and enabled during the build according to the target architecture. + Examples include assembly code. - All dependencies (e.g. libraries) must be present, either as pre-built or cross-compiled packages, before the target software using them is cross-compiled. - When building software stacks (as opposed to standalone software) using build tools (e.g. colcon), it is expected that the build tool provides a mechanism to allow the developer to enable cross-compilation on the underlying build system used by each piece of software in the stack. diff --git a/source/Concepts/Intermediate/About-Different-Middleware-Vendors.rst b/source/Concepts/Intermediate/About-Different-Middleware-Vendors.rst index 8c1b9ae4338..47ad1d950f5 100644 --- a/source/Concepts/Intermediate/About-Different-Middleware-Vendors.rst +++ b/source/Concepts/Intermediate/About-Different-Middleware-Vendors.rst @@ -37,19 +37,24 @@ Supported RMW implementations * - eProsima *Fast DDS* - Apache 2 - ``rmw_fastrtps_cpp`` - - Full support. Default RMW. Packaged with binary releases. + - Full support. + Default RMW. + Packaged with binary releases. * - Eclipse *Cyclone DDS* - Eclipse Public License v2.0 - ``rmw_cyclonedds_cpp`` - - Full support. Packaged with binary releases. + - Full support. + Packaged with binary releases. * - RTI *Connext DDS* - commercial, research - ``rmw_connextdds`` - - Full support. Support included in binaries, but Connext installed separately. + - Full support. + Support included in binaries, but Connext installed separately. * - GurumNetworks *GurumDDS* - commercial - ``rmw_gurumdds_cpp`` - - Community support. Support included in binaries, but GurumDDS installed separately. + - Community support. + Support included in binaries, but GurumDDS installed separately. For practical information on working with multiple RMW implementations, see the :doc:`"Working with multiple RMW implementations" <../../How-To-Guides/Working-with-multiple-RMW-implementations>` tutorial. diff --git a/source/Concepts/Intermediate/About-Executors.rst b/source/Concepts/Intermediate/About-Executors.rst index 49d53b2f10f..72e3e1532da 100644 --- a/source/Concepts/Intermediate/About-Executors.rst +++ b/source/Concepts/Intermediate/About-Executors.rst @@ -169,7 +169,8 @@ The following flow diagram visualizes this scheduling semantics. .. image:: ../images/executors_scheduling_semantics.png This semantics was first described in a `paper by Casini et al. at ECRTS 2019 `_. -(Note: The paper also explains that timer events are prioritized over all other messages. `This prioritization was removed in Eloquent. `_) +(Note: The paper also explains that timer events are prioritized over all other messages. +`This prioritization was removed in Eloquent. `_) Outlook @@ -198,6 +199,12 @@ These issues have been partially addressed by the following developments: Further information ------------------- -* Michael Pöhnl et al.: `"ROS 2 Executor: How to make it efficient, real-time and deterministic?" `_. Workshop at ROS World 2021. Virtual event. 19 October 2021. -* Ralph Lange: `"Advanced Execution Management with ROS 2" `_. ROS Industrial Conference. Virtual event. 16 December 2020. +* Michael Pöhnl et al.: `"ROS 2 Executor: How to make it efficient, real-time and deterministic?" `_. + Workshop at ROS World 2021. + Virtual event. + 19 October 2021. +* Ralph Lange: `"Advanced Execution Management with ROS 2" `_. + ROS Industrial Conference. + Virtual event. + 16 December 2020. * Daniel Casini, Tobias Blass, Ingo Lütkebohle, and Björn Brandenburg: `“Response-Time Analysis of ROS 2 Processing Chains under Reservation-Based Scheduling” `_, Proc. of 31st ECRTS 2019, Stuttgart, Germany, July 2019. diff --git a/source/Contact.rst b/source/Contact.rst index 888aa74160d..8340376e3b5 100644 --- a/source/Contact.rst +++ b/source/Contact.rst @@ -57,9 +57,14 @@ When filing an issue, please make sure to: Describe exactly what you were doing or are trying to do, and exactly what, if anything, went wrong. If following a tutorial or online instructions provide a link to the specific instructions. -* Use a descriptive headline or subject line. Bad: "rviz doesn't work". Good: "Rviz crashing looking for missing .so after latest apt update" -* Include information about the exact platform, software, versions, and environment relevant to the problem. This includes how you installed the software (from binaries or from source) and which ROS middleware/DDS vendor you are using (if you know it). -* Any warnings or errors. Cut and paste them directly from the terminal window to which they were printed. Please do not re-type or include a screenshot. +* Use a descriptive headline or subject line. + Bad: "rviz doesn't work". + Good: "Rviz crashing looking for missing .so after latest apt update" +* Include information about the exact platform, software, versions, and environment relevant to the problem. + This includes how you installed the software (from binaries or from source) and which ROS middleware/DDS vendor you are using (if you know it). +* Any warnings or errors. + Cut and paste them directly from the terminal window to which they were printed. + Please do not re-type or include a screenshot. * In case of a bug consider providing a `short, self contained, correct (compilable), example `__. * When discussing any compiling/linking/installation issues, also provide the compiler version diff --git a/source/Glossary.rst b/source/Glossary.rst index 48e0ad31592..7fa6ecc9343 100644 --- a/source/Glossary.rst +++ b/source/Glossary.rst @@ -8,7 +8,11 @@ Glossary of terms used throughout this documentation: .. glossary:: API - An API, or Application Programming Interface, is an interface that is provided by an "application", which in this case is usually a shared library or other language appropriate shared resource. APIs are made up of files that define a contract between the software using the interface and the software providing the interface. These files typically manifest as header files in C and C++ and as Python files in Python. In either case it is important that APIs are grouped and described in documentation and that they are declared as either public or private. Public interfaces are subject to change rules and changes to the public interfaces prompt a new version number of the software that provides them. + An API, or Application Programming Interface, is an interface that is provided by an "application", which in this case is usually a shared library or other language appropriate shared resource. + APIs are made up of files that define a contract between the software using the interface and the software providing the interface. + These files typically manifest as header files in C and C++ and as Python files in Python. + In either case it is important that APIs are grouped and described in documentation and that they are declared as either public or private. + Public interfaces are subject to change rules and changes to the public interfaces prompt a new version number of the software that provides them. client_library A client library is an :term:`API` that provides access to the ROS graph using primitive middleware concepts like Topics, Services, and Actions. @@ -17,7 +21,8 @@ Glossary of terms used throughout this documentation: A single unit of software, including source code, build system files, documentation, tests, and other associated resources. REP - ROS Enhancement Proposal. A document that describes an enhancement, standardization, or convention for the ROS community. + ROS Enhancement Proposal. + A document that describes an enhancement, standardization, or convention for the ROS community. The associated REP approval process allows the community to iterate on a proposal until some consensus has been made, at which point it can be ratified and implemented, which then becomes documentation. All REPs are viewable from the `REP index `_. @@ -25,7 +30,8 @@ Glossary of terms used throughout this documentation: Version Control System, such as CVS, SVN, git, mercurial, etc... rclcpp - The C++ specific :term:`Client Library ` for ROS. This includes any middleware related APIs as well as the related message generation of C++ data structures based on interface definitions like Messages, Services, and Actions. + The C++ specific :term:`Client Library ` for ROS. + This includes any middleware related APIs as well as the related message generation of C++ data structures based on interface definitions like Messages, Services, and Actions. repository A collection of packages usually managed using a :term:`VCS` like git or mercurial and usually hosted on a site like GitHub or BitBucket. diff --git a/source/How-To-Guides/Ament-CMake-Documentation.rst b/source/How-To-Guides/Ament-CMake-Documentation.rst index 32242743e59..97bc8ec40b7 100644 --- a/source/How-To-Guides/Ament-CMake-Documentation.rst +++ b/source/How-To-Guides/Ament-CMake-Documentation.rst @@ -323,7 +323,8 @@ One example of how to do so can be found in the `ament_cmake_lint_cmake document Testing ^^^^^^^ -Ament contains CMake macros to simplify setting up GTests. Call: +Ament contains CMake macros to simplify setting up GTests. +Call: .. code-block:: cmake @@ -348,7 +349,9 @@ The macros have additional parameters: - ``ENV``: set environment variables (same syntax as ``APPEND_ENV``). -- ``TIMEOUT``: set a test timeout in second. The default for GTests is 60 seconds. For example: +- ``TIMEOUT``: set a test timeout in second. + The default for GTests is 60 seconds. + For example: .. code-block:: cmake @@ -550,7 +553,8 @@ For the RViz mesh resource, the corresponding choices were: - ``rviz_ogre_media_exports`` as name of the resource, -- install path relative paths to all folders containing resources. This will already enable you to write the logic for using the corresponding resource in your package. +- install path relative paths to all folders containing resources. + This will already enable you to write the logic for using the corresponding resource in your package. To allow users to easily register resources for your package, you should furthermore provide macros or functions such as the pluginlib function or ``rviz_ogre_media_exports`` function. diff --git a/source/How-To-Guides/Ament-CMake-Python-Documentation.rst b/source/How-To-Guides/Ament-CMake-Python-Documentation.rst index ccb1bcf9283..34eceaf8156 100644 --- a/source/How-To-Guides/Ament-CMake-Python-Documentation.rst +++ b/source/How-To-Guides/Ament-CMake-Python-Documentation.rst @@ -63,8 +63,8 @@ In this case, it is ``my_project``, or ``${PROJECT_NAME}``. .. warning:: Calling ``rosidl_generate_interfaces`` and ``ament_python_install_package`` in the same CMake project does not work. - See this `Github issue `_ for more info. It is best practice to instead - separate out the message generation into a separate package. + See this `Github issue `_ for more info. + It is best practice to instead separate out the message generation into a separate package. Then, another Python package that correctly depends on ``my_project`` can use it as a normal Python module: diff --git a/source/How-To-Guides/DDS-tuning.rst b/source/How-To-Guides/DDS-tuning.rst index 79014a6b238..e2c0f7c1843 100644 --- a/source/How-To-Guides/DDS-tuning.rst +++ b/source/How-To-Guides/DDS-tuning.rst @@ -163,7 +163,8 @@ However, it always at least managed to complete the delivery. **Solution:** Use the `Connext QoS profile `_ *without* adjusting ``rmem_max``. -The ROS2TEST_QOS_PROFILES.xml file was configured using RTI’s documentation on `configuring flow controllers `_. It has slow, medium and fast flow controllers (seen in the Connext QoS profile link). +The ROS2TEST_QOS_PROFILES.xml file was configured using RTI’s documentation on `configuring flow controllers `_. +It has slow, medium and fast flow controllers (seen in the Connext QoS profile link). The medium flow controller produced the best results for our case. However, the controllers will still need to be tuned for the particular machine/network/environment they are operating in. diff --git a/source/How-To-Guides/Installation-Troubleshooting.rst b/source/How-To-Guides/Installation-Troubleshooting.rst index e1faee17226..459a9322a46 100644 --- a/source/How-To-Guides/Installation-Troubleshooting.rst +++ b/source/How-To-Guides/Installation-Troubleshooting.rst @@ -66,7 +66,8 @@ If so, compare the libraries present in the directory with the one mentioned in Assuming a file with a similar name exists (same prefix like ``_rclpy.`` and same suffix like ``.so`` but a different Python version / architecture) you are using a different Python interpreter than which was used to build the C extension. Be sure to use the same Python interpreter as the one used to build the binary. -For example, such a mismatch can crop up after an update of the OS. Then, rebuilding the workspace may fix the issue. +For example, such a mismatch can crop up after an update of the OS. +Then, rebuilding the workspace may fix the issue. .. _linux-troubleshooting: @@ -289,7 +290,8 @@ Use this information to install additional dependencies or adjust your path as n CMake error setting modification time ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -If you run into the CMake error ``file INSTALL cannot set modification time on ...`` when installing files it is likely that an anti virus software or Windows Defender are interfering with the build. E.g. for Windows Defender you can list the workspace location to be excluded to prevent it from scanning those files. +If you run into the CMake error ``file INSTALL cannot set modification time on ...`` when installing files it is likely that an anti virus software or Windows Defender are interfering with the build. +E.g. for Windows Defender you can list the workspace location to be excluded to prevent it from scanning those files. 260 character path limit ^^^^^^^^^^^^^^^^^^^^^^^^ @@ -323,7 +325,8 @@ patch.exe opens a new command window and asks for administrator This will also cause the build of packages which need to use patch to fail, even you allow it to use administrator rights. -- ``choco uninstall patch; colcon build --cmake-clean-cache`` - This is a bug in the `GNU Patch For Windows package `_. If this package is not installed, the build process will instead use the version of Patch distributed with git. +- ``choco uninstall patch; colcon build --cmake-clean-cache`` - This is a bug in the `GNU Patch For Windows package `_. + If this package is not installed, the build process will instead use the version of Patch distributed with git. Failed to load Fast RTPS shared library ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/source/How-To-Guides/Installing-on-Raspberry-Pi.rst b/source/How-To-Guides/Installing-on-Raspberry-Pi.rst index 9ee39dcbac7..a774526819a 100644 --- a/source/How-To-Guides/Installing-on-Raspberry-Pi.rst +++ b/source/How-To-Guides/Installing-on-Raspberry-Pi.rst @@ -29,7 +29,8 @@ After flashing the OS, `install Docker `__. -You may choose from ros-core, ros-base, or perception. See `here `__ for more information on these variants. +You may choose from ros-core, ros-base, or perception. +See `here `__ for more information on these variants. Fetch and run an image: diff --git a/source/How-To-Guides/ROS-2-IDEs.rst b/source/How-To-Guides/ROS-2-IDEs.rst index 157a80603b6..99fb66a4b4c 100644 --- a/source/How-To-Guides/ROS-2-IDEs.rst +++ b/source/How-To-Guides/ROS-2-IDEs.rst @@ -47,7 +47,8 @@ So: #. Create your ROS workspace as you would normally. #. In a terminal, source both ROS 2 and your install (if it was built already). -#. Start VSCode from the same command line. The terminal will be blocked until the application is closed again. +#. Start VSCode from the same command line. + The terminal will be blocked until the application is closed again. .. tabs:: @@ -172,7 +173,8 @@ Instead, some settings need to be tweaked. #. Create your ROS workspace as you would normally. #. Start PyCharm normally. -#. Open a project. This should be the root directory of the ROS node you're developing, e.g. ``C:\dev_ws\src\my_node``. +#. Open a project. + This should be the root directory of the ROS node you're developing, e.g. ``C:\dev_ws\src\my_node``. #. Click "Add new interpreter" > "Add local interpreter...". Select a system interpreter (or virtual environment if you're using one) and select the executable of your ROS Python version (typically ``C:\Python38\python.exe``). diff --git a/source/How-To-Guides/Releasing/Index-Your-Packages.rst b/source/How-To-Guides/Releasing/Index-Your-Packages.rst index 2249586273f..4a1716ff195 100644 --- a/source/How-To-Guides/Releasing/Index-Your-Packages.rst +++ b/source/How-To-Guides/Releasing/Index-Your-Packages.rst @@ -70,9 +70,15 @@ For each ROS distribution you want to release into: Here's how to fill out each item: -* YOUR-REPO-NAME: This is an arbitrary human-readable name. For repos hosted on GitHub, use the lowercase name of your repository not including the organization. For example, the repository name of ``https://github.com/ros2/rosidl`` is ``rosidl``. -* YOUR-GIT-REPO-URL: This is the https URL from which one could ``git clone`` your repository. For example, the git repo URL of ``https://github.com/ros2/rosidl`` is ``https://github.com/ros2/rosidl.git``. It is important that this URL ends in ``.git``, or it will fail to pass the linters. -* YOUR-BRANCH-NAME: This is the git branch on your repository from which you will release your package into this ROS distribution. This is commonly one of: ``main``, ``master``, or the name of the ROS distribution itself. For example, the `rosidl repository `__ uses the branch ``rolling`` to hold changes to be released into ROS Rolling. +* YOUR-REPO-NAME: This is an arbitrary human-readable name. + For repos hosted on GitHub, use the lowercase name of your repository not including the organization. + For example, the repository name of ``https://github.com/ros2/rosidl`` is ``rosidl``. +* YOUR-GIT-REPO-URL: This is the https URL from which one could ``git clone`` your repository + For example, the git repo URL of ``https://github.com/ros2/rosidl`` is ``https://github.com/ros2/rosidl.git``. + It is important that this URL ends in ``.git``, or it will fail to pass the linters. +* YOUR-BRANCH-NAME: This is the git branch on your repository from which you will release your package into this ROS distribution. + This is commonly one of: ``main``, ``master``, or the name of the ROS distribution itself. + For example, the `rosidl repository `__ uses the branch ``rolling`` to hold changes to be released into ROS Rolling. * YOUR-STATUS: This is a status from the list in `REP 141 `__. You likely want either ``maintained`` or ``developed``. Open a pull request to ros/rosdistro diff --git a/source/How-To-Guides/Run-2-nodes-in-single-or-separate-docker-containers.rst b/source/How-To-Guides/Run-2-nodes-in-single-or-separate-docker-containers.rst index b327094d8fb..717ec107ab5 100644 --- a/source/How-To-Guides/Run-2-nodes-in-single-or-separate-docker-containers.rst +++ b/source/How-To-Guides/Run-2-nodes-in-single-or-separate-docker-containers.rst @@ -58,13 +58,15 @@ Run a minimal example of 2 C++ nodes (1 topic subscriber ``listener``, 1 topic p Run two nodes in two separate docker containers ----------------------------------------------- -Open a terminal. Run the image in a container in interactive mode and launch a topic publisher (executable ``talker`` from the package ``demo_nodes_cpp``) with ``ros2 run``: +Open a terminal. +Run the image in a container in interactive mode and launch a topic publisher (executable ``talker`` from the package ``demo_nodes_cpp``) with ``ros2 run``: .. code-block:: bash docker run -it --rm osrf/ros:{DISTRO}-desktop ros2 run demo_nodes_cpp talker -Open a second terminal. Run the image in a container in interactive mode and launch a topic subscriber (executable ``listener`` from the package ``demo_nodes_cpp``) with ``ros2 run``: +Open a second terminal. +Run the image in a container in interactive mode and launch a topic subscriber (executable ``listener`` from the package ``demo_nodes_cpp``) with ``ros2 run``: .. code-block:: bash diff --git a/source/How-To-Guides/Setup-ROS-2-with-VSCode-and-Docker-Container.rst b/source/How-To-Guides/Setup-ROS-2-with-VSCode-and-Docker-Container.rst index 7d21be7f956..75b58914e97 100644 --- a/source/How-To-Guides/Setup-ROS-2-with-VSCode-and-Docker-Container.rst +++ b/source/How-To-Guides/Setup-ROS-2-with-VSCode-and-Docker-Container.rst @@ -201,7 +201,8 @@ Open and Build Development Container Use ``View->Command Palette...`` or ``Ctrl+Shift+P`` to open the command palette. Search for the command ``Dev Containers: Reopen in Container`` and execute it. -This will build your development docker container for your. It will take a while - sit back or go for a coffee. +This will build your development docker container for your. +It will take a while - sit back or go for a coffee. Test Container diff --git a/source/How-To-Guides/Topics-Services-Actions.rst b/source/How-To-Guides/Topics-Services-Actions.rst index 5a57e0d1185..dc37818d99c 100644 --- a/source/How-To-Guides/Topics-Services-Actions.rst +++ b/source/How-To-Guides/Topics-Services-Actions.rst @@ -14,13 +14,18 @@ This is written to provide the reader with guidelines about when to use each typ Topics ------ -* Should be used for continuous data streams (sensor data, robot state, ...). -* Are for continuous data flow. Data might be published and subscribed at any time independent of any senders/receivers. Many to many connection. Callbacks receive data once it is available. The publisher decides when data is sent. +* Should be used for continuous data streams (sensor data, robot state, ...) +* Are for continuous data flow. + Data might be published and subscribed at any time independent of any senders/receivers. + Many to many connection. + Callbacks receive data once it is available. + The publisher decides when data is sent. Services -------- -* Should be used for remote procedure calls that terminate quickly, e.g. for querying the state of a node or doing a quick calculation such as IK. They should never be used for longer running processes, in particular processes that might be required to preempt if exceptional situations occur and they should never change or depend on state to avoid unwanted side effects for other nodes. +* Should be used for remote procedure calls that terminate quickly, e.g. for querying the state of a node or doing a quick calculation such as IK. + They should never be used for longer running processes, in particular processes that might be required to preempt if exceptional situations occur and they should never change or depend on state to avoid unwanted side effects for other nodes. Actions ------- @@ -29,4 +34,6 @@ Actions * The most important property of actions is that they can be preempted and preemption should always be implemented cleanly by action servers. * Actions can keep state for the lifetime of a goal, i.e. if executing two action goals in parallel on the same server, for each client a separate state instance can be kept since the goal is uniquely identified by its id. * Slow perception routines which take several seconds to terminate or initiating a lower-level control mode are good use cases for actions. -* More complex non-blocking background processing. Used for longer tasks like execution of robot actions. Semantically for real-world actions. +* More complex non-blocking background processing. + Used for longer tasks like execution of robot actions. + Semantically for real-world actions. diff --git a/source/How-To-Guides/Using-Python-Packages.rst b/source/How-To-Guides/Using-Python-Packages.rst index da313b93ae7..27a750d7cba 100644 --- a/source/How-To-Guides/Using-Python-Packages.rst +++ b/source/How-To-Guides/Using-Python-Packages.rst @@ -23,7 +23,8 @@ Using Python Packages with ROS 2 Installing via ``rosdep`` ------------------------- -The fastest way to include third-party python packages is to use their corresponding rosdep keys, if available. ``rosdep`` keys can be checked via: +The fastest way to include third-party python packages is to use their corresponding rosdep keys, if available. +``rosdep`` keys can be checked via: * https://github.com/ros/rosdistro/blob/master/rosdep/base.yaml * https://github.com/ros/rosdistro/blob/master/rosdep/python.yaml diff --git a/source/How-To-Guides/Working-with-multiple-RMW-implementations.rst b/source/How-To-Guides/Working-with-multiple-RMW-implementations.rst index 78ee1a32461..a25fc367f4f 100644 --- a/source/How-To-Guides/Working-with-multiple-RMW-implementations.rst +++ b/source/How-To-Guides/Working-with-multiple-RMW-implementations.rst @@ -21,7 +21,8 @@ You should have already read the :doc:`DDS and ROS middleware implementations pa Specifying RMW implementations ------------------------------ -To have multiple RMW implementations available for use you must have installed the ROS 2 binaries and any additional dependencies for specific RMW implementations, or built ROS 2 from source with multiple RMW implementations in the workspace (the RMW implementations are included in the build by default if their compile-time dependencies are met). See :doc:`Install DDS implementations <../Installation/DDS-Implementations>`. +To have multiple RMW implementations available for use you must have installed the ROS 2 binaries and any additional dependencies for specific RMW implementations, or built ROS 2 from source with multiple RMW implementations in the workspace (the RMW implementations are included in the build by default if their compile-time dependencies are met). +See :doc:`Install DDS implementations <../Installation/DDS-Implementations>`. ---- @@ -79,7 +80,8 @@ Troubleshooting Checking the Current RMW ^^^^^^^^^^^^^^^^^^^^^^^^ -To check the RMW that is currently in use you simply check the ``RMW_IMPLEMENTATION`` environment variable. On Linux systems ``printenv`` prints the full list of environment variables. +To check the RMW that is currently in use you simply check the ``RMW_IMPLEMENTATION`` environment variable. +On Linux systems ``printenv`` prints the full list of environment variables. Other operating systems will have other procedures for viewing environment variables. If ``RMW_IMPLEMENTATION`` is not in the environment it is safe to assume you are using the default for your ROS distro, otherwise the current RMW is the value listed. The default RMW for each ROS Distro can be found in `REP-2000 `_. @@ -140,7 +142,8 @@ If you receive an error message similar to below when running RTI Connext on OSX [D0062|ENABLE]DDS_DomainParticipantPresentation_reserve_participant_index_entryports:!enable reserve participant index [D0062|ENABLE]DDS_DomainParticipant_reserve_participant_index_entryports:Unusable shared memory transport. For a more in- depth explanation of the possible problem and solution, please visit https://community.rti.com/kb/osx510. -This error is caused by an insufficient number or size of shared memory segments allowed by the operating system. As a result, the ``DomainParticipant`` is unable to allocate enough resources and calculate its participant index which causes the error. +This error is caused by an insufficient number or size of shared memory segments allowed by the operating system. +As a result, the ``DomainParticipant`` is unable to allocate enough resources and calculate its participant index which causes the error. You can increase the shared memory resources of your machine either temporarily or permanently. diff --git a/source/Package-Docs.rst b/source/Package-Docs.rst index 7f82f8adbfe..c12133aad8e 100644 --- a/source/Package-Docs.rst +++ b/source/Package-Docs.rst @@ -8,12 +8,14 @@ Here is a brief list of where to look for specific ROS package documentation. * Most ROS 2 packages have their package level documentation `included in this index page `__. -* All ROS 2 package's documentation is hosted alongside its information on the `ROS Index `_. Searching for packages on ROS Index will yield their information such as released distributions, ``README.md`` files, URLs, and other important metadata. +* All ROS 2 package's documentation is hosted alongside its information on the `ROS Index `_. + Searching for packages on ROS Index will yield their information such as released distributions, ``README.md`` files, URLs, and other important metadata. Larger Packages --------------- -Larger packages like MoveIt, Nav2, and microROS, are given their own domain or subdomain on ros.org. Here is a short list. +Larger packages like MoveIt, Nav2, and microROS, are given their own domain or subdomain on ros.org. +Here is a short list. * `MoveIt `__ * `Navigation2 `__ diff --git a/source/Related-Projects/Nvidia-ROS2-Projects.rst b/source/Related-Projects/Nvidia-ROS2-Projects.rst index 3240c848db8..a3d1a8e75a6 100644 --- a/source/Related-Projects/Nvidia-ROS2-Projects.rst +++ b/source/Related-Projects/Nvidia-ROS2-Projects.rst @@ -8,7 +8,8 @@ ROS Projects ------------ * `Isaac ROS Nvblox `__ : Hardware-accelerated 3D scene reconstruction and Nav2 local costmap provider using nvblox. * `Isaac ROS Object Detection `__ : Deep learning model support for object detection including DetectNet. -* `Isaac ROS DNN Inference `__ : This repository provides two NVIDIA GPU-accelerated ROS 2 nodes that perform deep learning inference using custom models. One node uses the TensorRT SDK, while the other uses the Triton SDK. +* `Isaac ROS DNN Inference `__ : This repository provides two NVIDIA GPU-accelerated ROS 2 nodes that perform deep learning inference using custom models. + One node uses the TensorRT SDK, while the other uses the Triton SDK. * `Isaac ROS Visual SLAM `__ : This repository provides a ROS 2 package that estimates stereo visual inertial odometry using the Isaac Elbrus GPU-accelerated library. * `Isaac ROS Argus Camera `__ : This repository provides monocular and stereo nodes that enable ROS developers to use cameras connected to Jetson platforms over a CSI interface. * `Isaac ROS image_pipeline `__ : This metapackage offers similar functionality as the standard, CPU-based image_pipeline metapackage, but does so by leveraging the Jetson platform's specialized computer vision hardware. @@ -16,7 +17,8 @@ ROS Projects * `Isaac ROS AprilTags `__ : ROS 2 node uses the NVIDIA GPU-accelerated AprilTags library to detect AprilTags in images and publish their poses, ids, and additional metadata. * `ROS and ROS 2 Docker Images `__ : Docker images for easy deployment on the NVIDIA Jetson platform, consisting of ROS 2, PyTorch, and other important machine learning libraries. * `ROS and ROS 2 DockerFiles `__: Dockerfiles for ROS 2 based on l4t which all you to build your own Docker image. -* `ROS 2 Packages for PyTorch and TensorRT `__: ROS 2 packageis for classification and object detection tasks using PyTorch and NVIDIA TensorRT. This tutorial is a good starting point AI integration with ROS 2 on NVIDIA Jetson. +* `ROS 2 Packages for PyTorch and TensorRT `__: ROS 2 packageis for classification and object detection tasks using PyTorch and NVIDIA TensorRT. + This tutorial is a good starting point AI integration with ROS 2 on NVIDIA Jetson. * `ROS / ROS 2 Packages for Accelerated Deep Learning Nodes `__: Deep learning image recognition, object detection, and semantic segmentation inference nodes and camera/video streaming nodes for ROS/ROS 2 using the `jetson-inference `__ library and `NVIDIA Hello AI World tutorial `__. * `ROS 2 Package for Human Pose Estimation `__: A ROS 2 package for human pose estimation. * `ROS 2 Package for Hand Pose Estimation and Gesture Classification `__: A ROS 2 package for real-time hand pose estimation and gesture classification using TensorRT. diff --git a/source/Related-Projects/Visualizing-ROS-2-Data-With-Foxglove.rst b/source/Related-Projects/Visualizing-ROS-2-Data-With-Foxglove.rst index 424341bdfb5..99e8d133ac6 100644 --- a/source/Related-Projects/Visualizing-ROS-2-Data-With-Foxglove.rst +++ b/source/Related-Projects/Visualizing-ROS-2-Data-With-Foxglove.rst @@ -11,7 +11,8 @@ It's available in the browser or as a standalone desktop app and is free for ind Installation ------------ -To use Foxglove, you'll need to `create an account `__. It's free and all you need is a valid email address. +To use Foxglove, you'll need to `create an account `__. +It's free and all you need is a valid email address. Once you've created an account, you can use Foxglove on the web by opening Google Chrome and navigating to `app.foxglove.dev `__. @@ -19,7 +20,9 @@ To use the desktop app for Linux, macOS, or Windows, download it directly from t .. note:: - Foxglove uses specific features of Google Chrome. While some features may work, other browsers are not supported. For the best experience, we recommend using Chrome or the desktop app. + Foxglove uses specific features of Google Chrome. + While some features may work, other browsers are not supported. + For the best experience, we recommend using Chrome or the desktop app. Connect to a live data source ----------------------------- @@ -36,9 +39,11 @@ Once you have the bridge installed, launch it with: ros2 launch foxglove_bridge foxglove_bridge_launch.xml -With the bridge running on your robot, you're ready to connect view data in Foxglove. Make sure you are on the same network as your robot, open Foxglove (web or desktop) and click "Open connection". +With the bridge running on your robot, you're ready to connect view data in Foxglove. +Make sure you are on the same network as your robot, open Foxglove (web or desktop) and click "Open connection". -Select the option for "Foxglove WebSocket" and enter your robot's WebSocket URL. The default is ``ws://localhost:8765``, however you can read about configuration options for the ROS Foxglove bridge `here `__. +Select the option for "Foxglove WebSocket" and enter your robot's WebSocket URL. +The default is ``ws://localhost:8765``, however you can read about configuration options for the ROS Foxglove bridge `here `__. .. note:: @@ -47,7 +52,8 @@ Select the option for "Foxglove WebSocket" and enter your robot's WebSocket URL. View and replay recorded data ----------------------------- -If you'd rather visualize recorded data, you can use Foxglove to replay ROS 2 ``.mcap`` as well as older ROS 2 ``.db3``, and ROS 1 ``.bag`` files. Foxglove is particularly convenient for recorded data because it does not require ROS 2 to be running to view data. +If you'd rather visualize recorded data, you can use Foxglove to replay ROS 2 ``.mcap`` as well as older ROS 2 ``.db3``, and ROS 1 ``.bag`` files. +Foxglove is particularly convenient for recorded data because it does not require ROS 2 to be running to view data. Use the :doc:`ros2 bag command line tool <../Tutorials/Beginner-CLI-Tools/Recording-And-Playing-Back-Data/Recording-And-Playing-Back-Data>` to record data from your robot to a ``.mcap`` file: @@ -73,7 +79,8 @@ We've highlighted some particularly useful ones below: 3D panel: View 3D data and visualization markers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Open the panel settings by clicking the gear icon in the upper right. Choose the topics you want to display via the topic picker on the left, and configure each topic's visualization settings in the "Edit topic settings" menu. +Open the panel settings by clicking the gear icon in the upper right. +Choose the topics you want to display via the topic picker on the left, and configure each topic's visualization settings in the "Edit topic settings" menu. Publish marker messages to add primitive shapes (arrows, spheres, etc.) and more complex visualizations (occupancy grids, point clouds, etc.) to your 3D panel's scene. @@ -97,7 +104,8 @@ Reference the `docs Image panel: View camera feed images ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -Display raw and compressed images, as well as compressed videos, with 2D annotations like text labels, circles, and points. Superimpose 3D markers for additional context. +Display raw and compressed images, as well as compressed videos, with 2D annotations like text labels, circles, and points. +Superimpose 3D markers for additional context. .. image:: foxglove/image.png :width: 500 px @@ -121,7 +129,8 @@ Plot panel: Plot arbitrary values over time Plot arbitrary numeric values from topic `message paths `__ . -When playing back local or remote data files, this panel will preload the data belonging to the specified topic message paths for the whole playback timeline. Current playback time is indicated by a vertical gray bar. +When playing back local or remote data files, this panel will preload the data belonging to the specified topic message paths for the whole playback timeline. +Current playback time is indicated by a vertical gray bar. .. image:: foxglove/plot.png :width: 500 px @@ -134,7 +143,8 @@ Raw Messages panel: View incoming topic messages Inspect a particular `message path `__ in your data source. -As new messages are received for a given path, the collapsible tree will show just the latest message. You will be able to expand and collapse keys, and have those changes persist across playback. +As new messages are received for a given path, the collapsible tree will show just the latest message. +You will be able to expand and collapse keys, and have those changes persist across playback. .. image:: foxglove/raw-messages.png :width: 500 px diff --git a/source/The-ROS2-Project/Contributing/Build-Farms.rst b/source/The-ROS2-Project/Contributing/Build-Farms.rst index 26edc804b2d..4f27b2c65b5 100644 --- a/source/The-ROS2-Project/Contributing/Build-Farms.rst +++ b/source/The-ROS2-Project/Contributing/Build-Farms.rst @@ -74,7 +74,8 @@ Execution of the jobs depends on the type of the job: * `devel jobs`_ will be triggered every time a commit is done to the respective branch polling based on a configured frequency. * `pull_request jobs`_ will be triggered by webhooks from respective pull request of the upstream [2]_ repository * `release jobs`_ will be triggered once every time a new package version is released, i.e. a new - rosdistro_ pull request was accepted for this package. The source jobs are triggered by a version + rosdistro_ pull request was accepted for this package. + The source jobs are triggered by a version change in the rosdistro distribution file, the binary jobs are triggered by their source counterpart. @@ -83,25 +84,26 @@ Frequency Asked Questions (FAQ) and Troubleshooting #. **I get Jenkins mails from failing build farm jobs. What do I do?** - Go to the job that raised the issue. You find the link on top of the Jenkins email. - Once you followed the link to the build job, click *Console Output* on the left, then click - *Full Log*. This will give you the full console output of the failing build. Try to find the - top-most error as it is usually the most important and other errors might be follow-ups. + Go to the job that raised the issue. + You find the link on top of the Jenkins email. + Once you followed the link to the build job, click *Console Output* on the left, then click *Full Log*. + This will give you the full console output of the failing build. + Try to find the top-most error as it is usually the most important and other errors might be follow-ups. - The bottom of the email might read ``'apt-src build [...]' failed. This is usually because of - an error building the package.`` This usually hints at missing dependencies, see 2. + The bottom of the email might read + ``'apt-src build [...]' failed. This is usually because of an error building the package.`` + This usually hints at missing dependencies, see 2. #. **I seem to be missing a dependency, how do I find out which one?** You basically have two options, a. is easier but may take several iterations, b. is more elaborate and gives you the full insight as well as local debugging. - a) Inspect the release job that raised the issue (see 1.) and localize the cmake dependency - issue. To do so, browse to the cmake section, e.g., navigate to the *build binarydeb* - section through the menu on the left in case of a Ubuntu/Debian build job. The *CMake Error* - will typically hint at a dependency required by the cmake configuration but missing in the - `package manifest`_. Once you have fixed the dependency in the manifest, do a new release - of your package and wait for feedback from the build farms or... + a) Inspect the release job that raised the issue (see 1.) and localize the cmake dependency issue. + To do so, browse to the cmake section, e.g., navigate to the *build binarydeb* + section through the menu on the left in case of a Ubuntu/Debian build job. + The *CMake Error* will typically hint at a dependency required by the cmake configuration but missing in the `package manifest`_. + Once you have fixed the dependency in the manifest, do a new release of your package and wait for feedback from the build farms or... b) To get the full insight and faster, local debugging, you can `run the release jobs locally`_. This allows to iterate the manifest locally until all dependencies are fixed. @@ -109,12 +111,13 @@ Frequency Asked Questions (FAQ) and Troubleshooting There are several potential reasons for this. First, release jobs build against a minimal ROS installation to check if all dependencies are - properly declared in the `package manifest`_. Devel jobs / github actions / local builds may + properly declared in the `package manifest`_. + Devel jobs / github actions / local builds may be performed in an environment that has the dependencies already installed, therefore does not - notice dependency issues. Second, they might build different versions of the source code. + notice dependency issues. + Second, they might build different versions of the source code. While devel jobs / github actions / local builds usually build the latest version from the - *upstream* [2]_ repository, `release jobs`_ build the source code of the latest release, i.e. - the source code in the respective *upstream* branches of the *release* repository [3]_. + *upstream* [2]_ repository, `release jobs`_ build the source code of the latest release, i.e. the source code in the respective *upstream* branches of the *release* repository [3]_. Further Reading diff --git a/source/The-ROS2-Project/Contributing/Code-Style-Language-Versions.rst b/source/The-ROS2-Project/Contributing/Code-Style-Language-Versions.rst index 5ee4cfafe68..99ac9f148f9 100644 --- a/source/The-ROS2-Project/Contributing/Code-Style-Language-Versions.rst +++ b/source/The-ROS2-Project/Contributing/Code-Style-Language-Versions.rst @@ -51,7 +51,8 @@ All of the following modifications only apply if we are not writing Python modul * The stuff about documentation strings doesn't apply -We can use the `pep7 `__ python module for style checking. The editor integration seems slim, we may need to look into automated checking for C in more detail. +We can use the `pep7 `__ python module for style checking. +The editor integration seems slim, we may need to look into automated checking for C in more detail. C++ --- @@ -194,7 +195,9 @@ Open Versus Cuddled Braces * Exception: when an ``if`` (or ``while``, etc.) condition is long enough to require line-wrapping, then use an open brace (i.e., don't cuddle). -* When a function call cannot fit on one line, wrap at the open parenthesis (not in between arguments) and start them on the next line with a 2-space indent. Continue with the 2-space indent on subsequent lines for more arguments. (Note that the `Google style guide `__ is internally contradictory on this point.) +* When a function call cannot fit on one line, wrap at the open parenthesis (not in between arguments) and start them on the next line with a 2-space indent. + Continue with the 2-space indent on subsequent lines for more arguments. + (Note that the `Google style guide `__ is internally contradictory on this point.) * Same goes for ``if`` (and ``while``, etc.) conditions that are too long to fit on one line. diff --git a/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst b/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst index 5c656f264dc..205069a8400 100644 --- a/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst +++ b/source/The-ROS2-Project/Contributing/Contributing-To-ROS-2-Documentation.rst @@ -194,9 +194,11 @@ We've found that the easiest way to migrate a page from the ROS Wiki is to conve Migrating a Wiki File ^^^^^^^^^^^^^^^^^^^^^ -#. Clone the appropriate repository. If you are migrating a page to the official documentation hosted here, then you should clone https://github.com/ros2/ros2_documentation. +#. Clone the appropriate repository. + If you are migrating a page to the official documentation hosted here, then you should clone https://github.com/ros2/ros2_documentation. -#. Create a new Github branch for your migrated page. We suggest something like ``pagename-migration``. +#. Create a new Github branch for your migrated page. + We suggest something like ``pagename-migration``. #. Download the appropriate ROS Wiki page to an html file using wget or a similar tool (e.g. ``wget -O urdf.html https://wiki.ros.org/urdf``). Alternatively you can use your web browser to save the page's HTML. @@ -204,7 +206,8 @@ Migrating a Wiki File #. Next you need to remove the extraneous HTML in the file you downloaded Using your browser's developer mode, find the name of the first useful HTML element in the Wiki page. In most cases all of the HTML between the third line of the file, starting with the ```` tag, through the start of the first ``

`` tag can be safely removed. - In the case where there is a table of contents, the first useful tag may be an ``

`` tag. Similarly, the ROS wiki contains some footer text that starts with ``
`` and ends just above ```` that can also be removed. + In the case where there is a table of contents, the first useful tag may be an ``

`` tag. + Similarly, the ROS wiki contains some footer text that starts with ``
`` and ends just above ```` that can also be removed. #. Convert your html file by running a PanDoc conversion between HTML and restructured text. The following command converts an HTML file to the equivalent reStructured text files: ``pandoc -f html -t rst urdf.html > URDF.rst``. @@ -219,7 +222,9 @@ Migrating a Wiki File This process may require you alter the document considerably, and you may need to pull multiple wiki files. You should verify that every code sample in the document is working correctly under ROS 2. -#. Find and download any images that may be in the old document. The easiest way to do this is to right click in the browser and download all of the images. Alternatively you can find images by searching for ```` tags in the HTML file. +#. Find and download any images that may be in the old document. + The easiest way to do this is to right click in the browser and download all of the images. + Alternatively you can find images by searching for ```` tags in the HTML file. #. For each image files downloaded update the image file links to point to the correct image directory for the ROS Docs. If any of the images require updating, or could be replaced with a `Mermaid `__ chart, please make this change. @@ -247,7 +252,8 @@ After that, you can open the repository in Codespaces, it can be done just by cl :alt: Codespaces creation After that, you will be redirected to your Codespaces page, where you can see the progress of the Codespaces creation. -Once it is done, a Visual Studio Code tab will be opened in your browser. You can open the terminal by clicking on the "Terminal" tab in the top panel or by pressing :kbd:`Ctrl-J`. +Once it is done, a Visual Studio Code tab will be opened in your browser. +You can open the terminal by clicking on the "Terminal" tab in the top panel or by pressing :kbd:`Ctrl-J`. In this terminal, you can run any command you want, for example, you can run the following command to build the site for just this branch: diff --git a/source/The-ROS2-Project/Contributing/Developer-Guide.rst b/source/The-ROS2-Project/Contributing/Developer-Guide.rst index 82527cec000..8b90556e6fd 100644 --- a/source/The-ROS2-Project/Contributing/Developer-Guide.rst +++ b/source/The-ROS2-Project/Contributing/Developer-Guide.rst @@ -425,7 +425,8 @@ Package Naming Conventions Names play an important role in ROS and following naming conventions simplifies the process of learning and understanding large systems. -The ROS packages occupy a flat namespace, so naming should be done carefully and consistently. There is a standard for package naming in `REP-144 `__ +The ROS packages occupy a flat namespace, so naming should be done carefully and consistently. +There is a standard for package naming in `REP-144 `__ * Package names should follow common C variable naming conventions: lower case, start with a letter, use underscore separators, e.g. laser_viewer @@ -578,7 +579,8 @@ The usual workflow is: * In the first box "CI_BRANCH_TO_TEST" enter your feature branch name * Hit the ``build`` button - (if you are not a ROS 2 committer, you don't have access to the CI farm. In that case, ping the reviewer of your PR to run CI for you) + (if you are not a ROS 2 committer, you don't have access to the CI farm. + In that case, ping the reviewer of your PR to run CI for you) * If your use case requires running code coverage: diff --git a/source/The-ROS2-Project/Contributing/Quality-Guide.rst b/source/The-ROS2-Project/Contributing/Quality-Guide.rst index 5963076861e..ad182afa69e 100644 --- a/source/The-ROS2-Project/Contributing/Quality-Guide.rst +++ b/source/The-ROS2-Project/Contributing/Quality-Guide.rst @@ -127,7 +127,8 @@ However, this step-by-step is a great place to start! * Enabling Analysis for Package/Target - When the C++ compiler is Clang, enable the ``-Wthread-safety`` flag. Example below for CMake-based projects + When the C++ compiler is Clang, enable the ``-Wthread-safety`` flag. + Example below for CMake-based projects .. code-block:: cmake diff --git a/source/The-ROS2-Project/Contributing/Windows-Tips-and-Tricks.rst b/source/The-ROS2-Project/Contributing/Windows-Tips-and-Tricks.rst index 01db8b8af0e..dda812a7d45 100644 --- a/source/The-ROS2-Project/Contributing/Windows-Tips-and-Tricks.rst +++ b/source/The-ROS2-Project/Contributing/Windows-Tips-and-Tricks.rst @@ -20,8 +20,10 @@ Practically speaking, 4 of those characters are always used by the drive letter, That means that only 256 characters are available for the *sum* of all parts of the path. This has two practical consequences for ROS 2: -* Some of the ROS 2 internal path names are fairly long. Because of this, we always recommend using a short path name for the root of your ROS 2 directory, like ``C:\dev``. -* When building ROS 2 from source, the default isolated build mode of colcon can generate very long path names. To avoid these very long path names, use ``--merge-install`` when building on Windows. +* Some of the ROS 2 internal path names are fairly long. + Because of this, we always recommend using a short path name for the root of your ROS 2 directory, like ``C:\dev``. +* When building ROS 2 from source, the default isolated build mode of colcon can generate very long path names. + To avoid these very long path names, use ``--merge-install`` when building on Windows. **Note**: It is possible to change Windows to have much longer maximum path lengths. See `this article `__ for more information. @@ -95,7 +97,8 @@ In another library, ``MY_LIB`` would be replaced with the library name. For a complete example of this header, see `rviz_rendering `__. -To use the macro, add ``MY_LIB_PUBLIC`` before symbols which need to be visible to external libraries. For example: +To use the macro, add ``MY_LIB_PUBLIC`` before symbols which need to be visible to external libraries. +For example: .. code-block:: c++ diff --git a/source/The-ROS2-Project/Feature-Ideas.rst b/source/The-ROS2-Project/Feature-Ideas.rst index acd1204b550..d063a42c488 100644 --- a/source/The-ROS2-Project/Feature-Ideas.rst +++ b/source/The-ROS2-Project/Feature-Ideas.rst @@ -133,7 +133,9 @@ The trailing stars indicate the rough effort: 1 star for small, 2 stars for medi * More granularity in security configuration (allow authentication only, authentication and encryption, etc.) [\*] * Integrate DDS-Security logging plugin (unified way to aggregate security events and report them to the users through a ROS interface) [\*\*] * Key storage security (right now, keys are just stored in the filesystem) [\*\*] - * More user friendly interface (make it easier to specify security config). Maybe a Qt GUI? This GUI could also assist in distributing keys somehow. [\*\*\*] + * More user friendly interface (make it easier to specify security config). + Maybe a Qt GUI? + This GUI could also assist in distributing keys somehow. [\*\*\*] * A way to say "please secure this running system" with some UI that would auto-generate keys and policies for everything that is currently running. [\*\*\*] * If there are hardware-specific features for securing keys or accelerating encryption/signing messages, that could be interesting to add to DDS/RTPS implementations that don't use it already. [\*\*\*] diff --git a/source/The-ROS2-Project/Features.rst b/source/The-ROS2-Project/Features.rst index bade5c363d3..749cf246d0b 100644 --- a/source/The-ROS2-Project/Features.rst +++ b/source/The-ROS2-Project/Features.rst @@ -73,7 +73,8 @@ For planned future development, see the :doc:`Roadmap `. - * - Preliminary support for real-time code - :doc:`Demo <../Tutorials/Demos/Real-Time-Programming>`, :doc:`demo <../Tutorials/Advanced/Allocator-Template-Tutorial>` - - Linux only. Not available for Fast RTPS. + - Linux only. + Not available for Fast RTPS. * - Preliminary support for "bare-metal" microcontrollers - `Wiki `__ - diff --git a/source/The-ROS2-Project/Marketing.rst b/source/The-ROS2-Project/Marketing.rst index 4f9037a713f..b07bee7c249 100644 --- a/source/The-ROS2-Project/Marketing.rst +++ b/source/The-ROS2-Project/Marketing.rst @@ -11,9 +11,8 @@ General Use ROS Artwork ----------------------- The ROS 2 media kit, which includes branding language, high resolution ROS logo -graphics, and release images, can be found in the `ROS art -repository. `__ Please refer to -this repository for ROS art work and our branding guidelines. +graphics, and release images, can be found in the `ROS art repository. `__ +Please refer to this repository for ROS art work and our branding guidelines. Stickers, Posters, and Canvas Prints ------------------------------------ diff --git a/source/The-ROS2-Project/Roadmap.rst b/source/The-ROS2-Project/Roadmap.rst index 4cda15fde53..f0a7b649589 100644 --- a/source/The-ROS2-Project/Roadmap.rst +++ b/source/The-ROS2-Project/Roadmap.rst @@ -56,7 +56,8 @@ Please see the :doc:`Distributions page <../Releases>` for the timeline of and i Contributing to ROS 2 --------------------- -Looking for something to work on, or just want to help out? Here are a few resources to get you going. +Looking for something to work on, or just want to help out? +Here are a few resources to get you going. 1. The :doc:`Contributing ` guide describes how to make a contribution to ROS 2. 2. Check out the list of :doc:`Feature Ideas ` for inspiration. diff --git a/source/Tutorials/Advanced/Ament-Lint-For-Clean-Code.rst b/source/Tutorials/Advanced/Ament-Lint-For-Clean-Code.rst index 14b619f960e..7f866ca5717 100644 --- a/source/Tutorials/Advanced/Ament-Lint-For-Clean-Code.rst +++ b/source/Tutorials/Advanced/Ament-Lint-For-Clean-Code.rst @@ -109,8 +109,10 @@ For example, if you wish to scan just a recently modified file you can call ``am ``ament_cppcheck`` supports the following options: -* ``--libraries [LIBRARIES ...]`` - Library configurations to load in addition to the standard libraries of C and C++. Each library is passed to cppcheck as '--library=' -* ``--include_dirs [INCLUDE_DIRS ...]`` - Include directories for C/C++ files being checked.Each directory is passed to cppcheck as '-I ' (default: None) +* ``--libraries [LIBRARIES ...]`` - Library configurations to load in addition to the standard libraries of C and C++. + Each library is passed to cppcheck as '--library=' +* ``--include_dirs [INCLUDE_DIRS ...]`` - Include directories for C/C++ files being checked. + Each directory is passed to cppcheck as '-I ' (default: None) * ``--cppcheck-version`` - Get the cppcheck version, print it, and then exit. 2.3 ``ament_cppcheck`` Example @@ -283,7 +285,8 @@ For example, if you wish to scan just one package in your workspace you can call 5.2 ``ament_uncrustify`` Options ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -* ``-c CFG`` - The config file that Uncrustify should use if you would prefer to use your own settings. We recommend you stick to the defaults +* ``-c CFG`` - The config file that Uncrustify should use if you would prefer to use your own settings. + We recommend you stick to the defaults * ``--linelength N`` - The maximum line length. * ``--language`` - One of {C,C++,CPP}, passed to uncrustify as '-l ' to force a specific language rather then choosing one based on file extension. * ``--reformat`` - Reformat the files in place, i.e. fix the formatting errors encountered. **We recommend you use this option when running ``ament_uncrustify`` as it will save you quite a bit of time!** diff --git a/source/Tutorials/Advanced/Discovery-Server/Discovery-Server.rst b/source/Tutorials/Advanced/Discovery-Server/Discovery-Server.rst index 2ca8e669bc0..6efd96bbf6e 100644 --- a/source/Tutorials/Advanced/Discovery-Server/Discovery-Server.rst +++ b/source/Tutorials/Advanced/Discovery-Server/Discovery-Server.rst @@ -76,7 +76,8 @@ Run this tutorial The ``talker-listener`` ROS 2 demo creates a ``talker`` node that publishes a "hello world" message every second, and a ``listener`` node that listens to these messages. By :doc:`sourcing ROS 2 <../../Beginner-CLI-Tools/Configuring-ROS2-Environment>` you will get access to the CLI tool ``fastdds``. -This tool gives access to the `discovery tool `__, which can be used to launch a discovery server. This server will manage the discovery process for the nodes that connect to it. +This tool gives access to the `discovery tool `__, which can be used to launch a discovery server. +This server will manage the discovery process for the nodes that connect to it. .. important:: @@ -117,7 +118,8 @@ In a new terminal, set the environment variable ``ROS_DISCOVERY_SERVER`` to the set ROS_DISCOVERY_SERVER=127.0.0.1:11811 -Launch the listener node. Use the argument ``--remap __node:=listener_discovery_server`` to change the node's name for this tutorial. +Launch the listener node. +Use the argument ``--remap __node:=listener_discovery_server`` to change the node's name for this tutorial. .. code-block:: console @@ -330,7 +332,9 @@ In another terminal run the second server listening on localhost using another p fastdds discovery --server-id 1 --ip-address 127.0.0.1 --port 11888 -Now, run each node in a different terminal. Use ``ROS_DISCOVERY_SERVER`` environment variable to decide which server they are connected to. Be aware that the `ids must match `__. +Now, run each node in a different terminal. +Use ``ROS_DISCOVERY_SERVER`` environment variable to decide which server they are connected to. +Be aware that the `ids must match `__. .. tabs:: @@ -428,7 +432,8 @@ In this sense, ROS 2 introspection tools can be configured as **Super Client**, .. note:: - In this section we use the term *Participant* as a DDS entity. Each DDS *Participant* corresponds with a ROS 2 *Context*, a ROS 2 abstraction over DDS. + In this section we use the term *Participant* as a DDS entity. + Each DDS *Participant* corresponds with a ROS 2 *Context*, a ROS 2 abstraction over DDS. `Nodes ` are ROS 2 entities that rely on DDS communication interfaces: ``DataWriter`` and ``DataReader``. Each *Participant* can hold multiple ROS 2 Nodes. For further details about these concepts, please visit the `Node to Participant mapping design document `__ diff --git a/source/Tutorials/Advanced/Security/Deployment-Guidelines.rst b/source/Tutorials/Advanced/Security/Deployment-Guidelines.rst index 430478790db..8a2b86a4156 100644 --- a/source/Tutorials/Advanced/Security/Deployment-Guidelines.rst +++ b/source/Tutorials/Advanced/Security/Deployment-Guidelines.rst @@ -30,7 +30,8 @@ Prerequisites * A docker installation with the compose plugin. Please refer to the installation steps detailed in `Docker installation `_ and `Compose Plugin `_. * (Recommended) A basic understanding on `ROS 2 Security design `_. -* (Recommended) Previous security tutorials completion. In particular: +* (Recommended) Previous security tutorials completion. + In particular: * :doc:`Introducing-ros2-security` * :doc:`The-Keystore` diff --git a/source/Tutorials/Advanced/Security/Examine-Traffic.rst b/source/Tutorials/Advanced/Security/Examine-Traffic.rst index 2a9bc7f66ba..254c8469448 100644 --- a/source/Tutorials/Advanced/Security/Examine-Traffic.rst +++ b/source/Tutorials/Advanced/Security/Examine-Traffic.rst @@ -185,7 +185,8 @@ The typical discovery packet looks somewhat like the following:: This packet is much larger and includes information which can be used to set up encryption among ROS nodes. As we will see shortly, this actually includes some of the security configuration files that were created when we enabled security. -Interested in learning more? Take a look at the excellent paper `Network Reconnaissance and Vulnerability Excavation of Secure DDS Systems `_ to understand why this matters. +Interested in learning more? +Take a look at the excellent paper `Network Reconnaissance and Vulnerability Excavation of Secure DDS Systems `_ to understand why this matters. Display encrypted data packets diff --git a/source/Tutorials/Advanced/Simulators/Webots/Installation-MacOS.rst b/source/Tutorials/Advanced/Simulators/Webots/Installation-MacOS.rst index 7fd83be0712..cbf850f6d31 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Installation-MacOS.rst +++ b/source/Tutorials/Advanced/Simulators/Webots/Installation-MacOS.rst @@ -59,7 +59,8 @@ In the UTM software: * Leave all the remaining parameters as default. * Start the VM. Note that you can select another shared folder each time you start the VM. -* During the first launch of the VM, install Ubuntu and choose a username for your account. In this example, the username is ``ubuntu``. +* During the first launch of the VM, install Ubuntu and choose a username for your account. + In this example, the username is ``ubuntu``. * Once Ubuntu is installed, close the VM, remove the iso image from the CD/DVD field and restart the VM. 2 Configure the VM diff --git a/source/Tutorials/Advanced/Simulators/Webots/Installation-Windows.rst b/source/Tutorials/Advanced/Simulators/Webots/Installation-Windows.rst index fcc93231580..51f8120f4bd 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Installation-Windows.rst +++ b/source/Tutorials/Advanced/Simulators/Webots/Installation-Windows.rst @@ -165,7 +165,8 @@ The Tiago robot can be controlled using: ros2 run teleop_twist_keyboard teleop_twist_keyboard -With older WSL versions, RViz2 may not work directly, as no display is available. To use RViz, you can either upgrade WSL or enable X11 forwarding. +With older WSL versions, RViz2 may not work directly, as no display is available. +To use RViz, you can either upgrade WSL or enable X11 forwarding. .. tabs:: .. group-tab:: Upgrade WSL diff --git a/source/Tutorials/Advanced/Simulators/Webots/Simulation-Supervisor.rst b/source/Tutorials/Advanced/Simulators/Webots/Simulation-Supervisor.rst index d16b4980b6e..06a9efe9188 100644 --- a/source/Tutorials/Advanced/Simulators/Webots/Simulation-Supervisor.rst +++ b/source/Tutorials/Advanced/Simulators/Webots/Simulation-Supervisor.rst @@ -32,7 +32,8 @@ The ``Ros2Supervisor`` The ``Ros2Supervisor`` is made of two main parts: -* A Webots Robot node added to the simulation world. Its ``supervisor`` field is set to TRUE. +* A Webots Robot node added to the simulation world. + Its ``supervisor`` field is set to TRUE. * A ROS 2 node that connects to the Webots Robot as an extern controller (in a similar way to your own robot plugin). The ROS 2 node acts as a controller that calls Supervisor API functions to control or interact with the simulation world. diff --git a/source/Tutorials/Advanced/Topic-Statistics-Tutorial/Topic-Statistics-Tutorial.rst b/source/Tutorials/Advanced/Topic-Statistics-Tutorial/Topic-Statistics-Tutorial.rst index 9fc850fc956..7d94dbf8263 100644 --- a/source/Tutorials/Advanced/Topic-Statistics-Tutorial/Topic-Statistics-Tutorial.rst +++ b/source/Tutorials/Advanced/Topic-Statistics-Tutorial/Topic-Statistics-Tutorial.rst @@ -324,8 +324,9 @@ Summary ------- You created a subscriber node with topic statistics enabled, which published statistics data from -the :doc:`C++ <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>`'s publisher node. You were able to compile and run this node. While running, -you were able to observe the statistics data. +the :doc:`C++ <../../Beginner-Client-Libraries/Writing-A-Simple-Cpp-Service-And-Client>`'s publisher node. +You were able to compile and run this node. +While running, you were able to observe the statistics data. Related content --------------- diff --git a/source/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Nodes/Understanding-ROS2-Nodes.rst b/source/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Nodes/Understanding-ROS2-Nodes.rst index cce9f52d0ef..4c50501f268 100644 --- a/source/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Nodes/Understanding-ROS2-Nodes.rst +++ b/source/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Nodes/Understanding-ROS2-Nodes.rst @@ -142,7 +142,8 @@ To examine your latest node, ``my_turtle``, run the following command: ros2 node info /my_turtle -``ros2 node info`` returns a list of subscribers, publishers, services, and actions. i.e. the ROS graph connections that interact with that node. +``ros2 node info`` returns a list of subscribers, publishers, services, and actions. +i.e. the ROS graph connections that interact with that node. The output should look like this: .. code-block:: console diff --git a/source/Tutorials/Beginner-Client-Libraries/Pluginlib.rst b/source/Tutorials/Beginner-Client-Libraries/Pluginlib.rst index ed95dd1a588..c8e1557e3ce 100644 --- a/source/Tutorials/Beginner-Client-Libraries/Pluginlib.rst +++ b/source/Tutorials/Beginner-Client-Libraries/Pluginlib.rst @@ -189,7 +189,8 @@ Create ``ros2_ws/src/polygon_plugins/plugins.xml`` with the following code: A couple things to note: 1. The ``library`` tag gives the relative path to a library that contains the plugins that we want to export. - In ROS 2, that is just the name of the library. In ROS 1, it contained the prefix ``lib`` or sometimes ``lib/lib`` (i.e. ``lib/libpolygon_plugins``), but here it is simpler. + In ROS 2, that is just the name of the library. + In ROS 1, it contained the prefix ``lib`` or sometimes ``lib/lib`` (i.e. ``lib/libpolygon_plugins``), but here it is simpler. 2. The ``class`` tag declares a plugin that we want to export from our library. Let's go through its parameters: @@ -313,4 +314,5 @@ It should print: Summary ------- -Congratulations! You've just written and used your first plugins. +Congratulations! +You've just written and used your first plugins. diff --git a/source/Tutorials/Demos/Intra-Process-Communication.rst b/source/Tutorials/Demos/Intra-Process-Communication.rst index 50a5217c4ac..acd65439876 100644 --- a/source/Tutorials/Demos/Intra-Process-Communication.rst +++ b/source/Tutorials/Demos/Intra-Process-Communication.rst @@ -324,7 +324,8 @@ The watermark and image view nodes are designed to modify the image without copy .. note:: On some systems (we've seen it happen on Linux), the address printed to the screen might not change. - This is because the same unique pointer is being reused. In this situation, the pipeline is still running. + This is because the same unique pointer is being reused. + In this situation, the pipeline is still running. Let's run the demo by executing the following executable: @@ -347,7 +348,8 @@ Pipeline with two image viewers ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Now let's look at an example just like the one above, except it has two image view nodes. -All the nodes are still in the same process, but now two image view windows should show up. (Note for macOS users: your image view windows might be on top of each other). +All the nodes are still in the same process, but now two image view windows should show up. +(Note for macOS users: your image view windows might be on top of each other). Let's run it with the command: .. code-block:: bash @@ -358,26 +360,39 @@ Let's run it with the command: .. image:: images/intra-process-demo-pipeline-two-windows-copy.png -Just like the last example, you can pause the rendering with the spacebar and continue by pressing the spacebar a second time. You can stop the updating to inspect the pointers written to the screen. +Just like the last example, you can pause the rendering with the spacebar and continue by pressing the spacebar a second time. +You can stop the updating to inspect the pointers written to the screen. -As you can see in the example image above, we have one image with all of the pointers the same and then another image with the same pointers as the first image for the first two entries, but the last pointer on the second image is different. To understand why this is happening consider the graph's topology: +As you can see in the example image above, we have one image with all of the pointers the same and then another image with the same pointers as the first image for the first two entries, but the last pointer on the second image is different. +To understand why this is happening consider the graph's topology: .. code-block:: bash camera_node -> watermark_node -> image_view_node -> image_view_node2 -The link between the ``camera_node`` and the ``watermark_node`` can use the same pointer without copying because there is only one intra process subscription to which the message should be delivered. But for the link between the ``watermark_node`` and the two image view nodes the relationship is one to many, so if the image view nodes were using ``unique_ptr`` callbacks then it would be impossible to deliver the ownership of the same pointer to both. It can be, however, delivered to one of them. Which one would get the original pointer is not defined, but instead is simply the last to be delivered. +The link between the ``camera_node`` and the ``watermark_node`` can use the same pointer without copying because there is only one intra process subscription to which the message should be delivered. +But for the link between the ``watermark_node`` and the two image view nodes the relationship is one to many, so if the image view nodes were using ``unique_ptr`` callbacks then it would be impossible to deliver the ownership of the same pointer to both. +It can be, however, delivered to one of them. +Which one would get the original pointer is not defined, but instead is simply the last to be delivered. -Note that the image view nodes are not subscribed with ``unique_ptr`` callbacks. Instead they are subscribed with ``const shared_ptr``\ s. This means the system deliveres the same ``shared_ptr`` to both callbacks. When the first intraprocess subscription is handled, the internally stored ``unique_ptr`` is promoted to a ``shared_ptr``. Each of the callbacks will receive shared ownership of the same message. +Note that the image view nodes are not subscribed with ``unique_ptr`` callbacks. +Instead they are subscribed with ``const shared_ptr``\ s. +This means the system deliveres the same ``shared_ptr`` to both callbacks. +When the first intraprocess subscription is handled, the internally stored ``unique_ptr`` is promoted to a ``shared_ptr``. +Each of the callbacks will receive shared ownership of the same message. Pipeline with interprocess viewer ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ -One other important thing to get right is to avoid interruption of the intra process zero-copy behavior when interprocess subscriptions are made. To test this we can run the first image pipeline demo, ``image_pipeline_all_in_one``, and then run an instance of the stand alone ``image_view_node`` (don't forget to prefix them with ``ros2 run intra_process_demo`` in the terminal). This will look something like this: +One other important thing to get right is to avoid interruption of the intra process zero-copy behavior when interprocess subscriptions are made. +To test this we can run the first image pipeline demo, ``image_pipeline_all_in_one``, and then run an instance of the stand alone ``image_view_node`` (don't forget to prefix them with ``ros2 run intra_process_demo`` in the terminal). +This will look something like this: .. image:: images/intra-process-demo-pipeline-inter-process.png -It's hard to pause both images at the same time so the images may not line up, but the important thing to notice is that the ``image_pipeline_all_in_one`` image view shows the same address for each step. This means that the intra process zero-copy is preserved even when an external view is subscribed as well. You can also see that the interprocess image view has different process IDs for the first two lines of text and the process ID of the standalone image viewer in the third line of text. +It's hard to pause both images at the same time so the images may not line up, but the important thing to notice is that the ``image_pipeline_all_in_one`` image view shows the same address for each step. +This means that the intra process zero-copy is preserved even when an external view is subscribed as well. +You can also see that the interprocess image view has different process IDs for the first two lines of text and the process ID of the standalone image viewer in the third line of text. diff --git a/source/Tutorials/Demos/Quality-of-Service.rst b/source/Tutorials/Demos/Quality-of-Service.rst index 4620196f78f..8d2ade34a49 100644 --- a/source/Tutorials/Demos/Quality-of-Service.rst +++ b/source/Tutorials/Demos/Quality-of-Service.rst @@ -126,7 +126,8 @@ In the first window, you'll see output from the subscriber: $ sudo sysctl -w net.inet.udp.recvspace=209715 $ sudo sysctl -w net.inet.udp.maxdgram=65500 - These changes will not persist a reboot. If you want the changes to persist, add these lines to ``/etc/sysctl.conf`` (create the file if it doesn't exist already): + These changes will not persist a reboot. + If you want the changes to persist, add these lines to ``/etc/sysctl.conf`` (create the file if it doesn't exist already): .. code-block:: bash diff --git a/source/Tutorials/Demos/Real-Time-Programming.rst b/source/Tutorials/Demos/Real-Time-Programming.rst index a669272a3a7..6cc079f80ab 100644 --- a/source/Tutorials/Demos/Real-Time-Programming.rst +++ b/source/Tutorials/Demos/Real-Time-Programming.rst @@ -16,7 +16,8 @@ Background Real-time computing is a key feature of many robotics systems, particularly safety- and mission-critical applications such as autonomous vehicles, spacecrafts, and industrial manufacturing. We are designing and prototyping ROS 2 with real-time performance constraints in mind, since this is a requirement that was not considered in the early stages of ROS 1 and it is now intractable to refactor ROS 1 to be real-time friendly. -`This document `__ outlines the requirements of real-time computing and best practices for software engineers. In short: +`This document `__ outlines the requirements of real-time computing and best practices for software engineers. +In short: To make a real-time computer system, our real-time loop must update periodically to meet deadlines. We can only tolerate a small margin of error on these deadlines (our maximum allowable jitter). @@ -35,18 +36,21 @@ The real-time demo was written with Linux operating systems in mind, since many Since many of the operations done in the demo to optimize performance are OS-specific, the demo only builds and runs on Linux systems. **So, if you are an OSX or Windows user, don't try this part!** -Also this must be built from source using a static DDS API. **Currently the only supported implementation is Connext**. +Also this must be built from source using a static DDS API. +**Currently the only supported implementation is Connext**. First, follow the instructions to build ROS 2 :doc:`from source <../../Installation/Alternatives/Ubuntu-Development-Setup>` using Connext DDS as the middleware. Run the tests ^^^^^^^^^^^^^ -**Before you run make sure you have at least 8Gb of RAM free. With the memory locking, swap will not work anymore.** +**Before you run make sure you have at least 8Gb of RAM free. +With the memory locking, swap will not work anymore.** Source your ROS 2 setup.bash. -Run the demo binary, and redirect the output. You may want to use ``sudo`` in case you get permission error: +Run the demo binary, and redirect the output. +You may want to use ``sudo`` in case you get permission error: .. code-block:: bash @@ -162,7 +166,8 @@ Here, latency means the amount of time after the update was expected to occur. The requirements of a real-time system depend on the application, but let's say in this demo we have a 1kHz (1 millisecond) update loop, and we're aiming for a maximum allowable latency of 5% of our update period. -So, our average latency was really good in this run, but the maximum latency was unacceptable because it actually exceeded our update loop! What happened? +So, our average latency was really good in this run, but the maximum latency was unacceptable because it actually exceeded our update loop! +What happened? We may be suffering from a non-deterministic scheduler. If you're running a vanilla Linux system and you don't have the RT_PREEMPT kernel installed, you probably won't be able to meet the real-time goal we set for ourselves, because the Linux scheduler won't allow you to arbitrarily preempt threads at the user level. diff --git a/source/Tutorials/Demos/dummy-robot-demo.rst b/source/Tutorials/Demos/dummy-robot-demo.rst index 791e7e70045..208f2cc33c1 100644 --- a/source/Tutorials/Demos/dummy-robot-demo.rst +++ b/source/Tutorials/Demos/dummy-robot-demo.rst @@ -11,7 +11,8 @@ In this demo, we present a simple demo robot with all components from publishing Launching the demo ------------------ -We assume your ROS 2 installation dir as ``~/ros2_ws``. Please change the directories according to your platform. +We assume your ROS 2 installation dir as ``~/ros2_ws``. +Please change the directories according to your platform. To start the demo, we execute the demo bringup launch file, which we are going to explain in more details in the next section. @@ -45,14 +46,17 @@ You should see some prints inside your terminal along the lines of the following [dummy_laser-4] [INFO] [1714837459.645626640] [dummy_laser]: scan time increment: 0.000000 [robot_state_publisher-2] [INFO] [1714837459.652977937] [robot_state_publisher]: Robot initialized -If you now open RViz2 in a new terminal, you'll see your robot. 🎉 +If you now open RViz2 in a new terminal, you'll see your robot. +🎉 .. code-block:: bash $ source ~/ros2_ws/install/setup.bash $ rviz2 -This opens RViz2. Assuming you have your dummy_robot_bringup still launched, you can now add the TF display plugin and configure your global frame to ``world``. Once you did that, you should see a similar picture: +This opens RViz2. +Assuming you have your dummy_robot_bringup still launched, you can now add the TF display plugin and configure your global frame to ``world``. +Once you did that, you should see a similar picture: .. image:: images/rviz-dummy-robot.png @@ -69,10 +73,15 @@ If you have a closer look at the launch file, we start a couple of nodes at the * dummy_joint_states * robot_state_publisher -The first two packages are relatively simple. The ``dummy_map_server`` constantly publishes an empty map with a periodic update. The ``dummy_laser`` does basically the same; publishing dummy fake laser scans. +The first two packages are relatively simple. +The ``dummy_map_server`` constantly publishes an empty map with a periodic update. +The ``dummy_laser`` does basically the same; publishing dummy fake laser scans. -The ``dummy_joint_states`` node is publishing fake joint state data. As we are publishing a simple RRbot with only two joints, this node publishes joint states values for these two joints. +The ``dummy_joint_states`` node is publishing fake joint state data. +As we are publishing a simple RRbot with only two joints, this node publishes joint states values for these two joints. -The ``robot_state_publisher`` is doing the actual interesting work. It parses the given URDF file, extracts the robot model and listens to the incoming joint states. With this information, it publishes TF values for our robot which we visualize in RViz. +The ``robot_state_publisher`` is doing the actual interesting work. +It parses the given URDF file, extracts the robot model and listens to the incoming joint states. +With this information, it publishes TF values for our robot which we visualize in RViz. Hooray! diff --git a/source/Tutorials/Intermediate/RViz/Marker-Display-types/Marker-Display-types.rst b/source/Tutorials/Intermediate/RViz/Marker-Display-types/Marker-Display-types.rst index ab82bac5e29..97494d97c89 100644 --- a/source/Tutorials/Intermediate/RViz/Marker-Display-types/Marker-Display-types.rst +++ b/source/Tutorials/Intermediate/RViz/Marker-Display-types/Marker-Display-types.rst @@ -85,15 +85,18 @@ The messages in this package include comments that are helpful in understanding * ``ns``: - Namespace for these markers. This plus the id form a unique identifier. + Namespace for these markers. + This plus the id form a unique identifier. * ``id``: - Unique id assigned to this marker. It is your responsibility to keep these unique within your namespace. + Unique id assigned to this marker. + It is your responsibility to keep these unique within your namespace. * ``type``: - Type of marker (Arrow, Sphere, ...). The available types are specified in the message definition. + Type of marker (Arrow, Sphere, ...). + The available types are specified in the message definition. * ``action``: @@ -105,11 +108,16 @@ The messages in this package include comments that are helpful in understanding * ``scale``: - Scale of the marker. Applied before the position/orientation. A scale of [1, 1, 1] means the object will be 1m by 1m by 1m. + Scale of the marker. + Applied before the position/orientation. + A scale of [1, 1, 1] means the object will be 1m by 1m by 1m. * ``color``: - Color of the object, specified as r/g/b/a, with values in the range of [0, 1]. The, ``a`` or alpha value, denotes the opacity of the marker with 1 indicating opaque and 0 indicating completely transparent. The default value is 0, or completely transparent. **You must set the a value of your marker to a non-zero value or it will be transparent by default!** + Color of the object, specified as r/g/b/a, with values in the range of [0, 1]. + The, ``a`` or alpha value, denotes the opacity of the marker with 1 indicating opaque and 0 indicating completely transparent. + The default value is 0, or completely transparent. + **You must set the a value of your marker to a non-zero value or it will be transparent by default!** * ``points``: @@ -119,7 +127,8 @@ The messages in this package include comments that are helpful in understanding * ``colors``: - This field is only used for markers that use the points member. This field specifies per-vertex color r/g/b/ color (no alpha yet) for each entry in ``points``. + This field is only used for markers that use the points member. + This field specifies per-vertex color r/g/b/ color (no alpha yet) for each entry in ``points``. * ``lifetime``: @@ -154,11 +163,14 @@ The arrow type provides two different ways of specifying where the arrow should * ``Position/Orientation``: - Pivot point is around the tip of its tail. Identity orientation points it along the +X axis. ``scale.x`` is the arrow length, ``scale.y`` is the arrow width and ``scale.z`` is the arrow height. + Pivot point is around the tip of its tail. + Identity orientation points it along the +X axis. + ``scale.x`` is the arrow length, ``scale.y`` is the arrow width and ``scale.z`` is the arrow height. * ``Start/End Points``: - You can also specify a start/end point for the arrow, using the points member. If you put points into the points member, it will assume you want to do things this way. + You can also specify a start/end point for the arrow, using the points member. + If you put points into the points member, it will assume you want to do things this way. * The point at index 0 is assumed to be the start point, and the point at index 1 is assumed to be the end. * ``scale.x`` is the shaft diameter, and ``scale.y`` is the head diameter. If ``scale.z`` is not zero, it specifies the head length. @@ -207,7 +219,8 @@ Note that ``pose`` is still used (the points in the line will be transformed by .. image:: images/LineListMarker.png -Line lists use the points member of the `visualization_msgs/msg/Marker `_ message. It will draw a line between each pair of points, so 0-1, 2-3, 4-5, ... +Line lists use the points member of the `visualization_msgs/msg/Marker `_ message. +It will draw a line between each pair of points, so 0-1, 2-3, 4-5, ... Line lists also have some special handling for scale: only ``scale.x`` is used and it controls the width of the line segments. @@ -256,7 +269,8 @@ Note that ``pose`` is still used (the ``points`` in the line will be transformed .. image:: images/text_view_facing_marker.png This marker displays text in a 3D spot in the world. -The text always appears oriented correctly for the RViZ user to see the included text. Uses the ``text`` field in the marker. +The text always appears oriented correctly for the RViZ user to see the included text. +Uses the ``text`` field in the marker. Only ``scale.z`` is used. ``scale.z`` specifies the height of an uppercase "A". diff --git a/source/Tutorials/Intermediate/RViz/RViz-Custom-Display/RViz-Custom-Display.rst b/source/Tutorials/Intermediate/RViz/RViz-Custom-Display/RViz-Custom-Display.rst index 3cdf5adede7..089733158e4 100644 --- a/source/Tutorials/Intermediate/RViz/RViz-Custom-Display/RViz-Custom-Display.rst +++ b/source/Tutorials/Intermediate/RViz/RViz-Custom-Display/RViz-Custom-Display.rst @@ -3,14 +3,17 @@ Building a Custom RViz Display Background ---------- -There are many types of data that have existing visualizations in RViz. However, if there is a message type that does +There are many types of data that have existing visualizations in RViz. +However, if there is a message type that does not yet have a plugin to display it, there are two choices to see it in RViz. 1. Convert the message to another type, such as ``visualization_msgs/Marker``. 2. Write a Custom RViz Display. -With the first option, there is more network traffic and limitations to how the data can be represented. It is also quick and flexible. -The latter option is explained in this tutorial. It takes a bit of work, but can lead to much richer visualizations. +With the first option, there is more network traffic and limitations to how the data can be represented. +It is also quick and flexible. +The latter option is explained in this tutorial. +It takes a bit of work, but can lead to much richer visualizations. All of the code for this tutorial can be found in `this repository `__. In order to see the incremental progress of the plugin written in this tutorial, @@ -224,7 +227,8 @@ First, you need to add a dependency in ``CMakeLists.txt`` and ``package.xml`` on We need to add three lines to the header file: -* ``#include `` - There's `lots of options in the rviz_rendering package `_ for objects to build your visualization on. Here we're using a simple shape. +* ``#include `` - There's `lots of options in the rviz_rendering package `_ for objects to build your visualization on. + Here we're using a simple shape. * In the class, we'll add a new ``protected`` virtual method: ``void onInitialize() override;`` * We also add a pointer to our shape object: ``std::unique_ptr point_shape_;`` @@ -407,11 +411,13 @@ First, we update the plugin declaration. * We add the ``name`` field to the ``class`` tag. This changes the name that is displayed in RViz. In code, it makes sense to call it a ``PointDisplay`` but in RViz, we want to simplify. -* We put actual text into the description. Don't be lazy. +* We put actual text into the description. + Don't be lazy. * By declaring the specific message type here, when you attempt to add a Display by Topic, it will suggest this plugin for the topics of that type. We also add an icon for the plugin at ``icons/classes/Point2D.png``. -The folder is hardcoded, and the filename should match the name from the plugin declaration (or the name of the class if not specified). `[icon source] `_ +The folder is hardcoded, and the filename should match the name from the plugin declaration (or the name of the class if not specified). +`[icon source] `_ We need to install the image file in the CMake. diff --git a/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/RViz-Custom-Panel.rst b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/RViz-Custom-Panel.rst index 1f03660ea1b..1f44bad8e61 100644 --- a/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/RViz-Custom-Panel.rst +++ b/source/Tutorials/Intermediate/RViz/RViz-Custom-Panel/RViz-Custom-Panel.rst @@ -293,7 +293,8 @@ Update ``demo_panel.cpp`` to have the following contents: Testing with ROS ^^^^^^^^^^^^^^^^ -Compile and launch RViz2 with your panel again. You should see your label and button in the panel now. +Compile and launch RViz2 with your panel again. +You should see your label and button in the panel now. .. image:: images/RViz1.png :target: images/RViz1.png diff --git a/source/Tutorials/Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst b/source/Tutorials/Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst index 2fdbd3ed689..cac256195a7 100644 --- a/source/Tutorials/Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst +++ b/source/Tutorials/Intermediate/RViz/RViz-User-Guide/RViz-User-Guide.rst @@ -108,7 +108,8 @@ Built-in Display Types - Draws cells from a grid, usually obstacles from a costmap from the `navigation `__ stack. - `nav_msgs/msg/GridCells `__ * - Image - - Creates a new rendering window with an Image. Unlike the Camera display, this display does not use a CameraInfo + - Creates a new rendering window with an Image. + Unlike the Camera display, this display does not use a CameraInfo - `sensor_msgs/msg/Image `__ * - InteractiveMarker - Displays 3D objects from one or multiple Interactive Marker servers and allows mouse interaction with them @@ -144,7 +145,8 @@ Built-in Display Types - Accumulates odometry poses from over time. - `nav_msgs/msg/Odometry `__ * - Range - - Displays cones representing range measurements from sonar or IR range sensors. Version: Electric+ + - Displays cones representing range measurements from sonar or IR range sensors. + Version: Electric+ - `sensor_msgs/msg/Range `__ * - RobotModel - Shows a visual representation of a robot in the correct pose (as defined by the current TF transforms). @@ -189,8 +191,10 @@ The focal point is visualized as a small disc while you're moving the camera: Controls: * **Left mouse button**: Click and drag to rotate around the focal point. -* **Middle mouse button**: Click and drag to move the focal point in the plane formed by the camera's up and right vectors. The distance moved depends on the focal point -- if there is an object on the focal point, and you click on top of it, it will stay under your mouse. -* **Right mouse button**: Click and drag to zoom in/out of the focal point. Dragging up zooms in, down zooms out. +* **Middle mouse button**: Click and drag to move the focal point in the plane formed by the camera's up and right vectors. + The distance moved depends on the focal point -- if there is an object on the focal point, and you click on top of it, it will stay under your mouse. +* **Right mouse button**: Click and drag to zoom in/out of the focal point. + Dragging up zooms in, down zooms out. * **Scrollwheel**: Zoom in/out of the focal point FPS (first-person) Camera @@ -199,9 +203,11 @@ The FPS camera is a first-person camera, so it rotates as if you're looking with Controls: -* **Left mouse button**: Click and drag to rotate. Control-click to pick the object under the mouse and look directly at it. +* **Left mouse button**: Click and drag to rotate. + Control-click to pick the object under the mouse and look directly at it. * **Middle mouse button**: Click and drag to move along the plane formed by the camera's up and right vectors. -* **Right mouse button**: Click and drag to move along the camera's forward vector. Dragging up moves forward, down moves backward. +* **Right mouse button**: Click and drag to move along the camera's forward vector. + Dragging up moves forward, down moves backward. * **Scrollwheel**: Move forward/backward. Top-down Orthographic diff --git a/source/Tutorials/Intermediate/Rosdep.rst b/source/Tutorials/Intermediate/Rosdep.rst index c7dda3a3fc7..87414d3411d 100644 --- a/source/Tutorials/Intermediate/Rosdep.rst +++ b/source/Tutorials/Intermediate/Rosdep.rst @@ -105,7 +105,8 @@ How do I know what keys to put in my package.xml? Great question, I'm glad you asked! * If the package you want to depend in your package is ROS-based, AND has been released into the ROS ecosystem [1]_, e.g. ``nav2_bt_navigator``, you may simply use the name of the package. You can find a list of all released ROS packages in https://github.com/ros/rosdistro at ``/distribution.yaml`` (e.g. ``humble/distribution.yaml``) for your given ROS distribution. -* If you want to depend on a non-ROS package, something often called "system dependencies", you will need to find the keys for a particular library. In general, there are two files of interest: +* If you want to depend on a non-ROS package, something often called "system dependencies", you will need to find the keys for a particular library. + In general, there are two files of interest: * `rosdep/base.yaml `_ contains the ``apt`` system dependencies * `rosdep/python.yaml `_ contains the Python dependencies diff --git a/source/Tutorials/Intermediate/Testing/Python.rst b/source/Tutorials/Intermediate/Testing/Python.rst index 4350f597ece..4a729ca4304 100644 --- a/source/Tutorials/Intermediate/Testing/Python.rst +++ b/source/Tutorials/Intermediate/Testing/Python.rst @@ -48,7 +48,8 @@ Example package layout: Test Contents ------------- -You can now write tests to your heart's content. There are `plenty of resources on pytest `__, but in short, you can write functions with the ``test_`` prefix and include whatever assert statements you'd like. +You can now write tests to your heart's content. +There are `plenty of resources on pytest `__, but in short, you can write functions with the ``test_`` prefix and include whatever assert statements you'd like. .. code-block:: python diff --git a/source/Tutorials/Intermediate/Testing/Testing-Main.rst b/source/Tutorials/Intermediate/Testing/Testing-Main.rst index 2f905a7f749..4a1720cf922 100644 --- a/source/Tutorials/Intermediate/Testing/Testing-Main.rst +++ b/source/Tutorials/Intermediate/Testing/Testing-Main.rst @@ -8,14 +8,43 @@ Why automatic tests? Here are some of the many good reasons why should we have automated tests: -* You can make incremental updates to your code more quickly. ROS has hundreds of packages with many interdependencies, so it can be hard to anticipate the problems a small change might cause. If your change passes the unit tests, you can be more confident that you haven't introduced problems — or at least the problems aren't your fault. -* You can refactor your code with greater confidence. Passing the unit tests verifies that you haven't introduced any bugs while refactoring. This gives you this wonderful freedom from change fear! -* It leads to better designed code. Unit tests force you to write your code so that it can be more easily tested. This often means keeping your underlying functions and framework separate, which is one of our design goals with ROS code. -* They prevent recurring bugs (bug regressions). It's a good practice to write a unit test for every bug you fix. In fact, write the unit test before you fix the bug. This will help you to precisely, or even deterministically, reproduce the bug, and much more precisely understand what the problem is. As a result, you will also create a better patch, which you can then test with your regression test to verify that the bug is fixed. That way the bug won't accidentally get reintroduced if the code gets modified later on. It also means that it will be easier to convince the reviewer of the patch that the problem is solved, and the contribution is of high quality. -* Other people can work on your code more easily (an automatic form of documentation). It can be hard to figure out whether or not you've broken someone else's code when you make a change. The unit tests are a tool for other developers to validate their changes. Automatic tests document your coding decisions, and communicate to other developers automatically about their violation. Thus tests become documentation for your code — a documentation that does not need to be read for the most time, and when it does need to be inspected the test system will precisely indicate what to read (which tests fail). By writing automatic tests you make other contributors faster. This improves the entire ROS project. -* It is much easier to become a contributor to ROS if we have automated unit tests. It is very difficult for new external developers to contribute to your components. When they make changes to code, they are often doing it in the blind, driven by a lot of guesswork. By providing a harness of automated tests, you help them in the task. They get immediate feedback for their changes. It becomes easier to contribute to a project, and new contributors to join more easily. Also their first contributions are of higher quality, which decreases the workload on maintainers. A win-win! -* Automatic tests simplify maintainership. Especially for mature packages, which change more slowly, and mostly need to be updated to new dependencies, an automatic test suite helps to very quickly establish whether the package still works. This makes it much easier to decide whether the package is still supported or not. -* Automatic tests amplify the value of Continuous Integration. Regression tests, along with normal scenario-based requirements tests, contribute to overall body of automated tests for your component. Your component is better tested against evolution of other APIs that it depends on (CI servers will tell you better and more precisely what problems develop in your code). +* You can make incremental updates to your code more quickly. + ROS has hundreds of packages with many interdependencies, so it can be hard to anticipate the problems a small change might cause. + If your change passes the unit tests, you can be more confident that you haven't introduced problems — or at least the problems aren't your fault. +* You can refactor your code with greater confidence. + Passing the unit tests verifies that you haven't introduced any bugs while refactoring. + This gives you this wonderful freedom from change fear! +* It leads to better designed code. + Unit tests force you to write your code so that it can be more easily tested. + This often means keeping your underlying functions and framework separate, which is one of our design goals with ROS code. +* They prevent recurring bugs (bug regressions). + It's a good practice to write a unit test for every bug you fix. + In fact, write the unit test before you fix the bug. + This will help you to precisely, or even deterministically, reproduce the bug, and much more precisely understand what the problem is. + As a result, you will also create a better patch, which you can then test with your regression test to verify that the bug is fixed. + That way the bug won't accidentally get reintroduced if the code gets modified later on. + It also means that it will be easier to convince the reviewer of the patch that the problem is solved, and the contribution is of high quality. +* Other people can work on your code more easily (an automatic form of documentation). + It can be hard to figure out whether or not you've broken someone else's code when you make a change. + The unit tests are a tool for other developers to validate their changes. + Automatic tests document your coding decisions, and communicate to other developers automatically about their violation. + Thus tests become documentation for your code — a documentation that does not need to be read for the most time, and when it does need to be inspected the test system will precisely indicate what to read (which tests fail). + By writing automatic tests you make other contributors faster. + This improves the entire ROS project. +* It is much easier to become a contributor to ROS if we have automated unit tests. + It is very difficult for new external developers to contribute to your components. + When they make changes to code, they are often doing it in the blind, driven by a lot of guesswork. + By providing a harness of automated tests, you help them in the task. + They get immediate feedback for their changes. + It becomes easier to contribute to a project, and new contributors to join more easily. + Also their first contributions are of higher quality, which decreases the workload on maintainers. + A win-win! +* Automatic tests simplify maintainership. + Especially for mature packages, which change more slowly, and mostly need to be updated to new dependencies, an automatic test suite helps to very quickly establish whether the package still works. + This makes it much easier to decide whether the package is still supported or not. +* Automatic tests amplify the value of Continuous Integration. + Regression tests, along with normal scenario-based requirements tests, contribute to overall body of automated tests for your component. + Your component is better tested against evolution of other APIs that it depends on (CI servers will tell you better and more precisely what problems develop in your code). Perhaps the most important benefit of writing tests is that tests make you a good citizen. Tests influence quality in the long term. @@ -28,8 +57,13 @@ Is this all coming for free? Of course, there is never free lunch. To get the benefits of testing, some investment is necessary. -* You need to develop a test, which sometimes may be difficult or costly. Sometimes it might also be nontrivial, as the test should be automatic. Things get particularly hairy if your tests should involve special hardware (they should not: try to use simulation, mock the hardware, or narrow down the test to a smaller software problem) or require external environment, for instance human operators. -* Regression tests and other automatic tests need to be maintained. When the design of the component changes, a lot of tests become invalidated (for instance they no longer compile, or throw runtime exceptions related to the API design). These tests fail not only because the redesign re-introduced bugs but also because they need to be updated to the new design. Occasionally, with bigger redesigns, old regression tests should be dropped. +* You need to develop a test, which sometimes may be difficult or costly. + Sometimes it might also be nontrivial, as the test should be automatic. + Things get particularly hairy if your tests should involve special hardware (they should not: try to use simulation, mock the hardware, or narrow down the test to a smaller software problem) or require external environment, for instance human operators. +* Regression tests and other automatic tests need to be maintained. + When the design of the component changes, a lot of tests become invalidated (for instance they no longer compile, or throw runtime exceptions related to the API design). + These tests fail not only because the redesign re-introduced bugs but also because they need to be updated to the new design. + Occasionally, with bigger redesigns, old regression tests should be dropped. * Large bodies of tests can take a long time to run, which can increase Continuous Integration server costs. Available Tutorials: diff --git a/source/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.rst b/source/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.rst index cf4907b96e7..d81ca0858b7 100644 --- a/source/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.rst +++ b/source/Tutorials/Intermediate/Tf2/Quaternion-Fundamentals.rst @@ -168,7 +168,8 @@ You want to find the relative rotation, ``q_r``, that converts ``q_1`` to ``q_2` q_2 = q_r * q_1 You can solve for ``q_r`` similarly to solving a matrix equation. -Invert ``q_1`` and right-multiply both sides. Again, the order of multiplication is important: +Invert ``q_1`` and right-multiply both sides. +Again, the order of multiplication is important: .. code-block:: C++ diff --git a/source/Tutorials/Intermediate/Tf2/Time-Travel-With-Tf2-Cpp.rst b/source/Tutorials/Intermediate/Tf2/Time-Travel-With-Tf2-Cpp.rst index 635145b29cb..adee5bc6474 100644 --- a/source/Tutorials/Intermediate/Tf2/Time-Travel-With-Tf2-Cpp.rst +++ b/source/Tutorials/Intermediate/Tf2/Time-Travel-With-Tf2-Cpp.rst @@ -48,7 +48,8 @@ Edit the ``lookupTransform()`` call in ``turtle_tf2_listener.cpp`` file to } catch (const tf2::TransformException & ex) { Now if you run this, during the first 5 seconds, the second turtle would not know where to go because we do not yet have a 5-second history of poses of the carrot. -But what happens after these 5 seconds? Build the package then let's just give it a try: +But what happens after these 5 seconds? +Build the package then let's just give it a try: .. code-block:: console @@ -56,9 +57,11 @@ But what happens after these 5 seconds? Build the package then let's just give i .. image:: images/turtlesim_delay1.png -You should now notice that your turtle is driving around uncontrollably like in this screenshot. Let's try to understand reason behind that behavior. +You should now notice that your turtle is driving around uncontrollably like in this screenshot. +Let's try to understand reason behind that behavior. -#. In our code we asked tf2 the following question: "What was the pose of ``carrot1`` 5 seconds ago, relative to ``turtle2`` 5 seconds ago?". This means we are controlling the second turtle based on where it was 5 seconds ago as well as where the first carrot was 5 seconds ago. +#. In our code we asked tf2 the following question: "What was the pose of ``carrot1`` 5 seconds ago, relative to ``turtle2`` 5 seconds ago?". + This means we are controlling the second turtle based on where it was 5 seconds ago as well as where the first carrot was 5 seconds ago. #. However, what we really want to ask is: "What was the pose of ``carrot1`` 5 seconds ago, relative to the current position of the ``turtle2``?". diff --git a/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Cpp.rst b/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Cpp.rst index e36f88ba29a..3f100774810 100644 --- a/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Cpp.rst +++ b/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Cpp.rst @@ -407,7 +407,8 @@ The following command publishes a static coordinate transform to tf2 using an x/ ros2 run tf2_ros static_transform_publisher --x x --y y --z z --qx qx --qy qy --qz qz --qw qw --frame-id frame_id --child-frame-id child_frame_id -``static_transform_publisher`` is designed both as a command-line tool for manual use, as well as for use within ``launch`` files for setting static transforms. For example: +``static_transform_publisher`` is designed both as a command-line tool for manual use, as well as for use within ``launch`` files for setting static transforms. +For example: .. code-block:: console diff --git a/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Py.rst b/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Py.rst index 442206d7a80..2b638d5925b 100644 --- a/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Py.rst +++ b/source/Tutorials/Intermediate/Tf2/Writing-A-Tf2-Static-Broadcaster-Py.rst @@ -426,7 +426,8 @@ The following command publishes a static coordinate transform to tf2 using an x/ ros2 run tf2_ros static_transform_publisher --x x --y y --z z --qx qx --qy qy --qz qz --qw qw --frame-id frame_id --child-frame-id child_frame_id -``static_transform_publisher`` is designed both as a command-line tool for manual use, as well as for use within ``launch`` files for setting static transforms. For example: +``static_transform_publisher`` is designed both as a command-line tool for manual use, as well as for use within ``launch`` files for setting static transforms. +For example: .. code-block:: python diff --git a/source/Tutorials/Intermediate/URDF/Adding-Physical-and-Collision-Properties-to-a-URDF-Model.rst b/source/Tutorials/Intermediate/URDF/Adding-Physical-and-Collision-Properties-to-a-URDF-Model.rst index 59d54df2e34..0064c8e7944 100644 --- a/source/Tutorials/Intermediate/URDF/Adding-Physical-and-Collision-Properties-to-a-URDF-Model.rst +++ b/source/Tutorials/Intermediate/URDF/Adding-Physical-and-Collision-Properties-to-a-URDF-Model.rst @@ -61,8 +61,7 @@ However, there are two main cases where you wouldn’t: Physical Properties ------------------- -In order to get your model to simulate properly, you need to define several physical properties of your robot, i.e. -the properties that a physics engine like Gazebo would need. +In order to get your model to simulate properly, you need to define several physical properties of your robot, i.e. the properties that a physics engine like Gazebo would need. Inertia ^^^^^^^ @@ -109,7 +108,8 @@ Here is a simple one. * The inertia tensor depends on both the mass and the distribution of mass of the object. A good first approximation is to assume equal distribution of mass in the volume of the object and compute the inertia tensor based on the object's shape, as outlined above. * If unsure what to put, a matrix with ixx/iyy/izz=1e-3 or smaller is often a reasonable default for a mid-sized link (it corresponds to a box of 0.1 m side length with a mass of 0.6 kg). - The identity matrix is a particularly bad choice, since it is often much too high (it corresponds to a box of 0.1 m side length with a mass of 600 kg!). + The identity matrix is a particularly bad choice, since it is often much too high. + (it corresponds to a box of 0.1 m side length with a mass of 600 kg!) * You can also specify an origin tag to specify the center of gravity and the inertial reference frame (relative to the link's reference frame). * When using realtime controllers, inertia elements of zero (or almost zero) can cause the robot model to collapse without warning, and all links will appear with their origins coinciding with the world origin. diff --git a/source/Tutorials/Intermediate/URDF/Building-a-Movable-Robot-Model-with-URDF.rst b/source/Tutorials/Intermediate/URDF/Building-a-Movable-Robot-Model-with-URDF.rst index dd34707f77b..d44b9688b5f 100644 --- a/source/Tutorials/Intermediate/URDF/Building-a-Movable-Robot-Model-with-URDF.rst +++ b/source/Tutorials/Intermediate/URDF/Building-a-Movable-Robot-Model-with-URDF.rst @@ -109,7 +109,8 @@ Specifying the Pose ------------------- As you move the sliders around in the GUI, the model moves in Rviz. -How is this done? First the `GUI `_ parses the URDF and finds all the non-fixed joints and their limits. +How is this done? +First the `GUI `_ parses the URDF and finds all the non-fixed joints and their limits. Then, it uses the values of the sliders to publish `sensor_msgs/msg/JointState `_ messages. Those are then used by `robot_state_publisher `_ to calculate all of transforms between the different parts. The resulting transform tree is then used to display all of the shapes in Rviz. diff --git a/source/Tutorials/Intermediate/URDF/Building-a-Visual-Robot-Model-with-URDF-from-Scratch.rst b/source/Tutorials/Intermediate/URDF/Building-a-Visual-Robot-Model-with-URDF-from-Scratch.rst index d28a955fd24..73ab6718e87 100644 --- a/source/Tutorials/Intermediate/URDF/Building-a-Visual-Robot-Model-with-URDF-from-Scratch.rst +++ b/source/Tutorials/Intermediate/URDF/Building-a-Visual-Robot-Model-with-URDF-from-Scratch.rst @@ -186,7 +186,8 @@ We also rotate the leg so it is upright. * The launch file runs packages that will create TF frames for each link in your model based on your URDF. Rviz uses this information to figure out where to display each shape. -* If a TF frame does not exist for a given URDF link, then it will be placed at the origin in white (ref. `related question `_). +* If a TF frame does not exist for a given URDF link, then it will be placed at the origin in white + (ref. `related question `_). Material Girl ------------- diff --git a/source/Tutorials/Intermediate/URDF/Exporting-an-URDF-File.rst b/source/Tutorials/Intermediate/URDF/Exporting-an-URDF-File.rst index cc50c2d9fcf..b4c9743c848 100644 --- a/source/Tutorials/Intermediate/URDF/Exporting-an-URDF-File.rst +++ b/source/Tutorials/Intermediate/URDF/Exporting-an-URDF-File.rst @@ -15,7 +15,8 @@ Most roboticists work in teams, and often those teams include a mechanical engin Instead of crafting an URDF by hand it is possible to export an URDF model from many different CAD and modeling programs. These export tools are often developed by individuals that are familiar with the particular CAD program they use. Below you will find a list of available URDF exporters for a variety of CAD and 3D modeling software systems. -*The ROS core maintainers do not maintain these packages. As such we make no claims about their performance or ease of use.* +*The ROS core maintainers do not maintain these packages. +As such we make no claims about their performance or ease of use.* However, we figured it would be helpful to produce a list of available URDF exporters. **CAD Exporters** diff --git a/source/Tutorials/Intermediate/URDF/Using-URDF-with-Robot-State-Publisher.rst b/source/Tutorials/Intermediate/URDF/Using-URDF-with-Robot-State-Publisher.rst index a7c9ba07d01..3459f13caf8 100644 --- a/source/Tutorials/Intermediate/URDF/Using-URDF-with-Robot-State-Publisher.rst +++ b/source/Tutorials/Intermediate/URDF/Using-URDF-with-Robot-State-Publisher.rst @@ -282,6 +282,7 @@ Save the ``setup.py`` file with your changes. 6 Install the package ^^^^^^^^^^^^^^^^^^^^^ + .. code-block:: console cd second_ros2_ws diff --git a/source/Tutorials/Intermediate/URDF/Using-Xacro-to-Clean-Up-a-URDF-File.rst b/source/Tutorials/Intermediate/URDF/Using-Xacro-to-Clean-Up-a-URDF-File.rst index c27c6f3cad5..2f5014ada1c 100644 --- a/source/Tutorials/Intermediate/URDF/Using-Xacro-to-Clean-Up-a-URDF-File.rst +++ b/source/Tutorials/Intermediate/URDF/Using-Xacro-to-Clean-Up-a-URDF-File.rst @@ -179,7 +179,8 @@ Let’s take a look at a simple useless macro. -(This is useless, since if the origin is not specified, it has the same value as this.) This code will generate the following. +(This is useless, since if the origin is not specified, it has the same value as this.) +This code will generate the following. .. code-block:: xml diff --git a/source/Tutorials/Intermediate/Writing-an-Action-Server-Client/Cpp.rst b/source/Tutorials/Intermediate/Writing-an-Action-Server-Client/Cpp.rst index 81d690570b5..5dd898e2d48 100644 --- a/source/Tutorials/Intermediate/Writing-an-Action-Server-Client/Cpp.rst +++ b/source/Tutorials/Intermediate/Writing-an-Action-Server-Client/Cpp.rst @@ -232,7 +232,8 @@ Open up ``custom_action_cpp/CMakeLists.txt``, and add the following right after LIBRARY DESTINATION lib RUNTIME DESTINATION bin) -And now we can compile the package. Go to the top-level of the ``ros2_ws``, and run: +And now we can compile the package. +Go to the top-level of the ``ros2_ws``, and run: .. code-block:: bash @@ -360,7 +361,8 @@ Open up ``custom_action_cpp/CMakeLists.txt``, and add the following right after LIBRARY DESTINATION lib RUNTIME DESTINATION bin) -And now we can compile the package. Go to the top-level of the ``ros2_ws``, and run: +And now we can compile the package. +Go to the top-level of the ``ros2_ws``, and run: .. code-block:: bash diff --git a/source/Tutorials/Intermediate/Writing-an-Action-Server-Client/Py.rst b/source/Tutorials/Intermediate/Writing-an-Action-Server-Client/Py.rst index b0830190a27..e24fd92a6fe 100644 --- a/source/Tutorials/Intermediate/Writing-an-Action-Server-Client/Py.rst +++ b/source/Tutorials/Intermediate/Writing-an-Action-Server-Client/Py.rst @@ -346,7 +346,8 @@ This is achieved by additionally passing the callback to the action client when :language: python :lines: 21 -We're all set. If we run our action client, you should see feedback being printed to the screen. +We're all set. +If we run our action client, you should see feedback being printed to the screen. Summary ------- diff --git a/source/Tutorials/Miscellaneous/Building-ROS2-Package-with-eclipse-2021-06.rst b/source/Tutorials/Miscellaneous/Building-ROS2-Package-with-eclipse-2021-06.rst index 7f5f559759a..b4bc0ad500d 100644 --- a/source/Tutorials/Miscellaneous/Building-ROS2-Package-with-eclipse-2021-06.rst +++ b/source/Tutorials/Miscellaneous/Building-ROS2-Package-with-eclipse-2021-06.rst @@ -38,7 +38,8 @@ We see that we got C++ includes. :alt: eclipse_c++_project_includes -We now import our ROS 2 project. The code is still in the old place. +We now import our ROS 2 project. +The code is still in the old place. .. image:: images/eclipse_import_project.png :target: images/eclipse_import_project.png diff --git a/source/Tutorials/Miscellaneous/Building-Realtime-rt_preempt-kernel-for-ROS-2.rst b/source/Tutorials/Miscellaneous/Building-Realtime-rt_preempt-kernel-for-ROS-2.rst index 71120de07a8..ff9ea4a0314 100644 --- a/source/Tutorials/Miscellaneous/Building-Realtime-rt_preempt-kernel-for-ROS-2.rst +++ b/source/Tutorials/Miscellaneous/Building-Realtime-rt_preempt-kernel-for-ROS-2.rst @@ -6,7 +6,9 @@ Building a real-time Linux kernel [community-contributed] ========================================================= -This tutorial begins with a clean Ubuntu 20.04.1 install on Intel x86_64. Actual kernel is 5.4.0-54-generic, but we will install the Latest Stable RT_PREEMPT Version. To build the kernel you need at least 30GB free disk space. +This tutorial begins with a clean Ubuntu 20.04.1 install on Intel x86_64. +Actual kernel is 5.4.0-54-generic, but we will install the Latest Stable RT_PREEMPT Version. +To build the kernel you need at least 30GB free disk space. Check https://wiki.linuxfoundation.org/realtime/start for the latest stable version, at the time of writing this is "Latest Stable Version 5.4-rt". If we click on the `link `_, we get the exact version. @@ -68,7 +70,8 @@ We simply want to use the config of our Ubuntu installation, so we get the Ubunt cp /boot/config-5.4.0-54-generic .config -Open Software & Updates. in the Ubuntu Software menu tick the 'Source code' box +Open Software & Updates. +in the Ubuntu Software menu tick the 'Source code' box We need some tools to build kernel, install them with @@ -83,7 +86,8 @@ To enable all Ubuntu configurations, we simply use yes '' | make oldconfig -Then we need to enable rt_preempt in the kernel. We call +Then we need to enable rt_preempt in the kernel. +We call .. code-block:: bash @@ -121,7 +125,8 @@ and set the following -> Default CPUFreq governor ( [=y]) (X) performance -Save and exit menuconfig. Now we're going to build the kernel which will take quite some time. (10-30min on a modern cpu) +Save and exit menuconfig. +Now we're going to build the kernel which will take quite some time. (10-30min on a modern cpu) .. code-block:: bash @@ -141,7 +146,8 @@ Then we install all kernel deb packages sudo dpkg -i ../*.deb -Now the real time kernel should be installed. Reboot the system and check the new kernel version +Now the real time kernel should be installed. +Reboot the system and check the new kernel version .. code-block:: bash diff --git a/source/Tutorials/Miscellaneous/Deploying-ROS-2-on-IBM-Cloud.rst b/source/Tutorials/Miscellaneous/Deploying-ROS-2-on-IBM-Cloud.rst index 47010283873..c758978f086 100644 --- a/source/Tutorials/Miscellaneous/Deploying-ROS-2-on-IBM-Cloud.rst +++ b/source/Tutorials/Miscellaneous/Deploying-ROS-2-on-IBM-Cloud.rst @@ -14,7 +14,8 @@ Deploying on IBM Cloud Kubernetes [community-contributed] About ----- -This article describes how to get ROS 2 running on IBM Cloud using Docker files. It first gives a brief overview of docker images and how they work locally and then explores IBM Cloud and how the user can deploy their containers on it. +This article describes how to get ROS 2 running on IBM Cloud using Docker files. +It first gives a brief overview of docker images and how they work locally and then explores IBM Cloud and how the user can deploy their containers on it. Afterwards, a short description of how the user can use their own custom packages for ROS 2 from github on IBM Cloud is provided. A walkthrough of how to create a cluster and utilize Kubernetes on IBM Cloud is provided and finally the Docker image is deployed on the cluster. Originally published `here `__ and `here `__. @@ -25,11 +26,10 @@ ROS 2 on IBM Cloud In this tutorial, we show how you can easily integrate and run ROS 2 on IBM Cloud with your custom packages. -ROS 2 is the new generation of ROS which gives more control over -multi-robot formations. With the advancements of cloud computing, cloud -robotics are becoming more important in today's age. In this tutorial, -we will go through a short introduction on running ROS 2 on IBM Cloud. By -the end of the tutorial, you will be able to create your own packages in +ROS 2 is the new generation of ROS which gives more control over multi-robot formations. +With the advancements of cloud computing, cloud robotics are becoming more important in today's age. +In this tutorial, we will go through a short introduction on running ROS 2 on IBM Cloud. +By the end of the tutorial, you will be able to create your own packages in ROS 2 and deploy them to the cloud using docker files. The following instructions assume you're using Linux and have been @@ -38,29 +38,26 @@ tested with Ubuntu 18.04 (Bionic Beaver). Step 1: Setting up your system ------------------------------- -Before we go into how the exact process works, lets first make sure all -the required software is properly installed. We'll point you towards the -appropriate sources to set up your system and only highlight the details -that pertain to our use-case. +Before we go into how the exact process works, lets first make sure all the required software is properly installed. +We'll point you towards the appropriate sources to set up your system and only highlight the details that pertain to our use-case. a) Docker files? ^^^^^^^^^^^^^^^^ Docker files are a form of containers that can run separate from your system, this way, you can set-up potentially hundreds of different -projects without affecting one another. You can even set-up different -versions of Linux on one machine, without the need for virtual machine. -Docker files have an advantage of saving space and only utilizing your -system resources when running. In addition, dockers are versatile and -transferable. They contain all the required pre-requisites to run +projects without affecting one another. +You can even set-up different versions of Linux on one machine, without the need for virtual machine. +Docker files have an advantage of saving space and only utilizing your system resources when running. +In addition, dockers are versatile and transferable. +They contain all the required pre-requisites to run separately, meaning that you can easily use a docker file for a specific system or service without any cubersome steps! -Excited yet? Let's start off by installing docker to your system by -following the following `link `__. -From the tutorial, you should have done some sanity checks to make sure -docker is properly set-up. Just in case, however, let's run the -following command once again that uses the hello-world docker image: +Excited yet? +Let's start off by installing docker to your system by following the following `link `__. +From the tutorial, you should have done some sanity checks to make sure docker is properly set-up. +Just in case, however, let's run the following command once again that uses the hello-world docker image: .. code-block:: bash @@ -96,16 +93,17 @@ b) ROS 2 Image ROS `announced `__ -image containers for several ROS distributions in January 2019. More -detailed instructions on the use of ROS 2 docker images can be found +image containers for several ROS distributions in January 2019. +More detailed instructions on the use of ROS 2 docker images can be found `here `__. Let's skip through that and get to real-deal right away; creating a -local ROS 2 docker. We'll create our own Dockerfile (instead of using a +local ROS 2 docker. +We'll create our own Dockerfile (instead of using a ready Image) since we'll need this method for deployment on IBM Cloud. First, we create a new directory which will hold our Dockerfile and any -other files we need later on and navigate to it. Using your favorite -$EDITOR of choice, open a new file named *Dockerfile* (make sure the +other files we need later on and navigate to it. +Using your favorite $EDITOR of choice, open a new file named *Dockerfile* (make sure the file naming is correct): .. code-block:: bash @@ -141,15 +139,14 @@ Insert the following in the *Dockerfile*, and save it (also found be for it Of course, you are free to change the ROS distribution (*foxy* is used -here) or change the directory name. The above docker file sets up -ROS-foxy and installs the demo nodes for C++ and Python. Then it -launches a file which runs a talker and a listener node. We will see it -in action in just a few, but they act very similar to the +here) or change the directory name. +The above docker file sets up ROS-foxy and installs the demo nodes for C++ and Python. +Then it launches a file which runs a talker and a listener node. +We will see it in action in just a few, but they act very similar to the publisher-subscriber example found in the `ROS wiki `__ -Now, we are ready to build the docker image to run ROS 2 in it (yes, it -is THAT easy!). +Now, we are ready to build the docker image to run ROS 2 in it (yes, it is THAT easy!). **Note**: if you have errors due to insufficient privileges or *permission denied*, try running the command with *sudo* privileges: @@ -162,7 +159,8 @@ is THAT easy!). Successfully built 0dc6ce7cb487 *0dc6ce7cb487* will most probably be different for you, so keep note of -it and copy it somewhere for reference. You can always go back and check +it and copy it somewhere for reference. +You can always go back and check the docker images you have on your system using: .. code-block:: bash @@ -191,15 +189,16 @@ Now, run the docker file using: [talker-1] [INFO] [1603852912.249556670] [talker]: Publishing: 'Hello World: 6' [listener-2] [INFO] [1603852912.250212678] [listener]: I heard: [Hello World: 6] -If it works correctly, you should see something similar to what is shown -above. As can be seen, there are two ROS nodes (a publisher and a +If it works correctly, you should see something similar to what is shown above. +As can be seen, there are two ROS nodes (a publisher and a subscriber) running and their output is provided to us through ROS INFO. Step 2: Running the image on IBM Cloud -------------------------------------- The following steps assume you have an IBM cloud account and have -ibmcloud CLI installed. If not, please check this +ibmcloud CLI installed. +If not, please check this `link `__ out to get that done first. @@ -216,20 +215,18 @@ Afterwards, login to your ibmcloud account through the terminal: $ ibmcloud login --sso -From here, let's create a container registry name-space. Make sure you -use a unique name that is also descriptive as to what it is. Here, I -used *ros2nasr*. +From here, let's create a container registry name-space. +Make sure you use a unique name that is also descriptive as to what it is. +Here, I used *ros2nasr*. .. code-block:: bash $ ibmcloud cr namespace-add ros2nasr -IBM cloud has a lot of shortcuts that would help us get our container -onto the cloud right away. The command below builds the container and -tags it with the name **ros2foxy** and the version of **1**. Make sure -you use the correct registry name you created and you are free to change -the container name as you wish. The **.** at the end indicates that the -*Dockerfile* is in the current directory (and it is important), if not, +IBM cloud has a lot of shortcuts that would help us get our container onto the cloud right away. +The command below builds the container and tags it with the name **ros2foxy** and the version of **1**. +Make sure you use the correct registry name you created and you are free to change the container name as you wish. +The **.** at the end indicates that the *Dockerfile* is in the current directory (and it is important), if not, change it to point to the directory containing the Dockerfile. .. code-block:: bash @@ -249,10 +246,9 @@ you created by running the following command OK -Next, it is important to log-in to your registry to run the docker -image. Again, if you face a *permission denied* error, perform the -command with sudo privileges. Afterwards, run your docker file as shown -below. +Next, it is important to log-in to your registry to run the docker image. +Again, if you face a *permission denied* error, perform the command with sudo privileges. +Afterwards, run your docker file as shown below. .. code-block:: bash @@ -276,14 +272,12 @@ to that you saw when you ran it locally on your machine. Step 3: Using Custom ROS 2 Packages ----------------------------------- -So now we have the full pipeline working, from creating the Dockerfile, -all the way to deploying it and seeing it work on IBM Cloud. But, what -if we want to use a custom set of packages we (or someone else) created? +So now we have the full pipeline working, from creating the Dockerfile, all the way to deploying it and seeing it work on IBM Cloud. +But, what if we want to use a custom set of packages we (or someone else) created? -Well that all has to do with how you set-up your Dockerfile. Let's use -the example provided by ROS 2 `here `__. -Create a new directory with a new Dockerfile (or overwrite the existing -one) and add the following in it (or download the file +Well that all has to do with how you set-up your Dockerfile. +Let's use the example provided by ROS 2 `here `__. +Create a new directory with a new Dockerfile (or overwrite the existing one) and add the following in it (or download the file `here `__) .. code-block:: bash @@ -408,12 +402,10 @@ and then run them. **Back to IBM Cloud** -With this Dockerfile, we can follow the same steps we did before to -deploy it on IBM Cloud. Since we already have our registry created, and -we're logged in to IBM Cloud, we directly build our new Dockerfile. -Notice how I kept the tag the same but changed the version, this way I -can update the docker image created previously. (You are free to create -a completely new one if you want) +With this Dockerfile, we can follow the same steps we did before to deploy it on IBM Cloud. +Since we already have our registry created, and we're logged in to IBM Cloud, we directly build our new Dockerfile. +Notice how I kept the tag the same but changed the version, this way I can update the docker image created previously. +(You are free to create a completely new one if you want) .. code-block:: bash @@ -434,9 +426,8 @@ image: $ docker run -v -it registry.ng.bluemix.net/ros2nasr/ros2foxy:2 -You should see, again, the same output. However, this time we did it -through custom packages from github, which allows us to utilize our -personally created packages for ROS 2 on IBM Cloud. +You should see, again, the same output. +However, this time we did it through custom packages from github, which allows us to utilize our personally created packages for ROS 2 on IBM Cloud. Extra: Deleting Docker Images ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -465,11 +456,11 @@ Step 4: Kubernetes a) Creating the Cluster ^^^^^^^^^^^^^^^^^^^^^^^ -Create a cluster using the Console. The instructions are found -`here `__. -The settings used are detailed below. These are merely suggestions and -can be changed if you need to. However, make sure you understand the -implications of your choices: +Create a cluster using the Console. +The instructions are found `here `__. +The settings used are detailed below. +These are merely suggestions and can be changed if you need to. +However, make sure you understand the implications of your choices: 1. Plan: *Standard* @@ -483,9 +474,8 @@ implications of your choices: - Geography: *North America* (you are free to change this) -- Availability: *Single zone* (you are free to change this but make - sure you understand the impact of your choices by checking the IBM - Cloud documentation.) +- Availability: *Single zone* + (you are free to change this but make sure you understand the impact of your choices by checking the IBM Cloud documentation.) - Worker Zone: *Toronto 01* (choose the location that is physically closest to you) @@ -506,13 +496,11 @@ implications of your choices: - Tags: *version:1* -After you create your cluster, you will be redirected to a page which -details how you can set up the CLI tools and access your cluster. Please -follow these instructions (or check the instructions -`here `__)and -wait for the progress bar to show that the worker nodes you created are -ready by indicating *Normal* next to the cluster name. You can also -reach this screen from the IBM Cloud Console inside the Kubernetes. +After you create your cluster, you will be redirected to a page which details how you can set up the CLI tools and access your cluster. +Please follow these instructions (or check the instructions `here `__) +and wait for the progress bar to show that the worker nodes you created are +ready by indicating *Normal* next to the cluster name. +You can also reach this screen from the IBM Cloud Console inside the Kubernetes. b) Deploying your Docker Image *Finally!* ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -588,8 +576,9 @@ parameters of your cluster as well as its CPU and Memory Usage. 4. On the top right corner, click on *Exec into pod* -Now you are inside your docker image! You can source your workspace (if -needed) and run ROS 2! For example: +Now you are inside your docker image! +You can source your workspace (if needed) and run ROS 2! +For example: .. code-block:: bash @@ -599,4 +588,8 @@ needed) and run ROS 2! For example: Final Remarks --------------- -At this point, you are capable of creating your own docker image using ROS 2 packages on github. It is also possible, with little changes to utilize local ROS 2 packages as well. This could be the topic of another article. However, you are encouraged to check out the following `Dockerfile `__ which uses a local copy of the demos repository. Similarly, you can use your own local package. +At this point, you are capable of creating your own docker image using ROS 2 packages on github. +It is also possible, with little changes to utilize local ROS 2 packages as well. +This could be the topic of another article. +However, you are encouraged to check out the following `Dockerfile `__ which uses a local copy of the demos repository. +Similarly, you can use your own local package. diff --git a/source/index.rst b/source/index.rst index a686ef528cc..0d38cb776f7 100644 --- a/source/index.rst +++ b/source/index.rst @@ -29,7 +29,8 @@ From drivers and state-of-the-art algorithms to powerful developer tools, ROS ha Since ROS was started in 2007, a lot has changed in the robotics and ROS community. The goal of the ROS 2 project is to adapt to these changes, leveraging what is great about ROS 1 and improving what isn’t. -**Are you looking for documentation for a particular ROS package like MoveIt, image_proc, or octomap?** Please see `ROS Index `__ or check out `this index of per-package documentation `__. +**Are you looking for documentation for a particular ROS package like MoveIt, image_proc, or octomap?** +Please see `ROS Index `__ or check out `this index of per-package documentation `__. This site contains the documentation for ROS 2. If you are looking for ROS 1 documentation, check out the `ROS wiki `__. From 489bb78fd6b303ff9754e719f92d97b969cfa388 Mon Sep 17 00:00:00 2001 From: Tomoya Fujita Date: Thu, 13 Feb 2025 22:14:00 -0800 Subject: [PATCH 29/29] fix group tag indent for ROSCon 2023 and 2024 contents. (#5016) Signed-off-by: Tomoya Fujita --- source/The-ROS2-Project/ROSCon-Content.rst | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/source/The-ROS2-Project/ROSCon-Content.rst b/source/The-ROS2-Project/ROSCon-Content.rst index 79fc05a65c4..d7dc328e1c8 100644 --- a/source/The-ROS2-Project/ROSCon-Content.rst +++ b/source/The-ROS2-Project/ROSCon-Content.rst @@ -11,7 +11,7 @@ The following `ROSCon `__ talks have been given on ROS 2 .. tabs:: - .. group-tab:: 2024 + .. group-tab:: 2024 .. list-table:: :header-rows: 1 @@ -131,7 +131,7 @@ The following `ROSCon `__ talks have been given on ROS 2 * - Navigation à la carte: choose navigation profile and strategy as you go - `video `__ - .. group-tab:: 2023 + .. group-tab:: 2023 .. list-table:: :header-rows: 1